diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000000000000000000000000000000000000..0471fce47ba86e07e10d77d1a2300d6e77612abf --- /dev/null +++ b/.gitignore @@ -0,0 +1 @@ +clik/build diff --git a/README.md b/README.md index 697b748629ed9c375bc40a7b4c99090bb76b0f70..5da62e2034c0aea62812d62fa626ebdcb27ead89 100644 --- a/README.md +++ b/README.md @@ -54,3 +54,5 @@ Here is a checklist of what to do together with the key remarks. and see whether the code works. the simulator accepts the same commands as the robot. the only TODO is to add the gripper to the simulator somehow, but you can also just skip using it when simulating. + +TODO:: explain hom transf mat diff --git a/dmp/matlab/dmp_from_ogs/README.md b/dmp/matlab/dmp_from_ogs/README.md new file mode 100644 index 0000000000000000000000000000000000000000..f3c4daa5a3f856e16e545a60accafc0274ccd640 --- /dev/null +++ b/dmp/matlab/dmp_from_ogs/README.md @@ -0,0 +1,33 @@ + +# Matlab Code for Dynamic Movement Primitives + +## Overview + +**Authors:** Stefan Schaal, Auke Ijspeert, and Heiko Hoffmann + +**Keywords:** dynamic movement primitives + +This code has been tested under **Matlab2019a**. + +This is research code, expect that it changes often and any fitness for a particular purpose is disclaimed. + +### Publications + +For more details on type-1 fuzzy logic controllers, please refer to: + +* Ijspeert A, Nakanishi J, Schaal S, "Learning attractor landscapes for learning motor primitives," in *Advances in Neural Information Processing Systems 15*, MIT Press, 2003. ([pdf](http://www-clmc.usc.edu/publications/I/ijspeert-NIPS2002.pdf)). + +## Usage + +For learning discrete movement primitives (DMPs) run `dmp_learn.m`. + +For learning rhythmic movement primitives (RMPs) run `rmp_learn.m`. + +## Licence + +The source code is released under [GPLv3](http://www.gnu.org/licenses/) license. + +## Notes + + - This code is written for research purpose and has not been fully optimized. In the future I will add more functionalities and improve efficiency, and also add more comment. + - Please report bugs and request features using the [Issue Tracker](https://github.com/andriyukr/controllers/issues). diff --git a/dmp/matlab/dmp_from_ogs/code/dcp.m b/dmp/matlab/dmp_from_ogs/code/dcp.m new file mode 100644 index 0000000000000000000000000000000000000000..36248f50705eae3313e2c981ce3d8ba5f72efc5e --- /dev/null +++ b/dmp/matlab/dmp_from_ogs/code/dcp.m @@ -0,0 +1,592 @@ +function [varargout] = dcp(action,varargin) +% A discrete movement primitive (DCP) inspired by +% Ijspeert A, Nakanishi J, Schaal S (2003) Learning attractor landscapes for +% learning motor primitives. In: Becker S, Thrun S, Obermayer K (eds) Advances +% in Neural Information Processing Systems 15. MIT Press, Cambridge, MA. +% http://www-clmc.usc.edu/publications/I/ijspeert-NIPS2002.pdf. This +% version adds several new features, including that the primitive is +% formulated as acceleration, and that the canonical system is normalized. +% Additinally, a new scale parameter for the nonlinear function allows a larger +% spectrum of modeling options with the primitives +% +% Copyright July, 2007 by +% Stefan Schaal, Auke Ijspeert, and Heiko Hoffmann +% +% --------------- Different Actions of the program ------------------------ +% +% Initialize a DCP model: +% FORMAT dcp('Init',ID,n_rfs,name,flag) +% ID : desired ID of model +% n_rfs : number of local linear models +% name : a name for the model +% flag : flag=1 use 2nd order canonical system, flag=0 use 1st order +% +% alternatively, the function is called as +% +% FORMAT dcp('Init',ID,d,) +% d : a complete data structure of a dcp model +% +% returns nothing +% ------------------------------------------------------------------------- +% +% Set the goal state: +% FORMAT dcp('Set_Goal',ID,g,flag) +% ID : ID of model +% g : the new goal +% flag : flag=1: update x0 with current state, flag=0: don't update x0 +% +% returns nothing +% ------------------------------------------------------------------------- +% +% Set the scale factor of the movement: +% FORMAT dcp('Set_Scale',ID,s,flag) +% ID : ID of model +% s : the new scale +% +% returns nothing +% ------------------------------------------------------------------------- +% +% Run the dcps: +% FORMAT [y,yd,ydd]=dcp('Run',ID,tau,dt,ct,cc) +% ID : ID of model +% tau : global time constant to scale speed of system +% dt : integration time step +% ct : coupling term for transformation system (optional) +% cc : coupling term for canonical system (optional) +% ct_tau : coupling term for transformation system's time constant (optional) +% cc_tau : coupling term for canonical system's time constant (optional) +% cw : additive coupling term for parameters (optional) +% +% returns y,yd,ydd, i.e., current pos,vel,acc, of the dcp +% ------------------------------------------------------------------------- +% +% Change values of a dcp: +% FORMAT dcp('Change',ID,pname,value) +% ID : ID of model +% pname : parameter name +% value : value to be assigned to parameter +% +% returns nothing +% ------------------------------------------------------------------------- +% +% Run the dcps: +% FORMAT dcp('Run',ID,tau,dt,t,td) +% ID : ID of model +% tau : time constant to scale speed, tau is roughly movement +% time until convergence +% dt : integration time step +% +% returns y,yd,ydd, i.e., current pos,vel,acc, of the dcp +% ------------------------------------------------------------------------- +% +% Run the dcp and update the weights: +% FORMAT dcp('Run_Fit',ID,tau,dt,t,td,tdd) +% ID : ID of model +% tau : time constant to scale speed, tau is roughly movement +% time until convergence +% dt : integration time step +% t : target for y +% td : target for yd +% tdd : target for ydd +% +% returns y,yd,ydd, i.e., current pos,vel,acc, of the dcp +% ------------------------------------------------------------------------- +% +% Fit the dcp to a complete trajectory in batch mode: +% FORMAT dcp('Batch_Fit',ID,tau,dt,T,Td,Tdd) +% ID : ID of model +% tau : time constant to scale speed, tau is roughly movement +% time until convergence the goal +% dt : somple time step in given trajectory +% T : target trajectory for y +% Td : target trajectory for yd (optional, will be generated +% as dT/dt otherwise +% Tdd : target trajectory for ydd (optional, will be generated +% as dTd/dt otherwise +% +% returns y,yd,ydd, i.e., current pos,vel,acc, of the dcp +% ------------------------------------------------------------------------- +% +% Return the data structure of a dcp model +% FORMAT [d] = dcp('Structure',ID) +% ID : desired ID of model +% +% returns the complete data structure of a dcp model, e.g., for saving or +% inspecting it +% ------------------------------------------------------------------------- +% +% Reset the states of a dcp model to zero (or a given state) +% FORMAT [d] = dcp('Reset_State',ID) +% ID : desired ID of model +% y : the state to which the primitive is set (optional) +% +% returns nothing +% ------------------------------------------------------------------------- +% +% Clear the data structure of a LWPR model +% FORMAT dcp('Clear',ID) +% ID : ID of model +% +% returns nothing +% ------------------------------------------------------------------------- +% +% Initializes the dcp with a minimum jerk trajectory +% FORMAT dcp('MinJerk',ID) +% ID : ID of model +% +% returns nothing +% ------------------------------------------------------------------------- + +% the global structure to store all dcps +global dcps; +global min_y; +global max_y; + +% at least two arguments are needed +if nargin < 2, + error('Incorrect call to dcp'); +end + +switch lower(action), +% ......................................................................... + case 'init' + if (nargin == 3) + ID = varargin{1}; + dcps(ID) = varargin{2}; + else + % this initialization is good for 0.5 seconds movement for tau=0.5 + ID = varargin{1}; + n_rfs = varargin{2}; + dcps(ID).name = varargin{3}; + dcps(ID).c_order = 0; + if (nargin == 5) + dcps(ID).c_order = varargin{4}; + end + % the time constants for chosen for critical damping + dcps(ID).alpha_z = 25; + dcps(ID).beta_z = dcps(ID).alpha_z/4; + dcps(ID).alpha_g = dcps(ID).alpha_z/2; + dcps(ID).alpha_x = dcps(ID).alpha_z/3; + dcps(ID).alpha_v = dcps(ID).alpha_z; + dcps(ID).beta_v = dcps(ID).beta_z; + % initialize the state variables + dcps(ID).z = 0; + dcps(ID).y = 0; + dcps(ID).x = 0; + dcps(ID).v = 0; + dcps(ID).zd = 0; + dcps(ID).yd = 0; + dcps(ID).xd = 0; + dcps(ID).vd = 0; + dcps(ID).ydd = 0; + % the current goal state + dcps(ID).g = 0; + dcps(ID).gd = 0; + dcps(ID).G = 0; + % the current start state of the primitive + dcps(ID).y0 = 0; + % the orginal amplitude (max(y)-min(y)) when the primitive was fit + dcps(ID).A = 0; + % the original goal amplitude (G-y0) when the primitive was fit + dcps(ID).dG = 0; + % the scale factor for the nonlinear function + dcps(ID).s = 1; + + t = (0:1/(n_rfs-1):1)'*0.5; + if (dcps(ID).c_order == 1) + % the local models, spaced on a grid in time by applying the + % anaytical solutions x(t) = 1-(1+alpha/2*t)*exp(-alpha/2*t) + dcps(ID).c = (1+dcps(ID).alpha_z/2*t).*exp(-dcps(ID).alpha_z/2*t); + % we also store the phase velocity at the centers which is used by some + % applications: xd(t) = (-alpha/2)*x(t) + alpha/2*exp(-alpha/2*t) + dcps(ID).cd = dcps(ID).c*(-dcps(ID).alpha_z/2) + dcps(ID).alpha_z/2*exp(-dcps(ID).alpha_z/2*t); + else + % the local models, spaced on a grid in time by applying the + % anaytical solutions x(t) = exp(-alpha*t) + dcps(ID).c = exp(-dcps(ID).alpha_x*t); + % we also store the phase velocity at the centers which is used by some + % applications: xd(t) = x(t)*(-dcps(ID).alpha_x); + dcps(ID).cd = dcps(ID).c*(-dcps(ID).alpha_x); + end + + dcps(ID).psi = zeros(n_rfs,1); + dcps(ID).w = zeros(n_rfs,1); + dcps(ID).sx2 = zeros(n_rfs,1); + dcps(ID).sxtd = zeros(n_rfs,1); + dcps(ID).D = (diff(dcps(ID).c)*0.55).^2; + dcps(ID).D = 1./[dcps(ID).D;dcps(ID).D(end)]; + dcps(ID).lambda = 1; + + end + +% ......................................................................... + case 'reset_state' + ID = varargin{1}; + if nargin > 2, + y = varargin{2}; + else + y = 0; + end + % initialize the state variables + dcps(ID).z = 0; + dcps(ID).y = y; + dcps(ID).x = 0; + dcps(ID).v = 0; + dcps(ID).zd = 0; + dcps(ID).yd = 0; + dcps(ID).xd = 0; + dcps(ID).vd = 0; + dcps(ID).ydd = 0; + % the goal state + dcps(ID).G = y; + dcps(ID).g = y; + dcps(ID).gd = 0; + dcps(ID).y0 = y; + dcps(ID).s = 1; + +% ......................................................................... + case 'set_goal' + ID = varargin{1}; + dcps(ID).G = varargin{2}; + if (dcps(ID).c_order == 0) + dcps(ID).g = dcps(ID).G; + end + flag = varargin{3}; + if (flag), + dcps(ID).x = 1; + dcps(ID).y0 = dcps(ID).y; + end + if (dcps(ID).A ~= 0) % check whether dcp has been fit + if (dcps(ID).A/(abs(dcps(ID).dG)+1.e-10) > 2.0) + % amplitude-based scaling needs to be set explicity + else + % dG based scaling cab work automatically + dcps(ID).s = (dcps(ID).G-dcps(ID).y0)/dcps(ID).dG; + end + end + +% ......................................................................... + case 'set_scale' + ID = varargin{1}; + dcps(ID).s = varargin{2}; + +% ......................................................................... + case 'run' + ID = varargin{1}; + tau = 0.5/varargin{2}; % tau is relative to 0.5 seconds nominal movement time + dt = varargin{3}; + + if nargin > 4, + ct = varargin{4}; + else + ct = 0; + end + + if nargin > 5, + cc = varargin{5}; + else + cc = 0; + end + + if nargin > 6, + ct_tau = varargin{6}; + else + ct_tau = 1; + end + + if nargin > 7, + cc_tau = varargin{7}; + else + cc_tau = 1; + end + + if nargin > 8, + cw = varargin{8}; + else + cw = 0; + end + + % the weighted sum of the locally weighted regression models + dcps(ID).psi = exp(-0.5*((dcps(ID).x-dcps(ID).c).^2).*dcps(ID).D); + amp = dcps(ID).s; + if (dcps(ID).c_order == 1) + in = dcps(ID).v; + else + in = dcps(ID).x; + end + f = sum(in*(dcps(ID).w+cw).*dcps(ID).psi)/sum(dcps(ID).psi+1.e-10) * amp; + + if (dcps(ID).c_order == 1), + dcps(ID).vd = (dcps(ID).alpha_v*(dcps(ID).beta_v*(0-dcps(ID).x)-dcps(ID).v)+cc)*tau*cc_tau; + dcps(ID).xd = dcps(ID).v*tau*cc_tau; + else + dcps(ID).vd = 0; + dcps(ID).xd = (dcps(ID).alpha_x*(0-dcps(ID).x)+cc)*tau*cc_tau; + end + + dcps(ID).zd = (dcps(ID).alpha_z*(dcps(ID).beta_z*(dcps(ID).g-dcps(ID).y)-dcps(ID).z)+f+ct)*tau*ct_tau; + dcps(ID).yd = dcps(ID).z*tau*ct_tau; + dcps(ID).ydd= dcps(ID).zd*tau*ct_tau; + + dcps(ID).gd = dcps(ID).alpha_g*(dcps(ID).G-dcps(ID).g); + + dcps(ID).x = dcps(ID).xd*dt+dcps(ID).x; + dcps(ID).v = dcps(ID).vd*dt+dcps(ID).v; + + + dcps(ID).z = dcps(ID).zd*dt+dcps(ID).z; + dcps(ID).y = dcps(ID).yd*dt+dcps(ID).y; + + dcps(ID).g = dcps(ID).gd*dt+dcps(ID).g; + + + varargout(1) = {dcps(ID).y}; + varargout(2) = {dcps(ID).yd}; + varargout(3) = {dcps(ID).ydd}; + varargout(4) = {dcps(ID).psi*in/sum(dcps(ID).psi+1.e-10) * amp}; + +% ......................................................................... + case 'change' + ID = varargin{1}; + command = sprintf('dcps(%d).%s = varargin{3};',ID,varargin{2}); + eval(command); + +% ......................................................................... + case 'run_fit' + ID = varargin{1}; + tau = 0.5/varargin{2}; % tau is relative to 0.5 seconds nominal movement time + dt = varargin{3}; + t = varargin{4}; + td = varargin{5}; + tdd = varargin{6}; + + % check whether this is the first time the primitive is fit, and record the + % amplitude and dG information + if (dcps(ID).A == 0) + dcps(ID).dG = dcps(ID).G - dcps(ID).y0; + if (dcps(ID).x == 1), + min_y = +1.e10; + max_y = -1.e10; + dcps(ID).s = 1; + end + end + + % the regression target + amp = dcps(ID).s; + ft = (tdd/tau^2-dcps(ID).alpha_z*(dcps(ID).beta_z*(dcps(ID).g-t)-td/tau))/amp; + + % the weighted sum of the locally weighted regression models + dcps(ID).psi = exp(-0.5*((dcps(ID).x-dcps(ID).c).^2).*dcps(ID).D); + + % update the regression + if (dcps(ID).c_order == 1), + dcps(ID).sx2 = dcps(ID).sx2*dcps(ID).lambda + dcps(ID).psi*dcps(ID).v^2; + dcps(ID).sxtd = dcps(ID).sxtd*dcps(ID).lambda + dcps(ID).psi*dcps(ID).v*ft; + dcps(ID).w = dcps(ID).sxtd./(dcps(ID).sx2+1.e-10); + else + dcps(ID).sx2 = dcps(ID).sx2*dcps(ID).lambda + dcps(ID).psi*dcps(ID).x^2; + dcps(ID).sxtd = dcps(ID).sxtd*dcps(ID).lambda + dcps(ID).psi*dcps(ID).x*ft; + dcps(ID).w = dcps(ID).sxtd./(dcps(ID).sx2+1.e-10); + end + + % compute nonlinearity + if (dcps(ID).c_order == 1) + in = dcps(ID).v; + else + in = dcps(ID).x; + end + f = sum(in*dcps(ID).w.*dcps(ID).psi)/sum(dcps(ID).psi+1.e-10) * amp; + + % integrate + if (dcps(ID).c_order == 1), + dcps(ID).vd = (dcps(ID).alpha_v*(dcps(ID).beta_v*(0-dcps(ID).x)-dcps(ID).v))*tau; + dcps(ID).xd = dcps(ID).v*tau; + else + dcps(ID).vd = 0; + dcps(ID).xd = dcps(ID).alpha_x*(0-dcps(ID).x)*tau; + end + + % note that yd = td = z*tau ==> z=td/tau; the first equation means + % simply dcps(ID).zd = tdd + dcps(ID).zd = (dcps(ID).alpha_z*(dcps(ID).beta_z*(dcps(ID).g-dcps(ID).y)-dcps(ID).z)+f)*tau; + dcps(ID).yd = dcps(ID).z*tau; + dcps(ID).ydd= dcps(ID).zd*tau; + + dcps(ID).gd = dcps(ID).alpha_g*(dcps(ID).G-dcps(ID).g); + + dcps(ID).x = dcps(ID).xd*dt+dcps(ID).x; + dcps(ID).v = dcps(ID).vd*dt+dcps(ID).v; + + dcps(ID).z = dcps(ID).zd*dt+dcps(ID).z; + dcps(ID).y = dcps(ID).yd*dt+dcps(ID).y; + + dcps(ID).g = dcps(ID).gd*dt+dcps(ID).g; + + varargout(1) = {dcps(ID).y}; + varargout(2) = {dcps(ID).yd}; + varargout(3) = {dcps(ID).ydd}; + + if (dcps(ID).A == 0) + max_y = max(max_y,dcps(ID).y); + min_y = min(min_y,dcps(ID).y); + if (dcps(ID).x < 0.0001) + dcps(ID).A = max_y - min_y; + end + end + +% ......................................................................... + case 'batch_fit' + + ID = varargin{1}; + tau = 0.5/varargin{2}; % tau is relative to 0.5 seconds nominal movement time + dt = varargin{3}; + T = varargin{4}; + if (nargin > 5) + Td = varargin{5}; + else + Td = diffnc(T,dt); + end + if (nargin > 6) + Tdd = varargin{6}; + else + Tdd = diffnc(Td,dt); + end + + % the start state is the first state in the trajectory + y0 = T(1); + g = y0; + + % the goal is the last state in the trajectory + goal = T(end); + if (dcps(ID).c_order == 0) + g = goal; + end + + % the amplitude is the max(T)-min(T) + A = max(T)-min(T); + + % compute the hidden states + X = zeros(size(T)); + V = zeros(size(T)); + G = zeros(size(T)); + x = 1; + v = 0; + + for i=1:length(T), + + X(i) = x; + V(i) = v; + G(i) = g; + + if (dcps(ID).c_order == 1) + vd = dcps(ID).alpha_v*(dcps(ID).beta_v*(0-x)-v)*tau; + xd = v*tau; + else + vd = 0; + xd = dcps(ID).alpha_x*(0-x)*tau; + end + gd = (goal - g) * dcps(ID).alpha_g; + + x = xd*dt+x; + v = vd*dt+v; + g = gd*dt+g; + + end + + % the regression target + dcps(ID).dG = goal - y0; + dcps(ID).A = max(T)-min(T); + dcps(ID).s = 1; % for fitting a new primitive, the scale factor is always equal to one + + amp = dcps(ID).s; + Ft = (Tdd/tau^2-dcps(ID).alpha_z*(dcps(ID).beta_z*(G-T)-Td/tau)) / amp; + + % compute the weights for each local model along the trajectory + PSI = exp(-0.5*((X*ones(1,length(dcps(ID).c))-ones(length(T),1)*dcps(ID).c').^2).*(ones(length(T),1)*dcps(ID).D')); + + % compute the regression + if (dcps(ID).c_order == 1) + dcps(ID).sx2 = sum(((V.^2)*ones(1,length(dcps(ID).c))).*PSI,1)'; + dcps(ID).sxtd = sum(((V.*Ft)*ones(1,length(dcps(ID).c))).*PSI,1)'; + dcps(ID).w = dcps(ID).sxtd./(dcps(ID).sx2+1.e-10); + else + dcps(ID).sx2 = sum(((X.^2)*ones(1,length(dcps(ID).c))).*PSI,1)'; + dcps(ID).sxtd = sum(((X.*Ft)*ones(1,length(dcps(ID).c))).*PSI,1)'; + dcps(ID).w = dcps(ID).sxtd./(dcps(ID).sx2+1.e-10); + end + + % compute the prediction + if (dcps(ID).c_order == 1) + F = sum((V*dcps(ID).w').*PSI,2)./sum(PSI,2) * amp; + else + F = sum((X*dcps(ID).w').*PSI,2)./sum(PSI,2) * amp; + end + z = 0; + zd = 0; + y = y0; + Y = zeros(size(T)); + Yd = zeros(size(T)); + Ydd = zeros(size(T)); + + for i=1:length(T), + + Ydd(i) = zd*tau; + Yd(i) = z; + Y(i) = y; + + zd = (dcps(ID).alpha_z*(dcps(ID).beta_z*(G(i)-y)-z)+F(i))*tau; + yd = z; + + z = zd*dt+z; + y = yd*dt+y; + + end + + varargout(1) = {Y}; + varargout(2) = {Yd}; + varargout(3) = {Ydd}; + +% ......................................................................... + case 'structure' + ID = varargin{1}; + varargout(1) = {dcps(ID)}; + +% ......................................................................... + case 'clear' + ID = varargin{1}; + if exist('dcps') + if length(dcps) >= ID, + dcps(ID) = []; + end + end + +% ......................................................................... + case 'minjerk' + ID = varargin{1}; + + % generate the minimum jerk trajectory as target to learn from + t=0; + td=0; + tdd=0; + goal = 1; + + dcp('reset_state',ID); + dcp('set_goal',ID,goal,1); + tau = 0.5; + dt = 0.001; + T=zeros(2*tau/dt,3); + + for i=0:2*tau/dt, + [t,td,tdd]=min_jerk_step(t,td,tdd,goal,tau-i*dt,dt); + T(i+1,:) = [t td tdd]; + end; + + % batch fitting + i = round(2*tau/dt); % only fit the part of the trajectory with the signal + [Yp,Ypd,Ypdd]=dcp('batch_fit',ID,tau,dt,T(1:i,1),T(1:i,2),T(1:i,3)); + +% ......................................................................... + otherwise + error('unknown action'); + +end \ No newline at end of file diff --git a/dmp/matlab/dmp_from_ogs/code/dmp_learn.m b/dmp/matlab/dmp_from_ogs/code/dmp_learn.m new file mode 100644 index 0000000000000000000000000000000000000000..8355cec88f66f427acbeac0000c7729359ef52a5 --- /dev/null +++ b/dmp/matlab/dmp_from_ogs/code/dmp_learn.m @@ -0,0 +1 @@ +% function to learn a DCP in batch mode using a minimum jerk trajectory as % template global dcps; % general parameters dt = 0.001; goal = 1; tau = 0.5; n_rfs = 10; ID = 1; % initialize DMP dcp('clear',ID); dcp('init',ID,n_rfs,'minJerk_dcp',1); % initialize some variables for plotting Z=zeros(floor(2*tau/dt+1),2); X=Z; V=Z; T=zeros(floor(2*tau/dt+1),3); Y=T; PSI=zeros(floor(2*tau/dt+1),n_rfs); W=PSI; % generate the minimum jerk trajectory t=0; td=0; tdd=0; for i=0:2*tau/dt, [t,td,tdd]=min_jerk_step(t,td,tdd,goal,tau-i*dt,dt); T(i+1,:) = [t td tdd]; end; % use the in-built function to initialize the dcp with minjerk dcp('Batch_Fit',ID,tau,dt,T(:,1),T(:,2),T(:,3)); % test the fit dcp('reset_state',ID); dcp('set_goal',ID,goal,1); for i=0:2*tau/dt, [y,yd,ydd]=dcp('run',ID,tau,dt); Z(i+1,:) = [dcps(ID).z dcps(ID).zd]; Y(i+1,:) = [y yd ydd]; X(i+1,:) = [dcps(ID).x dcps(ID).xd]; V(i+1,:) = [dcps(ID).v dcps(ID).vd]; PSI(i+1,:) = dcps(ID).psi'; W(i+1,:) = dcps(ID).w'; end; % plotting time = (0:dt:tau*2)'; figure(1); clf; % plot position, velocity, acceleration vs. target subplot(431); plot(time,[Y(:,1) T(:,1)]); title('y'); aa=axis; axis([min(time) max(time) aa(3:4)]); subplot(432); plot(time,[Y(:,2) T(:,2)]); title('yd'); aa=axis; axis([min(time) max(time) aa(3:4)]); subplot(433); plot(time,[Y(:,3) T(:,3)]); title('ydd'); aa=axis; axis([min(time) max(time) aa(3:4)]); % plot internal states subplot(434); plot(time,Z(:,1)); title('z'); aa=axis; axis([min(time) max(time) aa(3:4)]); subplot(435); plot(time,Z(:,2)); title('zd'); aa=axis; axis([min(time) max(time) aa(3:4)]); subplot(436); plot(time,PSI); title('Weighting Kernels'); aa=axis; axis([min(time) max(time) aa(3:4)]); subplot(437); plot(time,V(:,1)); title('v'); aa=axis; axis([min(time) max(time) aa(3:4)]); subplot(438); plot(time,V(:,2)); title('vd'); aa=axis; axis([min(time) max(time) aa(3:4)]); subplot(439); plot(time,W); title('Linear Model Weights over Time'); aa=axis; axis([min(time) max(time) aa(3:4)]); subplot(4,3,10); plot(time,X(:,1)); title('x'); aa=axis; axis([min(time) max(time) aa(3:4)]); subplot(4,3,11); plot(time,X(:,2)); title('xd'); aa=axis; axis([min(time) max(time) aa(3:4)]); subplot(4,3,12); plot(W(end,:)); title('Weights'); xlabel(sprintf('tau=%f',tau)); drawnow; \ No newline at end of file diff --git a/dmp/matlab/dmp_from_ogs/code/rcp.m b/dmp/matlab/dmp_from_ogs/code/rcp.m new file mode 100644 index 0000000000000000000000000000000000000000..b8005eecf703091e9f16e6bda1ca084e5f39c56a --- /dev/null +++ b/dmp/matlab/dmp_from_ogs/code/rcp.m @@ -0,0 +1,396 @@ +function [varargout] = rcp(action,varargin) +% A rhythmic movement primitive (RCP) as suggested in +% Ijspeert A, Nakanishi J, Schaal S (2003) Learning attractor landscapes for +% learning motor primitives. In: Becker S, Thrun S, Obermayer K (eds) Advances +% in Neural Information Processing Systems 15. MIT Press, Cambridge, MA. +% http://www-clmc.usc.edu/publications/I/ijspeert-NIPS2002.pdf +% This version simplfies the primitive and only uses a one dimensional +% function fitting. +% +% Copyright June, 2006 by +% Stefan Schaal and Auke Ijspeert +% +% --------------- Different Actions of the program ------------------------ +% +% Initialize a rcp model: +% FORMAT rcp('Init',ID,n_rfs,name) +% ID : desired ID of model +% n_rfs : number of local linear models +% name : a name for the model +% +% alternatively, the function is called as +% +% FORMAT rcp('Init',ID,d,) +% d : a complete data structure of a rcp model +% +% returns nothing +% ------------------------------------------------------------------------- +% +% Set the amplitude: +% FORMAT rcp('Set_Amplitude',ID,A) +% ID : ID of model +% A : the new amplitude +% +% returns nothing +% ------------------------------------------------------------------------- +% +% Set the baseline: +% FORMAT rcp('Set_Baseline',ID,ym) +% ID : ID of model +% ym : the new baseline for the oscillation +% +% returns nothing +% ------------------------------------------------------------------------- +% +% Run the rcp: +% FORMAT [[y,yd,ydd]=rcp('Run',ID,tau,dt) +% ID : ID of model +% tau : global time constant to scale speed of system +% dt : integration time step +% +% returns y,yd,ydd, i.e., current pos,vel,acc, of the rcp +% ------------------------------------------------------------------------- +% +% Change values of a rcp: +% FORMAT rcp('Change',ID,pname,value) +% ID : ID of model +% pname : parameter name +% value : value to be assigned to parameter +% +% returns nothing +% ------------------------------------------------------------------------- +% +% Run the rcps: +% FORMAT rcp('Run',ID,tau,dt,t,td) +% ID : ID of model +% tau : time constant to scale speed, roughly equivalent to +% period of movement +% dt : integration time step +% +% returns y,yd,ydd, i.e., current pos,vel,acc, of the rcp +% ------------------------------------------------------------------------- +% +% Run the rcp and update the weights: +% FORMAT rcp('Run_Fit',ID,tau,dt,t,td,tdd) +% ID : ID of model +% tau : time constant to scale speed +% dt : integration time step +% t : target for y +% td : target for yd +% tdd : target for ydd +% +% returns y,yd,ydd, i.e., current pos,vel,acc, of the rcp +% ------------------------------------------------------------------------- +% +% Fit the rcp to a complete trajectory in batch mode: +% FORMAT rcp('Batch_Fit',ID,tau,dt,T,Td) +% ID : ID of model +% tau : time constant to scale speed, tau is roughly movement +% time until convergence the goal +% dt : somple time step in given trajectory +% T : target trajectory for y +% Td : target trajectory for yd (optional, will be generated +% as dT/dt otherwise +% Tdd : target trajectory for ydd (optional, will be generated +% as dTd/dt otherwise +% +% returns y,yd,ydd, i.e., current pos,vel,acc, of the rcp +% ------------------------------------------------------------------------- +% +% Return the data structure of a rcp model +% FORMAT [d] = rcps('Structure',ID) +% ID : desired ID of model +% +% returns the complete data structure of a rcp model, e.g., for saving or +% inspecting it +% ------------------------------------------------------------------------- +% +% Reset the states of a rcp model to zero +% FORMAT [d] = rcps('Reset_State',ID) +% ID : desired ID of model +% +% returns nothing +% ------------------------------------------------------------------------- +% +% Clear the data structure of a LWPR model +% FORMAT rcps('Clear',ID) +% ID : ID of model +% +% returns nothing +% ------------------------------------------------------------------------- +% +% Initializes the rcp with a sine trajectory +% FORMAT rcps('Sine',ID) +% ID : ID of model +% +% returns nothing +% ------------------------------------------------------------------------- + +% the global structure to store all rcps +global rcps; + +% at least two arguments are needed +if nargin < 2, + error('Incorrect call to rcp'); +end + +switch lower(action), +% ......................................................................... + case 'init' + if (nargin == 3) + ID = varargin{1}; + rcps(ID) = varargin{2}; + else + % this initialization is good for period 1 second movement for tau=1 + ID = varargin{1}; + n_rfs = varargin{2}; + rcps(ID).name = varargin{3}; + % the time constants for chosen for critical damping + rcps(ID).alpha_z = 25; + rcps(ID).beta_z = rcps(ID).alpha_z/4; + rcps(ID).omega = 0.01;%2*pi; + % initialize the state variables + rcps(ID).z = 0; + rcps(ID).y = 0; + rcps(ID).p = 0; + rcps(ID).zd = 0; + rcps(ID).yd = 0; + rcps(ID).pd = 0; + rcps(ID).ydd = 0; + % baseline and amplitude of oscillation + rcps(ID).ym = 0; + rcps(ID).A = 0; + + % the local models, spaced on grid in phase space + rcps(ID).c = 2*pi*(1/n_rfs:1/n_rfs:1)'; + rcps(ID).psi = zeros(n_rfs,1); + rcps(ID).w = zeros(n_rfs,1); + rcps(ID).sp2 = zeros(n_rfs,1); + rcps(ID).sptd = zeros(n_rfs,1); + rcps(ID).D = ones(n_rfs,1)*.1*n_rfs^2; + rcps(ID).lambda = 1; + end + +% ......................................................................... + case 'reset_state' + ID = varargin{1}; + % initialize the state variables + rcps(ID).z = 0; + rcps(ID).y = 0; + rcps(ID).p = 0; + rcps(ID).zd = 0; + rcps(ID).yd = 0; + rcps(ID).pd = 0; + rcps(ID).ydd = 0; + % the baseline + rcps(ID).ym = 0; + +% ......................................................................... + case 'set_baseline' + ID = varargin{1}; + rcps(ID).ym = varargin{2}; + +% ......................................................................... + case 'set_amplitude' + ID = varargin{1}; + rcps(ID).A = varargin{2}; + +% ......................................................................... + case 'run' + ID = varargin{1}; + tau = varargin{2}; + dt = varargin{3}; + if nargin > 4, + random_value = varargin{4}; + else + random_value = 0; + end + + % the weighted sum of the locally weighted regression models + rcps(ID).psi = exp(rcps(ID).D.*(cos(rcps(ID).p-rcps(ID).c)-1)); + amp = rcps(ID).A; + f = sum(rcps(ID).w.*rcps(ID).psi)/sum(rcps(ID).psi+1.e-10) * amp; + + rcps(ID).pd = rcps(ID).omega*tau; + + rcps(ID).zd = (rcps(ID).alpha_z*(rcps(ID).beta_z*(rcps(ID).ym-rcps(ID).y)-rcps(ID).z)+f)*tau ... + + random_value; + rcps(ID).yd = rcps(ID).z*tau; + rcps(ID).ydd= rcps(ID).zd*tau; + + rcps(ID).p = rcps(ID).pd*dt+rcps(ID).p; + + rcps(ID).z = rcps(ID).zd*dt+rcps(ID).z; + rcps(ID).y = rcps(ID).yd*dt+rcps(ID).y; + + varargout(1) = {rcps(ID).y}; + varargout(2) = {rcps(ID).yd}; + varargout(3) = {rcps(ID).ydd}; + %varargout(4) = {rcps(ID).psi*rcps(ID).v/sum(rcps(ID).psi)}; + varargout(4) = {amp*rcps(ID).psi}; + +% ......................................................................... + case 'change' + ID = varargin{1}; + command = sprintf('rcps(%d).%s = varargin{3};',ID,varargin{2}); + eval(command); + +% ......................................................................... + case 'run_fit' + ID = varargin{1}; + tau = varargin{2}; + dt = varargin{3}; + t = varargin{4}; + td = varargin{5}; + tdd = varargin{6}; + + % the regression target + amp = rcps(ID).A; + ft = (tdd/tau^2-rcps(ID).alpha_z*(rcps(ID).beta_z*(rcps(ID).ym-t)-td/tau))/amp; + + % the weighted sum of the locally weighted regression models + rcps(ID).psi = exp(rcps(ID).D.*(cos(rcps(ID).p-rcps(ID).c)-1)); + + % update the regression + rcps(ID).sp2 = rcps(ID).sp2*rcps(ID).lambda + rcps(ID).psi; + rcps(ID).sptd = rcps(ID).sptd*rcps(ID).lambda + rcps(ID).psi*ft; + rcps(ID).w = rcps(ID).sptd./(rcps(ID).sp2+1.e-10); + + % compute nonlinearity + f = sum(rcps(ID).w.*rcps(ID).psi)/sum(rcps(ID).psi+1.e-10) * amp; + + % integrate + rcps(ID).pd = rcps(ID).omega*tau; + + % note that yd = td = z*tau ==> z=td/tau; the first equation means + % simply rcps(ID).zd = tdd + rcps(ID).zd = (rcps(ID).alpha_z*(rcps(ID).beta_z*(rcps(ID).ym-rcps(ID).y)-rcps(ID).z)+f)*tau; + rcps(ID).yd = rcps(ID).z*tau; + rcps(ID).ydd= rcps(ID).zd*tau; + + rcps(ID).p = rcps(ID).pd*dt+rcps(ID).p; + + rcps(ID).z = rcps(ID).zd*dt+rcps(ID).z; + rcps(ID).y = rcps(ID).yd*dt+rcps(ID).y; + + varargout(1) = {rcps(ID).y}; + varargout(2) = {rcps(ID).yd}; + varargout(3) = {rcps(ID).ydd}; + +% ......................................................................... + case 'batch_fit' + + ID = varargin{1}; + tau = varargin{2}; + dt = varargin{3}; + T = varargin{4}; + if (nargin > 4) + Td = varargin{5}; + else + Td = diffnc(T,dt); + end + if (nargin > 5) + Tdd = varargin{6}; + else + Tdd = diffnc(Td,dt); + end + + % the amplitude + A = rcps(ID).A; + + % the baseline + ym = rcps(ID).ym; + + % compute the hidden states + P = zeros(size(T)); + p = 0; + + for i=1:length(T), + P(i) = p; + pd = rcps(ID).omega*tau; + p = pd*dt+p; + end + + % the regression target + amp = A; + Ft = (Tdd/tau^2-rcps(ID).alpha_z*(rcps(ID).beta_z*(ym-T)-Td/tau)) / amp; + + % compute the weights for each local model along the trajectory + PSI = exp((cos(P*ones(1,length(rcps(ID).c))-ones(length(T),1)*rcps(ID).c')-1).*(ones(length(T),1)*rcps(ID).D')); + + + % compute the regression + rcps(ID).sp2 = sum((ones(length(P),length(rcps(ID).c))).*PSI,1)'; + rcps(ID).sptd = sum((Ft*ones(1,length(rcps(ID).c))).*PSI,1)'; + rcps(ID).w = rcps(ID).sptd./(rcps(ID).sp2+1.e-10); + + + % compute the prediction + F = sum((ones(length(P),1)*rcps(ID).w').*PSI,2)./sum(PSI,2) * amp; + z = 0; + zd = 0; + y = T(1); + Y = zeros(size(T)); + Yd = zeros(size(T)); + Ydd = zeros(size(T)); + + for i=1:length(T), + + Ydd(i) = zd*tau; + Yd(i) = z; + Y(i) = y; + + zd = (rcps(ID).alpha_z*(rcps(ID).beta_z*(ym-y)-z)+F(i))*tau; + yd = z; + + z = zd*dt+z; + y = yd*dt+y; + + end + + varargout(1) = {Y}; + varargout(2) = {Yd}; + varargout(3) = {Ydd}; + +% ......................................................................... + case 'structure' + ID = varargin{1}; + varargout(1) = {rcps(ID)}; + +% ......................................................................... + case 'clear' + ID = varargin{1}; + rcps(ID) = []; + +% ......................................................................... + case 'sine' + ID = varargin{1}; + + % generate the minimum jerk trajectory as target to learn from + t=0; + td=0; + tdd=0; + A = 1; + ym = 0; + + rcp('reset_state',ID); + rcp('set_amplitude',ID,A); + rcp('set_baseline',ID,ym); + tau = 1; + dt = 0.001; + T=zeros(2*tau/dt,3); + + for i=0:2*tau/dt, + t = i*dt; + T(i+1,:) = [A*sin(2*pi/tau*t) A*(2*pi/tau)*cos(2*pi/tau*t) -A*(2*pi/tau)^2*sin(2*pi/tau*t)]; + end; + + % batch fitting + i = round(2*tau/dt); % only fit the part of the trajectory with the signal + [Yp,Ypd,Ypdd]=rcp('batch_fit',ID,tau,dt,T(1:i,1),T(1:i,2),T(1:i,3)); + +% ......................................................................... + otherwise + error('unknown action'); + +end \ No newline at end of file diff --git a/dmp/matlab/dmp_from_ogs/code/rmp_learn.m b/dmp/matlab/dmp_from_ogs/code/rmp_learn.m new file mode 100644 index 0000000000000000000000000000000000000000..42ebf0d340ed4e8c44d4b72ea544cf0d66182768 --- /dev/null +++ b/dmp/matlab/dmp_from_ogs/code/rmp_learn.m @@ -0,0 +1 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% %% Learns a rhythmic movement primitive (RCP) in batch mode %% %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% clc; close all; clear all; %% Define parameters % global variable global rcps; % symbolic varible syms t; %time % general parameters BATCH = 1; % 0 - incremental learning, 1 - batch learning dt = 0.01; % ym = 0; % A = 1; % n_rfs = 1000; % 50 tau = 1; % omega = 0.01; % frequency duration = 10; % experiment duration (in sec) dimentions = 2; % number of conrolled axis % variables arrays for data monitoring time = []; % time time_end = []; % end of each experiment %D = zeros(round(duration*tau/dt+1),3,dimentions); % data: (D = [[t(0) t(1) ...] [position velocity acceleration] [x-axis y-axis]]) D = zeros(0,3,dimentions); % %% Generate data % for i=0:10*tau/dt % d(1) = 1 - (2*2^(1/2)*cos(2*pi*dt*i))/(cos(4*pi*dt*i) - 3); % dd(1) = (4*2^(1/2)*pi*sin(2*pi*dt*i))/(cos(4*pi*dt*i) - 3) - (8*2^(1/2)*pi*cos(2*pi*dt*i)*sin(4*pi*dt*i))/(cos(4*dt*i*pi) - 3)^2; % ddd(1) = (8*2^(1/2)*pi^2*cos(2*pi*dt*i))/(cos(4*pi*dt*i) - 3) - (64*2^(1/2)*pi^2*cos(2*pi*dt*i)*sin(4*pi*dt*i)^2)/(cos(4*dt*i*pi) - 3)^3 - (32*2^(1/2)*pi^2*cos(2*pi*dt*i)*cos(4*pi*dt*i))/(cos(4*dt*i*pi) - 3)^2 + (32*2^(1/2)*pi^2*sin(2*pi*dt*i)*sin(4*pi*dt*i))/(cos(4*dt*i*pi) - 3)^2; % d(2) = 2 - (2*sin(4*pi*dt*i))/(cos(4*pi*dt*i) - 3); % dd(2) = - (8*pi*cos(4*pi*dt*i))/(cos(4*pi*dt*i) - 3) - (8*pi*sin(4*pi*dt*i)^2)/(cos(4*dt*i*pi) - 3)^2; % ddd(2) = (32*pi^2*sin(4*pi*dt*i))/(cos(4*pi*dt*i) - 3) - (64*pi^2*sin(4*pi*dt*i)^3)/(cos(4*dt*i*pi) - 3)^3 - (96*pi^2*cos(4*pi*dt*i)*sin(4*pi*dt*i))/(cos(4*dt*i*pi) - 3)^2; % D(i+1,:,1) = [d(1) dd(1) ddd(1)]; % D(i+1,:,2) = [d(2) dd(2) ddd(2)]; % end % time = (0:dt:tau*10)'; % % % add some gausian white noise % D(:,1,:) = D(:,1,:) + randn(size(D(:,1,:))) .* (max(D(:,1,:)) - min(D(:,1,:))) / 50; % D(:,2,:) = D(:,2,:) + randn(size(D(:,2,:))) .* (max(D(:,2,:)) - min(D(:,2,:))) / 50; % D(:,3,:) = D(:,3,:) + randn(size(D(:,3,:))) .* (max(D(:,3,:)) - min(D(:,3,:))) / 50; %% Load data indx_Time = 1; indx_RawH1 = 2:3; indx_RawH2 = 4:5; indx_PosH1 = 6:7; indx_PosH2 = 8:9; indx_VelH1 = 10:11; indx_VelH2 = 12:13; indx_AccH1 = 14:15; indx_AccH2 = 16:17; indx_PosO1 = 18:19; indx_PosO2 = 20:21; indx_VelO1 = 22:23; indx_VelO2 = 24:25; indx_AccO1 = 26:27; indx_AccO2 = 28:29; indx_K1 = 37; %% Siffness indx_K2 = 38; indx_B1 = 39; %% Damping indx_B2 = 40; indx_A0 = 41; %% admittance Object pathname = [pwd '\MATLAB\data\Chris_Davide\session_1\HMan1_Intermit\']; file_list = dir([pathname '*.mat']); for i = 1:1%length(file_list) filename = file_list(i).name load([pathname filename]); data = data'; d1 = [data(:, indx_PosH1(1)) data(:, indx_VelH1(1)) data(:, indx_AccH1(1))]; d2 = [data(:, indx_PosH1(2)) data(:, indx_VelH1(2)) data(:, indx_AccH1(2))]; l = length(D); D(l+1:l+length(data),:,1) = d1; D(l+1:l+length(data),:,2) = d2; if isempty(time) time = data(:, indx_Time); else time = [time; data(:, indx_Time) + time(end)]; end time_end = [time_end, time(end)]; max(time) end % numerical derivation of velocity and acceleration D(:,2,1) = [0; diff(D(:,1,1))]/dt; D(:,3,1) = [0; diff(D(:,2,1))]/dt; D(:,2,2) = [0; diff(D(:,1,2))]/dt; D(:,3,2) = [0; diff(D(:,2,2))]/dt; %% Alocate variables for monitoring P = zeros(length(D),2,dimentions); % Z = zeros(length(D),2,dimentions); % Y = zeros(length(D),3,dimentions); % PSI = zeros(length(D),n_rfs,dimentions); % W = zeros(length(D),n_rfs,dimentions); % F = zeros(length(D),3,dimentions); % fit result: (F = [[t(0) t(1) ...] [position velocity acceleration] [x-axis y-axis]]) %% Initialize RCPs for j = 1:dimentions rcp('init',j,n_rfs,['axis', num2str(j)]); rcp('reset_state',j); rcp('set_baseline',j,ym); rcp('set_amplitude',j,A); end %% Batch fitting if BATCH == 1 for j = 1:dimentions [F(:,1,j), F(:,2,j), F(:,3,j)] = rcp('batch_fit', j, tau, dt, D(:,1,j), D(:,2,j), D(:,3,j)); end %% Incremental fitting else for j = 1:dimentions for i = 1:length(time) [F(i,1,j), F(i,2,j), F(i,3,j)] = rcp('run_fit', j, tau, dt, D(i,1,j), D(i,2,j), D(i,3,j)); end end end %% Reset RCP for j = 1:dimentions rcp('reset_state',j); rcp('set_baseline',j,ym); rcp('set_amplitude',j,A); end %% Run RCP for j = 1:dimentions for i = 1:length(time) [y,yd,ydd] = rcp('run',j,tau,dt); P(i,:,j) = [rcps(j).p rcps(j).pd]; Z(i,:,j) = [rcps(j).z rcps(j).zd]; Y(i,:,j) = [y yd ydd]; PSI(i,:,j) = rcps(j).psi'; W(i,:,j) = rcps(j).w'; disp([num2str(((j - 1)/dimentions + i/length(time)/dimentions)*100),'%']) end end %% Plot % plot position, velocity, acceleration vs. target figure(1); clf; hold on; grid on; scatter(D(:,1,1), D(:,1,2), 20, 'b.'); %plot(D(:,1,1), D(:,1,2), 'b:', 'linewidth', 2); plot(F(:,1,1), F(:,1,2), 'g--', 'linewidth', 2); plot(Y(:,1,1), Y(:,1,2), 'r-', 'linewidth', 2); legend('data', 'fit', 'run', 'Orientation', 'horizontal', 'FontSize', 11, 'Position', [0.21, 0.95, 0.58, 0.04]); set(gca, 'fontsize', 11); set(gca, 'TickLabelInterpreter', 'latex'); xlabel('$x$', 'interpreter', 'latex', 'fontsize', 11); ylabel('$y$', 'interpreter', 'latex', 'fontsize', 11); % figure(11); % subplot(211); % hold on; % grid on; % scatter(time, D(:,1,1), 20, 'b.'); % plot(time, F(:,1,1), 'g', 'linewidth', 2); % for i = 1:length(time_end) % xline(time_end(i), ':', 'linewidth', 1); % end % xlim([0 max(time)]); % set(gca, 'fontsize', 11); % set(gca, 'TickLabelInterpreter', 'latex') % ylabel('$x$', 'interpreter', 'latex', 'fontsize', 11); % subplot(212); % hold on; % grid on; % h1 = scatter(time, D(:,1,2), 20, 'b.'); % h2 = plot(time, F(:,1,2), 'g', 'linewidth', 2); % legend([h1, h2], {'data', 'fit'}, 'Orientation', 'horizontal', 'FontSize', 11, 'Position', [0.21, 0.95, 0.58, 0.04]); % for i = 1:length(time_end) % h_xline = xline(time_end(i), ':', 'linewidth', 1, 'HandleVisibility', 'off'); % end % xlim([0 max(time)]); % set(gca, 'fontsize', 11); % set(gca, 'TickLabelInterpreter', 'latex') % xlabel('$t$', 'interpreter', 'latex', 'fontsize', 11); % ylabel('$y$', 'interpreter', 'latex', 'fontsize', 11); % plot position, velocity, acceleration vs. target for j = 1:dimentions figure(j+1); Dd = [0; diff(D(:,1,j))]/dt; Ddd1 = [0; diff(Dd)]/dt; Ddd2 = [0; diff(D(:,2,j))]/dt; subplot(311); hold on; grid on; scatter(time, D(:,1,j), 20, 'b.'); plot(time, F(:,1,j), 'g--', 'linewidth', 2); plot(time, Y(:,1,j), 'r-', 'linewidth', 2); for i = 1:length(time_end) xline(time_end(i), ':', 'linewidth', 1); end xlim([0 max(time)]); set(gca, 'fontsize', 11); set(gca, 'TickLabelInterpreter', 'latex') ylabel(['$y_', num2str(j),'$ [m]'], 'interpreter', 'latex', 'fontsize', 11); subplot(312); hold on; grid on; scatter(time, D(:,2,j), 20, 'b.'); % plot(time, Dd, 'c:', 'linewidth', 2); plot(time, F(:,2,j), 'g--', 'linewidth', 2); plot(time, Y(:,2,j), 'r-', 'linewidth', 2); for i = 1:length(time_end) xline(time_end(i), ':', 'linewidth', 1); end xlim([0 max(time)]); set(gca, 'fontsize', 11); set(gca, 'TickLabelInterpreter', 'latex') ylabel(['$\dot{y}_', num2str(j),'$ [m/s]'], 'interpreter', 'latex', 'fontsize', 11); subplot(313); hold on; grid on; h1 = scatter(time, D(:,3,j), 20, 'b.'); % h2 = plot(time, Ddd1, 'c:', 'linewidth', 2); % plot(time, Ddd2, 'm:', 'linewidth', 2); h2 = plot(time, F(:,3,j), 'g--', 'linewidth', 2); h3 = plot(time, Y(:,3,j), 'r-', 'linewidth', 2); legend([h1, h2, h3], {'data', 'fit', 'run'}, 'Orientation', 'horizontal', 'FontSize', 11, 'Position', [0.21, 0.95, 0.58, 0.04]); for i = 1:length(time_end) h_xline = xline(time_end(i), ':', 'linewidth', 1, 'HandleVisibility', 'off'); end xlim([0 max(time)]); set(gca, 'fontsize', 11); set(gca, 'TickLabelInterpreter', 'latex') xlabel('$t$ [s]', 'interpreter', 'latex', 'fontsize', 11); ylabel(['$\ddot{y}_', num2str(j),'$ [m/s$^2$]'], 'interpreter', 'latex', 'fontsize', 11); end % plot internal states for j = 1:dimentions figure(dimentions+1+j); subplot(231); plot(time,Z(:,1,j)); title('z'); aa=axis; axis([min(time) max(time) aa(3:4)]); subplot(232); plot(time,Z(:,2,j)); title('zd'); aa=axis; axis([min(time) max(time) aa(3:4)]); subplot(233); plot(time,PSI(:,:,j)); title('Weighting Kernels'); aa=axis; axis([min(time) max(time) aa(3:4)]); subplot(234); plot(time,P(:,1,j)); title('p'); aa=axis; axis([min(time) max(time) aa(3:4)]); subplot(235); plot(time,P(:,2,j)); title('pd'); aa=axis; axis([min(time) max(time) aa(3:4)]); subplot(236); plot(W(end,:,j)); title('Weights'); xlabel(sprintf('tau=%f',tau)); end for j = 1:dimentions for h = 1:3 performance(j,h,1) = immse(Y(:,h,j), D(:,h,j)); % performance(j,h,2) = immse(F(:,h,j), D(:,h,j)); % performance(j,h,3) = immse(Y(:,h,j), F(:,h,j)); end performance(j,:,:) end \ No newline at end of file diff --git a/dmp/matlab/dmp_from_ogs/code/transformation.m b/dmp/matlab/dmp_from_ogs/code/transformation.m new file mode 100644 index 0000000000000000000000000000000000000000..f67e6e70333df47626890a7afba1fbcc77be4ea8 --- /dev/null +++ b/dmp/matlab/dmp_from_ogs/code/transformation.m @@ -0,0 +1,81 @@ +clc; +close all; +clear all; + +%% Load data + +indx_Time = 1; +indx_RawH1 = 2:3; +indx_RawH2 = 4:5; +indx_PosH1 = 6:7; +indx_PosH2 = 8:9; +indx_VelH1 = 10:11; +indx_VelH2 = 12:13; +indx_AccH1 = 14:15; +indx_AccH2 = 16:17; +indx_PosO1 = 18:19; +indx_PosO2 = 20:21; +indx_VelO1 = 22:23; +indx_VelO2 = 24:25; +indx_AccO1 = 26:27; +indx_AccO2 = 28:29; + +indx_K1 = 37; %% Siffness +indx_K2 = 38; +indx_B1 = 39; %% Damping +indx_B2 = 40; +indx_A0 = 41; %% admittance Object + +pathname = [pwd '\..\MATLAB\data\Chris_Davide\session_1\HMan1_Intermit\']; +file_list = dir([pathname '*.mat']); + +for i = 10:10%length(file_list) + filename = file_list(i).name + load([pathname filename]); + data = data'; + + x = [data(:, indx_PosH1(1))]; + wL = [data(:, indx_VelH1(1))]; + aL = [data(:, indx_AccH1(1))]; + y = [data(:, indx_PosH1(2))]; + wR = [data(:, indx_VelH1(2))]; + aR = [data(:, indx_AccH1(2))]; + + t = [data(:, indx_Time)]; +end + +dt = mean(diff(t)); + +% numerical derivation of velocity and acceleration +vx_numerical = [0; diff(x)]/dt; +ax_numerical = [0; diff(vx_numerical)]/dt; +vy_numerical = [0; diff(y)]/dt; +ay_numerical = [0; diff(vy_numerical)]/dt; + +% +J = [vx_numerical'; vy_numerical'] * pinv([wL'; wR']) + +rotm2eul([J [0; 0]; [0 0 1]])/pi*180 + +% J = [0 -1; 1 0] + +rm = 2 * [vx_numerical' vy_numerical'] * pinv([J(1,1)*wL' + J(1,2)*wR' J(2,1)*wL' + J(2,2)*wR']) + +vx_measured = J(1,:)*[wL'; wR']; +vy_measured = J(2,:)*[wL'; wR']; + +figure(2); +hold on; +grid on; +plot(t, vx_numerical, 'r', 'linewidth', 2); +plot(t, vy_numerical, 'g', 'linewidth', 2); +% plot(t, wL, 'm--', 'linewidth', 2); +% plot(t, -wR, 'c--', 'linewidth', 2); +plot(t, vx_measured, 'y:', 'linewidth', 2); +plot(t, vy_measured, 'b:', 'linewidth', 2); +xlim([0 max(t)]); +set(gca, 'fontsize', 11); +set(gca, 'TickLabelInterpreter', 'latex'); +legend('$\dot{x}$', '$\dot{y}$', '$\tilde{v}_x$', '$\tilde{v}_y$', 'interpreter', 'latex', 'fontsize', 11); +xlabel('$t$ [s]', 'interpreter', 'latex', 'fontsize', 11); +ylabel(['$v$ [m/s]'], 'interpreter', 'latex', 'fontsize', 11); \ No newline at end of file diff --git a/dmp/motion_planning/dmp/.dmp.py.swp b/dmp/motion_planning/dmp/.dmp.py.swp new file mode 100644 index 0000000000000000000000000000000000000000..a3910b56929b4cb2d4e3a6d1fde51c388d51c8a8 Binary files /dev/null and b/dmp/motion_planning/dmp/.dmp.py.swp differ diff --git a/dmp/motion_planning/online_traj_scaling/__pycache__/gmr_oa.cpython-310.pyc b/dmp/motion_planning/online_traj_scaling/__pycache__/gmr_oa.cpython-310.pyc new file mode 100644 index 0000000000000000000000000000000000000000..487aeba6b15304b71ac2ca6e7c9c9f0daf37d616 Binary files /dev/null and b/dmp/motion_planning/online_traj_scaling/__pycache__/gmr_oa.cpython-310.pyc differ diff --git a/dmp/my_sol/.run_dmp.py.swp b/dmp/my_sol/.run_dmp.py.swp new file mode 100644 index 0000000000000000000000000000000000000000..eb0534bd4cb7b61dc3a3789fe772b7727640843d Binary files /dev/null and b/dmp/my_sol/.run_dmp.py.swp differ diff --git a/dmp/my_sol/.test_traj_w_speedj.py.swp b/dmp/my_sol/.test_traj_w_speedj.py.swp new file mode 100644 index 0000000000000000000000000000000000000000..b0a2e39c26f4e81689ada873f61d6c521e61172c Binary files /dev/null and b/dmp/my_sol/.test_traj_w_speedj.py.swp differ diff --git a/dmp/my_sol/__pycache__/create_dmp.cpython-310.pyc b/dmp/my_sol/__pycache__/create_dmp.cpython-310.pyc new file mode 100644 index 0000000000000000000000000000000000000000..6624a8482e4f4610de7960c76fea932f0bb877bb Binary files /dev/null and b/dmp/my_sol/__pycache__/create_dmp.cpython-310.pyc differ diff --git a/dmp/my_sol/__pycache__/robotiq_gripper.cpython-310.pyc b/dmp/my_sol/__pycache__/robotiq_gripper.cpython-310.pyc new file mode 100644 index 0000000000000000000000000000000000000000..920ab2eaa831d5fc8c5fd75d9763fe49beff7bbc Binary files /dev/null and b/dmp/my_sol/__pycache__/robotiq_gripper.cpython-310.pyc differ diff --git a/dmp/my_sol/create_dmp.py b/dmp/my_sol/create_dmp.py new file mode 100644 index 0000000000000000000000000000000000000000..c524edceaefe4fa0c38701f60d072123571ebf70 --- /dev/null +++ b/dmp/my_sol/create_dmp.py @@ -0,0 +1,147 @@ +import numpy as np + +class DMP: + def __init__(self, k=100, d=20, a_s=1, n_bfs=100): + # parameters + self.k = k + self.d = d + self.a_s = a_s + self.n_bfs = n_bfs + + # trajectory parameters + self.n = 0 + self.y0 = None + self.tau0 = None + self.g = None + self.tau = None + + # initialize basis functions for LWR + self.w = None + self.centers = None + self.widths = None + + # state + self.x = None + self.theta = None + self.pos = None + self.vel = None + self.acc = None + + # desired path + self.path = None + + # actually init + # TODO pass other trajectories as arguments and etc to make this nice + self.load_trajectory() + self.fit() + + + # TODO pass other trajectories as arguments and etc to make this nice + def load_trajectory(self): + # load trajectory. the current one is something on ur10, but apart from scale it's the same robot + # and this is just joint positions + trajectory_loadpath = './ur10_omega_trajectory.csv' + data = np.genfromtxt(trajectory_loadpath, delimiter=',') + self.time = data[:, 0] + self.time = self.time.reshape(1, len(self.time)) + self.y = np.array(data[:, 1:]).T + + def reset(self): + self.x = np.vstack((np.zeros((self.n, 1)), self.y0, 1.)) + self.tau = self.tau0 + self.theta = 0 + self.pos = self.y0 + self.vel = 0 * self.y0 + self.acc = 0 * self.y0 + + def z(self, x=None): + if x is None: + x = self.x + return x[0:self.n] + + def y_fun(self, x=None): + if x is None: + x = self.x + return x[self.n:2 * self.n] + + def s(self, x=None): + if x is None: + x = self.x + return x[2 * self.n] + + def set_goal(self, g): + self.g = g + + def set_tau(self, tau): + self.tau = tau + + def psi(self, s, i=None): + if i is not None and len(s) == 1: + return np.exp(-1 / (2 * self.widths[i] ** 2) * (s - self.centers[i]) ** 2) + if i is None: + return np.exp(-1 / (2 * self.widths ** 2) * (s - self.centers) ** 2) + + def h(self, x=None): + if x is None: + x = self.x + psi = self.psi(self.s(x)).reshape((self.n_bfs, 1)) + v = (self.w.dot(psi)) / np.maximum(np.sum(psi), 1e-8) * (self.g - self.y0) * self.s(x) + h = self.k * (self.g - self.y_fun(x)) - self.d * self.z(x) + v + return h + + def f(self, x=None): + if x is None: + x = self.x + return np.vstack((self.h(x), self.z(x), -self.a_s * self.s(x))) + + def step(self, dt): + # Update state + self.x = self.x + self.f() / self.tau * dt + self.theta = self.theta + 1 / self.tau * dt + + # Extract trajectory state + vel_prev = self.vel + self.pos = self.y_fun() + self.vel = self.z() / self.tau + self.acc = (self.vel - vel_prev) / dt + +# if you don't know what the letters mean, +# look at the equation (which you need to know anyway) + def fit(self): + # Set target trajectory parameters + self.n = self.y.shape[0] + self.y0 = self.y[:, 0].reshape((self.n, 1)) + self.g = self.y[:, -1].reshape((self.n, 1)) + self.tau0 = self.time[0, -1] + + # Set basis functions + t_centers = np.linspace(0, self.tau0, self.n_bfs, endpoint=True) + self.centers = np.exp(-self.a_s / self.tau0 * t_centers) + widths = np.abs((np.diff(self.centers))) + self.widths = np.concatenate((widths, [widths[-1]])) + + # Calculate derivatives + yd_demo = (self.y[:, 1:] - self.y[:, :-1]) / (self.time[0, 1:] - self.time[0, :-1]) + yd_demo = np.concatenate((yd_demo, np.zeros((self.n, 1))), axis=1) + ydd_demo = (yd_demo[:, 1:] - yd_demo[:, :-1]) / (self.time[0, 1:] - self.time[0, :-1]) + ydd_demo = np.concatenate((ydd_demo, np.zeros((self.n, 1))), axis=1) + + # Compute weights + s_seq = np.exp(-self.a_s / self.tau0 * self.time) + self.w = np.zeros((self.n, self.n_bfs)) + for i in range(self.n): + if abs(self.g[i] - self.y0[i]) < 1e-5: + continue + f_gain = s_seq * (self.g[i] - self.y0[i]) + f_target = self.tau0 ** 2 * ydd_demo[i, :] - self.k * ( + self.g[i] - self.y[i, :]) + self.d * self.tau0 * yd_demo[i, :] + for j in range(self.n_bfs): + psi_j = self.psi(s_seq, j) + num = f_gain.dot((psi_j * f_target).T) + den = f_gain.dot((psi_j * f_gain).T) + if abs(den) < 1e-6: + continue + self.w[i, j] = num / den + + # Reset state + self.reset() diff --git a/dmp/my_sol/generate_traj_from_screen.py b/dmp/my_sol/generate_traj_from_screen.py new file mode 100644 index 0000000000000000000000000000000000000000..7e9b82a40888cc462746f8a1398d8cdbfda14823 --- /dev/null +++ b/dmp/my_sol/generate_traj_from_screen.py @@ -0,0 +1,10 @@ +# we're doing this last, +# just run with a predefined trajectory until then. +# afterward copy the functionality of the matlab part. +# you can do it with one of the tkinter/matplotlib examples you found (and saved) +# while working on the wasp_ivc project + +# the output will be a csv with timestamps and joint angles q +# if required you can finite-difference the q into dq and ddq here +# and shove that into the csv as well, doesn't really matter. +# just comply with the example demo csv. diff --git a/dmp/my_sol/robotiq_gripper.py b/dmp/my_sol/robotiq_gripper.py new file mode 100644 index 0000000000000000000000000000000000000000..a17ab18b99a15f62dc5dff3b0785589ca33b37ac --- /dev/null +++ b/dmp/my_sol/robotiq_gripper.py @@ -0,0 +1,291 @@ +"""Module to control Robotiq's grippers - tested with HAND-E""" + +import socket +import threading +import time +from enum import Enum +from typing import Union, Tuple, OrderedDict + +class RobotiqGripper: + """ + Communicates with the gripper directly, via socket with string commands, leveraging string names for variables. + """ + # WRITE VARIABLES (CAN ALSO READ) + ACT = 'ACT' # act : activate (1 while activated, can be reset to clear fault status) + GTO = 'GTO' # gto : go to (will perform go to with the actions set in pos, for, spe) + ATR = 'ATR' # atr : auto-release (emergency slow move) + ADR = 'ADR' # adr : auto-release direction (open(1) or close(0) during auto-release) + FOR = 'FOR' # for : force (0-255) + SPE = 'SPE' # spe : speed (0-255) + POS = 'POS' # pos : position (0-255), 0 = open + # READ VARIABLES + STA = 'STA' # status (0 = is reset, 1 = activating, 3 = active) + PRE = 'PRE' # position request (echo of last commanded position) + OBJ = 'OBJ' # object detection (0 = moving, 1 = outer grip, 2 = inner grip, 3 = no object at rest) + FLT = 'FLT' # fault (0=ok, see manual for errors if not zero) + + ENCODING = 'UTF-8' # ASCII and UTF-8 both seem to work + + class GripperStatus(Enum): + """Gripper status reported by the gripper. The integer values have to match what the gripper sends.""" + RESET = 0 + ACTIVATING = 1 + # UNUSED = 2 # This value is currently not used by the gripper firmware + ACTIVE = 3 + + class ObjectStatus(Enum): + """Object status reported by the gripper. The integer values have to match what the gripper sends.""" + MOVING = 0 + STOPPED_OUTER_OBJECT = 1 + STOPPED_INNER_OBJECT = 2 + AT_DEST = 3 + + def __init__(self): + """Constructor.""" + self.socket = None + self.command_lock = threading.Lock() + self._min_position = 0 + self._max_position = 255 + self._min_speed = 0 + self._max_speed = 255 + self._min_force = 0 + self._max_force = 255 + + def connect(self, hostname: str, port: int, socket_timeout: float = 2.0) -> None: + """Connects to a gripper at the given address. + :param hostname: Hostname or ip. + :param port: Port. + :param socket_timeout: Timeout for blocking socket operations. + """ + self.socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + self.socket.connect((hostname, port)) + self.socket.settimeout(socket_timeout) + + def disconnect(self) -> None: + """Closes the connection with the gripper.""" + self.socket.close() + + def _set_vars(self, var_dict: OrderedDict[str, Union[int, float]]): + """Sends the appropriate command via socket to set the value of n variables, and waits for its 'ack' response. + :param var_dict: Dictionary of variables to set (variable_name, value). + :return: True on successful reception of ack, false if no ack was received, indicating the set may not + have been effective. + """ + # construct unique command + cmd = "SET" + for variable, value in var_dict.items(): + cmd += f" {variable} {str(value)}" + cmd += '\n' # new line is required for the command to finish + # atomic commands send/rcv + with self.command_lock: + self.socket.sendall(cmd.encode(self.ENCODING)) + data = self.socket.recv(1024) + return self._is_ack(data) + + def _set_var(self, variable: str, value: Union[int, float]): + """Sends the appropriate command via socket to set the value of a variable, and waits for its 'ack' response. + :param variable: Variable to set. + :param value: Value to set for the variable. + :return: True on successful reception of ack, false if no ack was received, indicating the set may not + have been effective. + """ + return self._set_vars(OrderedDict([(variable, value)])) + + def _get_var(self, variable: str): + """Sends the appropriate command to retrieve the value of a variable from the gripper, blocking until the + response is received or the socket times out. + :param variable: Name of the variable to retrieve. + :return: Value of the variable as integer. + """ + # atomic commands send/rcv + with self.command_lock: + cmd = f"GET {variable}\n" + self.socket.sendall(cmd.encode(self.ENCODING)) + data = self.socket.recv(1024) + + # expect data of the form 'VAR x', where VAR is an echo of the variable name, and X the value + # note some special variables (like FLT) may send 2 bytes, instead of an integer. We assume integer here + var_name, value_str = data.decode(self.ENCODING).split() + if var_name != variable: + raise ValueError(f"Unexpected response {data} ({data.decode(self.ENCODING)}): does not match '{variable}'") + value = int(value_str) + return value + + @staticmethod + def _is_ack(data: str): + return data == b'ack' + + def _reset(self): + """ + Reset the gripper. + The following code is executed in the corresponding script function + def rq_reset(gripper_socket="1"): + rq_set_var("ACT", 0, gripper_socket) + rq_set_var("ATR", 0, gripper_socket) + + while(not rq_get_var("ACT", 1, gripper_socket) == 0 or not rq_get_var("STA", 1, gripper_socket) == 0): + rq_set_var("ACT", 0, gripper_socket) + rq_set_var("ATR", 0, gripper_socket) + sync() + end + + sleep(0.5) + end + """ + self._set_var(self.ACT, 0) + self._set_var(self.ATR, 0) + while (not self._get_var(self.ACT) == 0 or not self._get_var(self.STA) == 0): + self._set_var(self.ACT, 0) + self._set_var(self.ATR, 0) + time.sleep(0.5) + + + def activate(self, auto_calibrate: bool = True): + """Resets the activation flag in the gripper, and sets it back to one, clearing previous fault flags. + :param auto_calibrate: Whether to calibrate the minimum and maximum positions based on actual motion. + The following code is executed in the corresponding script function + def rq_activate(gripper_socket="1"): + if (not rq_is_gripper_activated(gripper_socket)): + rq_reset(gripper_socket) + + while(not rq_get_var("ACT", 1, gripper_socket) == 0 or not rq_get_var("STA", 1, gripper_socket) == 0): + rq_reset(gripper_socket) + sync() + end + + rq_set_var("ACT",1, gripper_socket) + end + end + def rq_activate_and_wait(gripper_socket="1"): + if (not rq_is_gripper_activated(gripper_socket)): + rq_activate(gripper_socket) + sleep(1.0) + + while(not rq_get_var("ACT", 1, gripper_socket) == 1 or not rq_get_var("STA", 1, gripper_socket) == 3): + sleep(0.1) + end + + sleep(0.5) + end + end + """ + if not self.is_active(): + self._reset() + while (not self._get_var(self.ACT) == 0 or not self._get_var(self.STA) == 0): + time.sleep(0.01) + + self._set_var(self.ACT, 1) + time.sleep(1.0) + while (not self._get_var(self.ACT) == 1 or not self._get_var(self.STA) == 3): + time.sleep(0.01) + + # auto-calibrate position range if desired + if auto_calibrate: + self.auto_calibrate() + + def is_active(self): + """Returns whether the gripper is active.""" + status = self._get_var(self.STA) + return RobotiqGripper.GripperStatus(status) == RobotiqGripper.GripperStatus.ACTIVE + + def get_min_position(self) -> int: + """Returns the minimum position the gripper can reach (open position).""" + return self._min_position + + def get_max_position(self) -> int: + """Returns the maximum position the gripper can reach (closed position).""" + return self._max_position + + def get_open_position(self) -> int: + """Returns what is considered the open position for gripper (minimum position value).""" + return self.get_min_position() + + def get_closed_position(self) -> int: + """Returns what is considered the closed position for gripper (maximum position value).""" + return self.get_max_position() + + def is_open(self): + """Returns whether the current position is considered as being fully open.""" + return self.get_current_position() <= self.get_open_position() + + def is_closed(self): + """Returns whether the current position is considered as being fully closed.""" + return self.get_current_position() >= self.get_closed_position() + + def get_current_position(self) -> int: + """Returns the current position as returned by the physical hardware.""" + return self._get_var(self.POS) + + def auto_calibrate(self, log: bool = True) -> None: + """Attempts to calibrate the open and closed positions, by slowly closing and opening the gripper. + :param log: Whether to print the results to log. + """ + # first try to open in case we are holding an object + (position, status) = self.move_and_wait_for_pos(self.get_open_position(), 64, 1) + if RobotiqGripper.ObjectStatus(status) != RobotiqGripper.ObjectStatus.AT_DEST: + raise RuntimeError(f"Calibration failed opening to start: {str(status)}") + + # try to close as far as possible, and record the number + (position, status) = self.move_and_wait_for_pos(self.get_closed_position(), 64, 1) + if RobotiqGripper.ObjectStatus(status) != RobotiqGripper.ObjectStatus.AT_DEST: + raise RuntimeError(f"Calibration failed because of an object: {str(status)}") + assert position <= self._max_position + self._max_position = position + + # try to open as far as possible, and record the number + (position, status) = self.move_and_wait_for_pos(self.get_open_position(), 64, 1) + if RobotiqGripper.ObjectStatus(status) != RobotiqGripper.ObjectStatus.AT_DEST: + raise RuntimeError(f"Calibration failed because of an object: {str(status)}") + assert position >= self._min_position + self._min_position = position + + if log: + print(f"Gripper auto-calibrated to [{self.get_min_position()}, {self.get_max_position()}]") + + def move(self, position: int, speed: int, force: int) -> Tuple[bool, int]: + """Sends commands to start moving towards the given position, with the specified speed and force. + :param position: Position to move to [min_position, max_position] + :param speed: Speed to move at [min_speed, max_speed] + :param force: Force to use [min_force, max_force] + :return: A tuple with a bool indicating whether the action it was successfully sent, and an integer with + the actual position that was requested, after being adjusted to the min/max calibrated range. + """ + + def clip_val(min_val, val, max_val): + return max(min_val, min(val, max_val)) + + clip_pos = clip_val(self._min_position, position, self._max_position) + clip_spe = clip_val(self._min_speed, speed, self._max_speed) + clip_for = clip_val(self._min_force, force, self._max_force) + + # moves to the given position with the given speed and force + var_dict = OrderedDict([(self.POS, clip_pos), (self.SPE, clip_spe), (self.FOR, clip_for), (self.GTO, 1)]) + return self._set_vars(var_dict), clip_pos + + def move_and_wait_for_pos(self, position: int, speed: int, force: int) -> Tuple[int, ObjectStatus]: # noqa + """Sends commands to start moving towards the given position, with the specified speed and force, and + then waits for the move to complete. + :param position: Position to move to [min_position, max_position] + :param speed: Speed to move at [min_speed, max_speed] + :param force: Force to use [min_force, max_force] + :return: A tuple with an integer representing the last position returned by the gripper after it notified + that the move had completed, a status indicating how the move ended (see ObjectStatus enum for details). Note + that it is possible that the position was not reached, if an object was detected during motion. + """ + set_ok, cmd_pos = self.move(position, speed, force) + if not set_ok: + raise RuntimeError("Failed to set variables for move.") + + # wait until the gripper acknowledges that it will try to go to the requested position + while self._get_var(self.PRE) != cmd_pos: + time.sleep(0.001) + + # wait until not moving + cur_obj = self._get_var(self.OBJ) + while RobotiqGripper.ObjectStatus(cur_obj) == RobotiqGripper.ObjectStatus.MOVING: + cur_obj = self._get_var(self.OBJ) + + # report the actual position and the object status + final_pos = self._get_var(self.POS) + final_obj = cur_obj + return final_pos, RobotiqGripper.ObjectStatus(final_obj) \ No newline at end of file diff --git a/dmp/my_sol/run_dmp.py b/dmp/my_sol/run_dmp.py new file mode 100644 index 0000000000000000000000000000000000000000..171fa7fd2474d341c1481495166b4e99dcebca55 --- /dev/null +++ b/dmp/my_sol/run_dmp.py @@ -0,0 +1,117 @@ +from create_dmp import DMP +from rtde_control import RTDEControlInterface as RTDEControl +from rtde_receive import RTDEReceiveInterface as RTDEReceive +from robotiq_gripper import RobotiqGripper +import pinocchio as pin +import numpy as np +import os +import time +import signal +import matplotlib.pyplot as plt + + +#urdf_path_relative = "../../robot_descriptions/urdf/ur5e_with_robotiq_hande.urdf" +#urdf_path_absolute = os.path.abspath(urdf_path_relative) +#mesh_dir = "../../robot_descriptions/" +#mesh_dir_absolute = os.path.abspath(mesh_dir) +##print(mesh_dir_absolute) +#model = pin.buildModelFromUrdf(urdf_path_absolute) +##print(model) +#data = pin.Data(model) +##print(data) + +rtde_control = RTDEControl("192.168.1.102") +rtde_receive = RTDEReceive("192.168.1.102") +#rtde_control = RTDEControl("127.0.0.1") +#rtde_receive = RTDEReceive("127.0.0.1") + +N_ITER = 10000 +qs = np.zeros((N_ITER, 6)) +dmp_poss = np.zeros((N_ITER, 6)) +dqs = np.zeros((N_ITER, 6)) +dmp_vels = np.zeros((N_ITER, 6)) + +def handler(signum, frame): + print('sending 100 speedjs full of zeros') + for i in range(100): + rtde_control.endFreedriveMode() + vel_cmd = np.zeros(6) + rtde_control.speedJ(vel_cmd, 0.1, 1.0 / 500) + + print('also plotting') + time = np.arange(N_ITER) + ax_q = plt.subplot(221) + ax_dq = plt.subplot(222) + ax_dmp_q = plt.subplot(223) + ax_dmp_dq = plt.subplot(224) + for i in range(5): + ax_q.plot(time, qs[:,i], color='blue') + ax_dq.plot(time, dqs[:,i], color='red') + ax_dmp_q.plot(time, dmp_poss[:,i], color='green') + ax_dmp_dq.plot(time, dmp_vels[:,i], color='orange') + # for labels + ax_q.plot(time, qs[:,5], color='blue', label='q') + ax_q.legend() + ax_dq.plot(time, dqs[:,5], color='red', label='dq') + ax_dq.legend() + ax_dmp_q.plot(time, dmp_poss[:,5], color='green', label='dmp_q') + ax_dmp_q.legend() + ax_dmp_dq.plot(time, dmp_vels[:,5], color='orange', label='dmp_dq') + ax_dmp_dq.legend() + plt.show() + exit() +# if not rtde_control.isProgramRunning(): +# exit() + +signal.signal(signal.SIGINT, handler) +dmp = DMP() +rtde_control.moveJ(dmp.pos.reshape((6,))) +# TODO check that you're there instead of a sleep +#time.sleep(3) + +#exit() +update_rate = 500 +dt = 1.0 / update_rate +JOINT_ID = 6 + +kp = 100 +acceleration = 0.15 + +print("starting the trajectory") +for i in range(N_ITER): + start = time.time() +#while True: + dmp.step(dt) + q = np.array(rtde_receive.getActualQ()) + dq = np.array(rtde_receive.getActualQd()) + #print("dq:", dq) + vel_cmd = dmp.vel + kp * (dmp.pos - q.reshape((6,1))) + #print("dmp.vel", dmp.vel.reshape((6,))) + #print("dmp.pos", dmp.pos.reshape((6,))) + #print("q:", q) + #print("vel_cmd", vel_cmd.reshape((6,))) + vel_cmd = np.clip(vel_cmd, -2.0, 2.0) + if np.isnan(vel_cmd[0][0]): + break + exit() + #rtde_control.speedJ(vel_cmd, 0.1, 1.0 / 500) + rtde_control.speedJ(vel_cmd, acceleration, dt) + + qs[i] = q.reshape((6,)) + dmp_poss[i] = dmp.pos.reshape((6,)) + dqs[i] = dq.reshape((6,)) + dmp_vels[i] = dmp.vel.reshape((6,)) + end = time.time() + diff = end - start + print(diff) + try: + time.sleep(dt - diff) + except ValueError: + print("it took", dt - (end - start), "more than", dt, "seconds") + +handler(None, None) + + #print(vel_cmd[0][0]) + + + diff --git a/dmp/my_sol/test_traj_w_movej.py b/dmp/my_sol/test_traj_w_movej.py new file mode 100644 index 0000000000000000000000000000000000000000..83e2eb2aa40c81ce90870ca4728893c3722a61d1 --- /dev/null +++ b/dmp/my_sol/test_traj_w_movej.py @@ -0,0 +1,35 @@ +from create_dmp import DMP +from rtde_control import RTDEControlInterface as RTDEControl +from rtde_receive import RTDEReceiveInterface as RTDEReceive +from robotiq_gripper import RobotiqGripper +import pinocchio as pin +import numpy as np +import os +import time +import signal +import matplotlib.pyplot as plt + + +#urdf_path_relative = "../../robot_descriptions/urdf/ur5e_with_robotiq_hande.urdf" +#urdf_path_absolute = os.path.abspath(urdf_path_relative) +#mesh_dir = "../../robot_descriptions/" +#mesh_dir_absolute = os.path.abspath(mesh_dir) +##print(mesh_dir_absolute) +#model = pin.buildModelFromUrdf(urdf_path_absolute) +##print(model) +#data = pin.Data(model) +##print(data) + +rtde_control = RTDEControl("192.168.1.102") +rtde_receive = RTDEReceive("192.168.1.102") + +trajectory_loadpath = './ur10_omega_trajectory.csv' +data = np.genfromtxt(trajectory_loadpath, delimiter=',') +time = data[:, 0] +time = time.reshape(1, len(time)) +y = np.array(data[:, 1:]) + +for i in range(len(y)): + if i % 100 == 0: + rtde_control.moveJ(y[i]) + diff --git a/dmp/my_sol/test_traj_w_speedj.py b/dmp/my_sol/test_traj_w_speedj.py new file mode 100644 index 0000000000000000000000000000000000000000..c00dc8eca82ee5ba4e62492873dc0b0be4da53aa --- /dev/null +++ b/dmp/my_sol/test_traj_w_speedj.py @@ -0,0 +1,42 @@ +from create_dmp import DMP +from rtde_control import RTDEControlInterface as RTDEControl +from rtde_receive import RTDEReceiveInterface as RTDEReceive +from robotiq_gripper import RobotiqGripper +import pinocchio as pin +import numpy as np +import os +import time +import signal +import matplotlib.pyplot as plt + + +#urdf_path_relative = "../../robot_descriptions/urdf/ur5e_with_robotiq_hande.urdf" +#urdf_path_absolute = os.path.abspath(urdf_path_relative) +#mesh_dir = "../../robot_descriptions/" +#mesh_dir_absolute = os.path.abspath(mesh_dir) +##print(mesh_dir_absolute) +#model = pin.buildModelFromUrdf(urdf_path_absolute) +##print(model) +#data = pin.Data(model) +##print(data) + +rtde_control = RTDEControl("192.168.1.102") +rtde_receive = RTDEReceive("192.168.1.102") + +trajectory_loadpath = './ur10_omega_trajectory.csv' +data = np.genfromtxt(trajectory_loadpath, delimiter=',') +t = data[:, 0] +t = t.reshape(1, len(t)) +y = np.array(data[:, 1:]).T + +n = y.shape[0] +yd_demo = (y[:, 1:] - y[:, :-1]) / (t[0, 1:] - t[0, :-1]) +yd_demo = np.concatenate((yd_demo, np.zeros((n, 1))), axis=1) +#print(yd_demo) +rtde_control.moveJ(y[:,0]) +for i in range(yd_demo.shape[1]): + start = time.time() + rtde_control.speedJ(y[:,i], 0.1, 1/500) + end = time.time() + diff = end - start + time.sleep(diff) diff --git a/dmp/my_sol/ur10_omega_trajectory.csv b/dmp/my_sol/ur10_omega_trajectory.csv new file mode 100644 index 0000000000000000000000000000000000000000..98f354af6ebcb0d442145ae44295c93e21b6c239 --- /dev/null +++ b/dmp/my_sol/ur10_omega_trajectory.csv @@ -0,0 +1,10001 @@ +0,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.001,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.002,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.003,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.004,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.005,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.006,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.007,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.008,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.009,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.01,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.011,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.012,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.013,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.014,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.015,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.016,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.017,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.018,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.019,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.02,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.021,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.022,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.023,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.024,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.025,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.026,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.027,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.028,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.029,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.03,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.031,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.032,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.033,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.034,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.035,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.036,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.037,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.038,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.039,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.04,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.041,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.042,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.043,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.044,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.045,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.046,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.047,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.048,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.049,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.05,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.051,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.052,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.053,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.054,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.055,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.056,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.057,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.058,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.059,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.06,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.061,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.062,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.063,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.064,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.065,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.066,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.067,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.068,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.069,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.07,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.071,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.072,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.073,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.074,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.075,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.076,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.077,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.078,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.079,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.08,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.081,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.082,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.083,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.084,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.085,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.086,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.087,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.088,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.089,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.09,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.091,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.092,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.093,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.094,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.095,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.096,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.097,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.098,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.099,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.1,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.101,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.102,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.103,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.104,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.105,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.106,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.107,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.108,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.109,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.11,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.111,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.112,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.113,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.114,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.115,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.116,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.117,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.118,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.119,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.12,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.121,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.122,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.123,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.124,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.125,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.126,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.127,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.128,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.129,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.13,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.131,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.132,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.133,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.134,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.135,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.136,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.137,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.138,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.139,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.14,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.141,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.142,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.143,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.144,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.145,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.146,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.147,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.148,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.149,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.15,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.151,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.152,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.153,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.154,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.155,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.156,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.157,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.158,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.159,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.16,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.161,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.162,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.163,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.164,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.165,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.166,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.167,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.168,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.169,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.17,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.171,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.172,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.173,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.174,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.175,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.176,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.177,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.178,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.179,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.18,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.181,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.182,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.183,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.184,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.185,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.186,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.187,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.188,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.189,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.19,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.191,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.192,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.193,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.194,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.195,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.196,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.197,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.198,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.199,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.2,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.201,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.202,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.203,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.204,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.205,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.206,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.207,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.208,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.209,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.21,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.211,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.212,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.213,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.214,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.215,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.216,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.217,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.218,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.219,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.22,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.221,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.222,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.223,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.224,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.225,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.226,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.227,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.228,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.229,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.23,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.231,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.232,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.233,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.234,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.235,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.236,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.237,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.238,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.239,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.24,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.241,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.242,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.243,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.244,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.245,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.246,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.247,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.248,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.249,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.25,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.251,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.252,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.253,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.254,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.255,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.256,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.257,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.258,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.259,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.26,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.261,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.262,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.263,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.264,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.265,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.266,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.267,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.268,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.269,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.27,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.271,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.272,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.273,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.274,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.275,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.276,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.277,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.278,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.279,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.28,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.281,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.282,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.283,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.284,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.285,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.286,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.287,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.288,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.289,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.29,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.291,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.292,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.293,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.294,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.295,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.296,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.297,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.298,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.299,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.3,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.301,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.302,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.303,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.304,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.305,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.306,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.307,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.308,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.309,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.31,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.311,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.312,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.313,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.314,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.315,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.316,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.317,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.318,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.319,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.32,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.321,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.322,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.323,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.324,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.325,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.326,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.327,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.328,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.329,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.33,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.331,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.332,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.333,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.334,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.335,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.336,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.337,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.338,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.339,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.34,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.341,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.342,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.343,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.344,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.345,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.346,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.347,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.348,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.349,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.35,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.351,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.352,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.353,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.354,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.355,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.356,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.357,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.358,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.359,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.36,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.361,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.362,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.363,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.364,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.365,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.366,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.367,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.368,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.369,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.37,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.371,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.372,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.373,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.374,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.375,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.376,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.377,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.378,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.379,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.38,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.381,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.382,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.383,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.384,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.385,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.386,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.387,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.388,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.389,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.39,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.391,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.392,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.393,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.394,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.395,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.396,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.397,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.398,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.399,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.4,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.401,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.402,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.403,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.404,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.405,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.406,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.407,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.408,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.409,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.41,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.411,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.412,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.413,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.414,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.415,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.416,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.417,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.418,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.419,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.42,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.421,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.422,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.423,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.424,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.425,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.426,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.427,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.428,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.429,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.43,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.431,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.432,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.433,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.434,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.435,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.436,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.437,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.438,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.439,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.44,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.441,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.442,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.443,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.444,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.445,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.446,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.447,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.448,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.449,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.45,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.451,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.452,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.453,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.454,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.455,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.456,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.457,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.458,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.459,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.46,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.461,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.462,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.463,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.464,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.465,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.466,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.467,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.468,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.469,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.47,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.471,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.472,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.473,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.474,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.475,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.476,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.477,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.478,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.479,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.48,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.481,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.482,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.483,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.484,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.485,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.486,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.487,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.488,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.489,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.49,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.491,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.492,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.493,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.494,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.495,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.496,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.497,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.498,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.499,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.5,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.501,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.502,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.503,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.504,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.505,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.506,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.507,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.508,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.509,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.51,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.511,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.512,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.513,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.514,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.515,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.516,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.517,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.518,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.519,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.52,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.521,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.522,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.523,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.524,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.525,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.526,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.527,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.528,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.529,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.53,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.531,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.532,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.533,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.534,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.535,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.536,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.537,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.538,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.539,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.54,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.541,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.542,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.543,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.544,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.545,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.546,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.547,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.548,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.549,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.55,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.551,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.552,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.553,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.554,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.555,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.556,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.557,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.558,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.559,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.56,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.561,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.562,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.563,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.564,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.565,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.566,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.567,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.568,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.569,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.57,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.571,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.572,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.573,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.574,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.575,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.576,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.577,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.578,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.579,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.58,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.581,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.582,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.583,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.584,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.585,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.586,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.587,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.588,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.589,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.59,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.591,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.592,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.593,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.594,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.595,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.596,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.597,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.598,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.599,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.6,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.601,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.602,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.603,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.604,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.605,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.606,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.607,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.608,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.609,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.61,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.611,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.612,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.613,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.614,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.615,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.616,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.617,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.618,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.619,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.62,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.621,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.622,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.623,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.624,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.625,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.626,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.627,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.628,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.629,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.63,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.631,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.632,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.633,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.634,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.635,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.636,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.637,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.638,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.639,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.64,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.641,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.642,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.643,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.644,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.645,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.646,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.647,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.648,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.649,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.65,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.651,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.652,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.653,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.654,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.655,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.656,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.657,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.658,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.659,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.66,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.661,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.662,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.663,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.664,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.665,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.666,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.667,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.668,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.669,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.67,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.671,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.672,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.673,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.674,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.675,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.676,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.677,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.678,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.679,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.68,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.681,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.682,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.683,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.684,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.685,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.686,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.687,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.688,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.689,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.69,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.691,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.692,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.693,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.694,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.695,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.696,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.697,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.698,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.699,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.7,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.701,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.702,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.703,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.704,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.705,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.706,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.707,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.708,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.709,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.71,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.711,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.712,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.713,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.714,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.715,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.716,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.717,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.718,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.719,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.72,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.721,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.722,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.723,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.724,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.725,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.726,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.727,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.728,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.729,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.73,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.731,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.732,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.733,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.734,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.735,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.736,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.737,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.738,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.739,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.74,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.741,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.742,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.743,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.744,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.745,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.746,-2.0859,-2.0857,-1.8438,0.78783,2.0859,0 +0.747,-2.0859,-2.0857,-1.8438,0.78784,2.0859,0 +0.748,-2.0859,-2.0856,-1.8438,0.78784,2.0859,0 +0.749,-2.0859,-2.0856,-1.8438,0.78784,2.0859,0 +0.75,-2.0859,-2.0856,-1.8438,0.78785,2.0859,0 +0.751,-2.0859,-2.0856,-1.8438,0.78786,2.0859,0 +0.752,-2.0858,-2.0856,-1.8438,0.78786,2.0858,0 +0.753,-2.0858,-2.0856,-1.8439,0.78787,2.0858,0 +0.754,-2.0858,-2.0856,-1.8439,0.78788,2.0858,0 +0.755,-2.0858,-2.0856,-1.8439,0.78789,2.0858,0 +0.756,-2.0858,-2.0856,-1.8439,0.7879,2.0858,0 +0.757,-2.0858,-2.0856,-1.8439,0.78791,2.0858,0 +0.758,-2.0857,-2.0855,-1.844,0.78792,2.0857,0 +0.759,-2.0857,-2.0855,-1.844,0.78792,2.0857,0 +0.76,-2.0857,-2.0855,-1.844,0.78793,2.0857,0 +0.761,-2.0857,-2.0855,-1.844,0.78794,2.0857,0 +0.762,-2.0857,-2.0855,-1.844,0.78795,2.0857,0 +0.763,-2.0856,-2.0855,-1.8441,0.78796,2.0856,0 +0.764,-2.0856,-2.0855,-1.8441,0.78797,2.0856,0 +0.765,-2.0856,-2.0855,-1.8441,0.78798,2.0856,0 +0.766,-2.0856,-2.0855,-1.8441,0.78799,2.0856,0 +0.767,-2.0856,-2.0854,-1.8441,0.78799,2.0856,0 +0.768,-2.0856,-2.0854,-1.8442,0.788,2.0856,0 +0.769,-2.0855,-2.0854,-1.8442,0.78801,2.0855,0 +0.77,-2.0855,-2.0854,-1.8442,0.78802,2.0855,0 +0.771,-2.0855,-2.0854,-1.8442,0.78803,2.0855,0 +0.772,-2.0855,-2.0854,-1.8442,0.78804,2.0855,0 +0.773,-2.0855,-2.0854,-1.8443,0.78805,2.0855,0 +0.774,-2.0855,-2.0854,-1.8443,0.78806,2.0855,0 +0.775,-2.0854,-2.0853,-1.8443,0.78806,2.0854,0 +0.776,-2.0854,-2.0853,-1.8443,0.78807,2.0854,0 +0.777,-2.0854,-2.0853,-1.8444,0.78808,2.0854,0 +0.778,-2.0854,-2.0853,-1.8444,0.78809,2.0854,0 +0.779,-2.0854,-2.0853,-1.8444,0.7881,2.0854,0 +0.78,-2.0854,-2.0853,-1.8444,0.78811,2.0854,0 +0.781,-2.0853,-2.0853,-1.8444,0.78812,2.0853,0 +0.782,-2.0853,-2.0853,-1.8445,0.78813,2.0853,0 +0.783,-2.0853,-2.0853,-1.8445,0.78813,2.0853,0 +0.784,-2.0853,-2.0852,-1.8445,0.78814,2.0853,0 +0.785,-2.0853,-2.0852,-1.8445,0.78815,2.0853,0 +0.786,-2.0852,-2.0852,-1.8445,0.78816,2.0852,0 +0.787,-2.0852,-2.0852,-1.8446,0.78818,2.0852,0 +0.788,-2.0852,-2.0852,-1.8446,0.7882,2.0852,0 +0.789,-2.0851,-2.0851,-1.8447,0.78822,2.0851,0 +0.79,-2.0851,-2.0851,-1.8447,0.78824,2.0851,0 +0.791,-2.085,-2.0851,-1.8448,0.78827,2.085,0 +0.792,-2.085,-2.085,-1.8449,0.7883,2.085,0 +0.793,-2.0849,-2.085,-1.8449,0.78833,2.0849,0 +0.794,-2.0848,-2.0849,-1.845,0.78837,2.0848,0 +0.795,-2.0848,-2.0849,-1.8451,0.7884,2.0848,0 +0.796,-2.0847,-2.0848,-1.8452,0.78844,2.0847,0 +0.797,-2.0846,-2.0848,-1.8453,0.78848,2.0846,0 +0.798,-2.0845,-2.0847,-1.8454,0.78852,2.0845,0 +0.799,-2.0845,-2.0847,-1.8455,0.78856,2.0845,0 +0.8,-2.0844,-2.0846,-1.8456,0.7886,2.0844,0 +0.801,-2.0843,-2.0846,-1.8457,0.78864,2.0843,0 +0.802,-2.0842,-2.0845,-1.8457,0.78868,2.0842,0 +0.803,-2.0841,-2.0845,-1.8458,0.78871,2.0841,0 +0.804,-2.0841,-2.0844,-1.8459,0.78875,2.0841,0 +0.805,-2.084,-2.0844,-1.846,0.78879,2.084,0 +0.806,-2.0839,-2.0843,-1.8461,0.78883,2.0839,0 +0.807,-2.0838,-2.0843,-1.8462,0.78887,2.0838,0 +0.808,-2.0838,-2.0842,-1.8463,0.78891,2.0838,0 +0.809,-2.0837,-2.0842,-1.8464,0.78895,2.0837,0 +0.81,-2.0836,-2.0841,-1.8465,0.78898,2.0836,0 +0.811,-2.0835,-2.0841,-1.8466,0.78902,2.0835,0 +0.812,-2.0834,-2.084,-1.8466,0.78906,2.0834,0 +0.813,-2.0834,-2.084,-1.8467,0.7891,2.0834,0 +0.814,-2.0833,-2.0839,-1.8468,0.78914,2.0833,0 +0.815,-2.0832,-2.0839,-1.8469,0.78918,2.0832,0 +0.816,-2.0831,-2.0838,-1.847,0.78922,2.0831,0 +0.817,-2.0831,-2.0837,-1.8471,0.78926,2.0831,0 +0.818,-2.083,-2.0837,-1.8472,0.78929,2.083,0 +0.819,-2.0829,-2.0836,-1.8473,0.78933,2.0829,0 +0.82,-2.0828,-2.0836,-1.8474,0.78937,2.0828,0 +0.821,-2.0827,-2.0835,-1.8475,0.78941,2.0827,0 +0.822,-2.0827,-2.0835,-1.8476,0.78945,2.0827,0 +0.823,-2.0826,-2.0834,-1.8476,0.78949,2.0826,0 +0.824,-2.0825,-2.0834,-1.8477,0.78953,2.0825,0 +0.825,-2.0824,-2.0833,-1.8478,0.78956,2.0824,0 +0.826,-2.0824,-2.0833,-1.8479,0.7896,2.0824,0 +0.827,-2.0823,-2.0832,-1.848,0.78964,2.0823,0 +0.828,-2.0822,-2.0832,-1.8481,0.78968,2.0822,0 +0.829,-2.0821,-2.0831,-1.8482,0.78973,2.0821,0 +0.83,-2.082,-2.083,-1.8484,0.78977,2.082,0 +0.831,-2.0819,-2.0829,-1.8485,0.78982,2.0819,0 +0.832,-2.0817,-2.0828,-1.8486,0.78987,2.0817,0 +0.833,-2.0816,-2.0827,-1.8488,0.78992,2.0816,0 +0.834,-2.0815,-2.0826,-1.8489,0.78997,2.0815,0 +0.835,-2.0813,-2.0825,-1.8491,0.79003,2.0813,0 +0.836,-2.0812,-2.0824,-1.8493,0.79008,2.0812,0 +0.837,-2.081,-2.0823,-1.8495,0.79014,2.081,0 +0.838,-2.0808,-2.0822,-1.8496,0.7902,2.0808,0 +0.839,-2.0807,-2.082,-1.8498,0.79025,2.0807,0 +0.84,-2.0805,-2.0819,-1.85,0.79031,2.0805,0 +0.841,-2.0804,-2.0818,-1.8502,0.79037,2.0804,0 +0.842,-2.0802,-2.0817,-1.8504,0.79042,2.0802,0 +0.843,-2.08,-2.0815,-1.8505,0.79048,2.08,0 +0.844,-2.0799,-2.0814,-1.8507,0.79054,2.0799,0 +0.845,-2.0797,-2.0813,-1.8509,0.79059,2.0797,0 +0.846,-2.0796,-2.0812,-1.8511,0.79065,2.0796,0 +0.847,-2.0794,-2.081,-1.8513,0.79071,2.0794,0 +0.848,-2.0792,-2.0809,-1.8514,0.79077,2.0792,0 +0.849,-2.0791,-2.0808,-1.8516,0.79082,2.0791,0 +0.85,-2.0789,-2.0807,-1.8518,0.79088,2.0789,0 +0.851,-2.0787,-2.0805,-1.852,0.79094,2.0787,0 +0.852,-2.0786,-2.0804,-1.8522,0.79099,2.0786,0 +0.853,-2.0784,-2.0803,-1.8523,0.79105,2.0784,0 +0.854,-2.0783,-2.0802,-1.8525,0.79111,2.0783,0 +0.855,-2.0781,-2.08,-1.8527,0.79116,2.0781,0 +0.856,-2.0779,-2.0799,-1.8529,0.79122,2.0779,0 +0.857,-2.0778,-2.0798,-1.8531,0.79128,2.0778,0 +0.858,-2.0776,-2.0797,-1.8533,0.79133,2.0776,0 +0.859,-2.0775,-2.0796,-1.8534,0.79139,2.0775,0 +0.86,-2.0773,-2.0794,-1.8536,0.79145,2.0773,0 +0.861,-2.0771,-2.0793,-1.8538,0.79151,2.0771,0 +0.862,-2.077,-2.0792,-1.854,0.79156,2.077,0 +0.863,-2.0768,-2.0791,-1.8542,0.79162,2.0768,0 +0.864,-2.0767,-2.0789,-1.8543,0.79168,2.0767,0 +0.865,-2.0765,-2.0788,-1.8545,0.79173,2.0765,0 +0.866,-2.0763,-2.0787,-1.8547,0.79179,2.0763,0 +0.867,-2.0762,-2.0786,-1.8549,0.79185,2.0762,0 +0.868,-2.076,-2.0784,-1.8551,0.7919,2.076,0 +0.869,-2.0758,-2.0783,-1.8552,0.79196,2.0758,0 +0.87,-2.0757,-2.0782,-1.8554,0.79201,2.0757,0 +0.871,-2.0755,-2.0781,-1.8556,0.79207,2.0755,0 +0.872,-2.0754,-2.078,-1.8558,0.79212,2.0754,0 +0.873,-2.0752,-2.0778,-1.8559,0.79217,2.0752,0 +0.874,-2.0751,-2.0777,-1.8561,0.79223,2.0751,0 +0.875,-2.0749,-2.0776,-1.8563,0.79228,2.0749,0 +0.876,-2.0748,-2.0775,-1.8564,0.79233,2.0748,0 +0.877,-2.0746,-2.0774,-1.8566,0.79237,2.0746,0 +0.878,-2.0745,-2.0773,-1.8568,0.79242,2.0745,0 +0.879,-2.0743,-2.0772,-1.8569,0.79247,2.0743,0 +0.88,-2.0742,-2.077,-1.8571,0.79252,2.0742,0 +0.881,-2.074,-2.0769,-1.8572,0.79257,2.074,0 +0.882,-2.0739,-2.0768,-1.8574,0.79261,2.0739,0 +0.883,-2.0737,-2.0767,-1.8576,0.79266,2.0737,0 +0.884,-2.0736,-2.0766,-1.8577,0.79271,2.0736,0 +0.885,-2.0735,-2.0765,-1.8579,0.79276,2.0735,0 +0.886,-2.0733,-2.0764,-1.858,0.79281,2.0733,0 +0.887,-2.0732,-2.0763,-1.8582,0.79285,2.0732,0 +0.888,-2.073,-2.0761,-1.8584,0.7929,2.073,0 +0.889,-2.0729,-2.076,-1.8585,0.79295,2.0729,0 +0.89,-2.0727,-2.0759,-1.8587,0.793,2.0727,0 +0.891,-2.0726,-2.0758,-1.8588,0.79305,2.0726,0 +0.892,-2.0724,-2.0757,-1.859,0.79309,2.0724,0 +0.893,-2.0723,-2.0756,-1.8592,0.79314,2.0723,0 +0.894,-2.0721,-2.0755,-1.8593,0.79319,2.0721,0 +0.895,-2.072,-2.0753,-1.8595,0.79324,2.072,0 +0.896,-2.0718,-2.0752,-1.8596,0.79329,2.0718,0 +0.897,-2.0717,-2.0751,-1.8598,0.79333,2.0717,0 +0.898,-2.0716,-2.075,-1.86,0.79338,2.0716,0 +0.899,-2.0714,-2.0749,-1.8601,0.79343,2.0714,0 +0.9,-2.0713,-2.0748,-1.8603,0.79348,2.0713,0 +0.901,-2.0711,-2.0747,-1.8604,0.79353,2.0711,0 +0.902,-2.071,-2.0746,-1.8606,0.79358,2.071,0 +0.903,-2.0708,-2.0744,-1.8608,0.79362,2.0708,0 +0.904,-2.0707,-2.0743,-1.8609,0.79367,2.0707,0 +0.905,-2.0705,-2.0742,-1.8611,0.79372,2.0705,0 +0.906,-2.0704,-2.0741,-1.8612,0.79377,2.0704,0 +0.907,-2.0702,-2.074,-1.8614,0.79382,2.0702,0 +0.908,-2.0701,-2.0739,-1.8616,0.79386,2.0701,0 +0.909,-2.0699,-2.0738,-1.8617,0.79391,2.0699,0 +0.91,-2.0698,-2.0737,-1.8619,0.79396,2.0698,0 +0.911,-2.0696,-2.0735,-1.8621,0.79401,2.0696,0 +0.912,-2.0695,-2.0734,-1.8622,0.79406,2.0695,0 +0.913,-2.0693,-2.0733,-1.8624,0.79411,2.0693,0 +0.914,-2.0691,-2.0731,-1.8626,0.79416,2.0691,0 +0.915,-2.069,-2.073,-1.8628,0.7942,2.069,0 +0.916,-2.0688,-2.0729,-1.863,0.79425,2.0688,0 +0.917,-2.0686,-2.0727,-1.8632,0.79431,2.0686,0 +0.918,-2.0684,-2.0725,-1.8634,0.79436,2.0684,0 +0.919,-2.0682,-2.0724,-1.8636,0.79441,2.0682,0 +0.92,-2.068,-2.0722,-1.8638,0.79446,2.068,0 +0.921,-2.0678,-2.072,-1.8641,0.79451,2.0678,0 +0.922,-2.0676,-2.0719,-1.8643,0.79456,2.0676,0 +0.923,-2.0674,-2.0717,-1.8645,0.79461,2.0674,0 +0.924,-2.0672,-2.0715,-1.8647,0.79466,2.0672,0 +0.925,-2.067,-2.0714,-1.8649,0.79471,2.067,0 +0.926,-2.0668,-2.0712,-1.8651,0.79476,2.0668,0 +0.927,-2.0665,-2.071,-1.8654,0.79482,2.0665,0 +0.928,-2.0663,-2.0709,-1.8656,0.79487,2.0663,0 +0.929,-2.0661,-2.0707,-1.8658,0.79492,2.0661,0 +0.93,-2.0659,-2.0706,-1.866,0.79497,2.0659,0 +0.931,-2.0657,-2.0704,-1.8662,0.79502,2.0657,0 +0.932,-2.0655,-2.0702,-1.8664,0.79507,2.0655,0 +0.933,-2.0653,-2.0701,-1.8667,0.79512,2.0653,0 +0.934,-2.0651,-2.0699,-1.8669,0.79517,2.0651,0 +0.935,-2.0649,-2.0697,-1.8671,0.79522,2.0649,0 +0.936,-2.0647,-2.0696,-1.8673,0.79527,2.0647,0 +0.937,-2.0645,-2.0694,-1.8675,0.79533,2.0645,0 +0.938,-2.0643,-2.0692,-1.8677,0.79538,2.0643,0 +0.939,-2.0641,-2.0691,-1.868,0.79543,2.0641,0 +0.94,-2.0639,-2.0689,-1.8682,0.79548,2.0639,0 +0.941,-2.0637,-2.0687,-1.8684,0.79553,2.0637,0 +0.942,-2.0635,-2.0686,-1.8686,0.79558,2.0635,0 +0.943,-2.0633,-2.0684,-1.8688,0.79563,2.0633,0 +0.944,-2.0631,-2.0682,-1.869,0.79568,2.0631,0 +0.945,-2.0629,-2.0681,-1.8693,0.79573,2.0629,0 +0.946,-2.0627,-2.0679,-1.8695,0.79578,2.0627,0 +0.947,-2.0625,-2.0677,-1.8697,0.79584,2.0625,0 +0.948,-2.0623,-2.0676,-1.8699,0.79589,2.0623,0 +0.949,-2.0621,-2.0674,-1.8701,0.79594,2.0621,0 +0.95,-2.0618,-2.0672,-1.8703,0.79599,2.0618,0 +0.951,-2.0616,-2.0671,-1.8706,0.79604,2.0616,0 +0.952,-2.0614,-2.0669,-1.8708,0.7961,2.0614,0 +0.953,-2.0612,-2.0667,-1.871,0.79615,2.0612,0 +0.954,-2.061,-2.0665,-1.8713,0.79622,2.061,0 +0.955,-2.0607,-2.0664,-1.8715,0.79628,2.0607,0 +0.956,-2.0605,-2.0662,-1.8718,0.79635,2.0605,0 +0.957,-2.0602,-2.066,-1.872,0.79642,2.0602,0 +0.958,-2.06,-2.0658,-1.8723,0.7965,2.06,0 +0.959,-2.0597,-2.0656,-1.8726,0.79658,2.0597,0 +0.96,-2.0594,-2.0653,-1.8729,0.79666,2.0594,0 +0.961,-2.0591,-2.0651,-1.8732,0.79674,2.0591,0 +0.962,-2.0588,-2.0649,-1.8735,0.79683,2.0588,0 +0.963,-2.0586,-2.0647,-1.8738,0.79692,2.0586,0 +0.964,-2.0583,-2.0645,-1.8741,0.797,2.0583,0 +0.965,-2.058,-2.0643,-1.8744,0.79709,2.058,0 +0.966,-2.0577,-2.0641,-1.8747,0.79717,2.0577,0 +0.967,-2.0574,-2.0638,-1.875,0.79726,2.0574,0 +0.968,-2.0571,-2.0636,-1.8753,0.79734,2.0571,0 +0.969,-2.0568,-2.0634,-1.8756,0.79743,2.0568,0 +0.97,-2.0565,-2.0632,-1.8759,0.79751,2.0565,0 +0.971,-2.0562,-2.063,-1.8762,0.7976,2.0562,0 +0.972,-2.056,-2.0628,-1.8765,0.79768,2.056,0 +0.973,-2.0557,-2.0625,-1.8768,0.79777,2.0557,0 +0.974,-2.0554,-2.0623,-1.8771,0.79785,2.0554,0 +0.975,-2.0551,-2.0621,-1.8774,0.79794,2.0551,0 +0.976,-2.0548,-2.0619,-1.8777,0.79803,2.0548,0 +0.977,-2.0545,-2.0617,-1.878,0.79811,2.0545,0 +0.978,-2.0542,-2.0615,-1.8783,0.7982,2.0542,0 +0.979,-2.0539,-2.0613,-1.8786,0.79828,2.0539,0 +0.98,-2.0537,-2.061,-1.8789,0.79837,2.0537,0 +0.981,-2.0534,-2.0608,-1.8792,0.79845,2.0534,0 +0.982,-2.0531,-2.0606,-1.8795,0.79854,2.0531,0 +0.983,-2.0528,-2.0604,-1.8798,0.79862,2.0528,0 +0.984,-2.0525,-2.0602,-1.8801,0.79871,2.0525,0 +0.985,-2.0522,-2.06,-1.8804,0.79879,2.0522,0 +0.986,-2.0519,-2.0597,-1.8807,0.79888,2.0519,0 +0.987,-2.0516,-2.0595,-1.881,0.79896,2.0516,0 +0.988,-2.0514,-2.0593,-1.8813,0.79905,2.0514,0 +0.989,-2.0511,-2.0591,-1.8816,0.79913,2.0511,0 +0.99,-2.0508,-2.0589,-1.8819,0.79922,2.0508,0 +0.991,-2.0505,-2.0587,-1.8822,0.79931,2.0505,0 +0.992,-2.0502,-2.0585,-1.8825,0.79939,2.0502,0 +0.993,-2.0499,-2.0582,-1.8828,0.79948,2.0499,0 +0.994,-2.0496,-2.058,-1.8831,0.79956,2.0496,0 +0.995,-2.0493,-2.0578,-1.8835,0.79965,2.0493,0 +0.996,-2.049,-2.0575,-1.8838,0.79974,2.049,0 +0.997,-2.0487,-2.0573,-1.8841,0.79982,2.0487,0 +0.998,-2.0483,-2.057,-1.8845,0.79991,2.0483,0 +0.999,-2.048,-2.0568,-1.8848,0.8,2.048,0 +1,-2.0477,-2.0565,-1.8851,0.80009,2.0477,0 +1.001,-2.0473,-2.0563,-1.8855,0.80017,2.0473,0 +1.002,-2.0469,-2.056,-1.8859,0.80026,2.0469,0 +1.003,-2.0466,-2.0557,-1.8862,0.80035,2.0466,0 +1.004,-2.0462,-2.0554,-1.8866,0.80044,2.0462,0 +1.005,-2.0458,-2.0552,-1.887,0.80053,2.0458,0 +1.006,-2.0455,-2.0549,-1.8873,0.80062,2.0455,0 +1.007,-2.0451,-2.0546,-1.8877,0.80071,2.0451,0 +1.008,-2.0448,-2.0543,-1.888,0.8008,2.0448,0 +1.009,-2.0444,-2.0541,-1.8884,0.80089,2.0444,0 +1.01,-2.044,-2.0538,-1.8888,0.80098,2.044,0 +1.011,-2.0437,-2.0535,-1.8891,0.80106,2.0437,0 +1.012,-2.0433,-2.0533,-1.8895,0.80115,2.0433,0 +1.013,-2.0429,-2.053,-1.8899,0.80124,2.0429,0 +1.014,-2.0426,-2.0527,-1.8902,0.80133,2.0426,0 +1.015,-2.0422,-2.0524,-1.8906,0.80142,2.0422,0 +1.016,-2.0419,-2.0522,-1.8909,0.80151,2.0419,0 +1.017,-2.0415,-2.0519,-1.8913,0.8016,2.0415,0 +1.018,-2.0411,-2.0516,-1.8917,0.80169,2.0411,0 +1.019,-2.0408,-2.0513,-1.892,0.80178,2.0408,0 +1.02,-2.0404,-2.0511,-1.8924,0.80187,2.0404,0 +1.021,-2.04,-2.0508,-1.8928,0.80195,2.04,0 +1.022,-2.0397,-2.0505,-1.8931,0.80204,2.0397,0 +1.023,-2.0393,-2.0502,-1.8935,0.80213,2.0393,0 +1.024,-2.039,-2.05,-1.8938,0.80222,2.039,0 +1.025,-2.0386,-2.0497,-1.8942,0.80231,2.0386,0 +1.026,-2.0382,-2.0494,-1.8946,0.8024,2.0382,0 +1.027,-2.0379,-2.0491,-1.8949,0.80249,2.0379,0 +1.028,-2.0375,-2.0489,-1.8953,0.80258,2.0375,0 +1.029,-2.0371,-2.0486,-1.8957,0.80267,2.0371,0 +1.03,-2.0368,-2.0483,-1.896,0.80276,2.0368,0 +1.031,-2.0364,-2.048,-1.8964,0.80284,2.0364,0 +1.032,-2.036,-2.0478,-1.8968,0.80293,2.036,0 +1.033,-2.0357,-2.0475,-1.8971,0.80302,2.0357,0 +1.034,-2.0353,-2.0472,-1.8975,0.80311,2.0353,0 +1.035,-2.035,-2.0469,-1.8978,0.8032,2.035,0 +1.036,-2.0346,-2.0467,-1.8982,0.80329,2.0346,0 +1.037,-2.0342,-2.0464,-1.8986,0.80338,2.0342,0 +1.038,-2.0338,-2.0461,-1.899,0.80346,2.0338,0 +1.039,-2.0334,-2.0458,-1.8994,0.80355,2.0334,0 +1.04,-2.033,-2.0455,-1.8998,0.80364,2.033,0 +1.041,-2.0326,-2.0452,-1.9002,0.80372,2.0326,0 +1.042,-2.0322,-2.0448,-1.9006,0.80381,2.0322,0 +1.043,-2.0317,-2.0445,-1.901,0.80389,2.0317,0 +1.044,-2.0313,-2.0442,-1.9014,0.80398,2.0313,0 +1.045,-2.0309,-2.0439,-1.9018,0.80406,2.0309,0 +1.046,-2.0304,-2.0436,-1.9022,0.80414,2.0304,0 +1.047,-2.03,-2.0432,-1.9026,0.80423,2.03,0 +1.048,-2.0296,-2.0429,-1.903,0.80431,2.0296,0 +1.049,-2.0292,-2.0426,-1.9034,0.8044,2.0292,0 +1.05,-2.0287,-2.0423,-1.9038,0.80448,2.0287,0 +1.051,-2.0283,-2.0419,-1.9042,0.80457,2.0283,0 +1.052,-2.0279,-2.0416,-1.9046,0.80465,2.0279,0 +1.053,-2.0274,-2.0413,-1.905,0.80473,2.0274,0 +1.054,-2.027,-2.041,-1.9055,0.80482,2.027,0 +1.055,-2.0266,-2.0406,-1.9059,0.8049,2.0266,0 +1.056,-2.0261,-2.0403,-1.9063,0.80499,2.0261,0 +1.057,-2.0257,-2.04,-1.9067,0.80507,2.0257,0 +1.058,-2.0253,-2.0397,-1.9071,0.80516,2.0253,0 +1.059,-2.0249,-2.0393,-1.9075,0.80524,2.0249,0 +1.06,-2.0244,-2.039,-1.9079,0.80532,2.0244,0 +1.061,-2.024,-2.0387,-1.9083,0.80541,2.024,0 +1.062,-2.0236,-2.0384,-1.9087,0.80549,2.0236,0 +1.063,-2.0231,-2.038,-1.9091,0.80558,2.0231,0 +1.064,-2.0227,-2.0377,-1.9095,0.80566,2.0227,0 +1.065,-2.0223,-2.0374,-1.9099,0.80575,2.0223,0 +1.066,-2.0218,-2.0371,-1.9104,0.80583,2.0218,0 +1.067,-2.0214,-2.0367,-1.9108,0.80591,2.0214,0 +1.068,-2.021,-2.0364,-1.9112,0.806,2.021,0 +1.069,-2.0206,-2.0361,-1.9116,0.80608,2.0206,0 +1.07,-2.0201,-2.0358,-1.912,0.80617,2.0201,0 +1.071,-2.0197,-2.0354,-1.9124,0.80625,2.0197,0 +1.072,-2.0193,-2.0351,-1.9128,0.80634,2.0193,0 +1.073,-2.0188,-2.0348,-1.9132,0.80642,2.0188,0 +1.074,-2.0184,-2.0345,-1.9136,0.8065,2.0184,0 +1.075,-2.018,-2.0341,-1.914,0.80659,2.018,0 +1.076,-2.0175,-2.0338,-1.9144,0.80667,2.0175,0 +1.077,-2.0171,-2.0335,-1.9149,0.80676,2.0171,0 +1.078,-2.0166,-2.0332,-1.9153,0.80685,2.0166,0 +1.079,-2.0162,-2.0328,-1.9157,0.80694,2.0162,0 +1.08,-2.0157,-2.0325,-1.9161,0.80703,2.0157,0 +1.081,-2.0153,-2.0321,-1.9166,0.80712,2.0153,0 +1.082,-2.0148,-2.0318,-1.917,0.80722,2.0148,0 +1.083,-2.0143,-2.0314,-1.9175,0.80731,2.0143,0 +1.084,-2.0138,-2.0311,-1.9179,0.80741,2.0138,0 +1.085,-2.0133,-2.0307,-1.9184,0.80751,2.0133,0 +1.086,-2.0128,-2.0304,-1.9188,0.80761,2.0128,0 +1.087,-2.0123,-2.03,-1.9193,0.80771,2.0123,0 +1.088,-2.0118,-2.0297,-1.9197,0.80781,2.0118,0 +1.089,-2.0113,-2.0293,-1.9202,0.80791,2.0113,0 +1.09,-2.0108,-2.029,-1.9206,0.80801,2.0108,0 +1.091,-2.0103,-2.0286,-1.9211,0.80811,2.0103,0 +1.092,-2.0098,-2.0283,-1.9215,0.80821,2.0098,0 +1.093,-2.0093,-2.0279,-1.922,0.80831,2.0093,0 +1.094,-2.0088,-2.0275,-1.9225,0.80841,2.0088,0 +1.095,-2.0083,-2.0272,-1.9229,0.80851,2.0083,0 +1.096,-2.0078,-2.0268,-1.9234,0.80861,2.0078,0 +1.097,-2.0073,-2.0265,-1.9238,0.80871,2.0073,0 +1.098,-2.0068,-2.0261,-1.9243,0.80881,2.0068,0 +1.099,-2.0063,-2.0258,-1.9247,0.80891,2.0063,0 +1.1,-2.0058,-2.0254,-1.9252,0.809,2.0058,0 +1.101,-2.0053,-2.0251,-1.9256,0.8091,2.0053,0 +1.102,-2.0048,-2.0247,-1.9261,0.8092,2.0048,0 +1.103,-2.0043,-2.0243,-1.9266,0.8093,2.0043,0 +1.104,-2.0038,-2.024,-1.927,0.8094,2.0038,0 +1.105,-2.0033,-2.0236,-1.9275,0.8095,2.0033,0 +1.106,-2.0028,-2.0233,-1.9279,0.8096,2.0028,0 +1.107,-2.0023,-2.0229,-1.9284,0.8097,2.0023,0 +1.108,-2.0018,-2.0226,-1.9288,0.8098,2.0018,0 +1.109,-2.0013,-2.0222,-1.9293,0.8099,2.0013,0 +1.11,-2.0008,-2.0219,-1.9297,0.81,2.0008,0 +1.111,-2.0003,-2.0215,-1.9302,0.8101,2.0003,0 +1.112,-1.9998,-2.0211,-1.9306,0.8102,1.9998,0 +1.113,-1.9993,-2.0208,-1.9311,0.8103,1.9993,0 +1.114,-1.9988,-2.0204,-1.9316,0.8104,1.9988,0 +1.115,-1.9983,-2.0201,-1.932,0.8105,1.9983,0 +1.116,-1.9978,-2.0197,-1.9325,0.8106,1.9978,0 +1.117,-1.9973,-2.0194,-1.9329,0.8107,1.9973,0 +1.118,-1.9967,-2.019,-1.9334,0.8108,1.9967,0 +1.119,-1.9962,-2.0186,-1.9339,0.8109,1.9962,0 +1.12,-1.9957,-2.0183,-1.9343,0.81099,1.9957,0 +1.121,-1.9951,-2.0179,-1.9348,0.81109,1.9951,0 +1.122,-1.9946,-2.0175,-1.9353,0.81119,1.9946,0 +1.123,-1.994,-2.0171,-1.9358,0.81129,1.994,0 +1.124,-1.9934,-2.0167,-1.9363,0.81139,1.9934,0 +1.125,-1.9929,-2.0163,-1.9368,0.81148,1.9929,0 +1.126,-1.9923,-2.0159,-1.9373,0.81158,1.9923,0 +1.127,-1.9917,-2.0155,-1.9378,0.81168,1.9917,0 +1.128,-1.9911,-2.015,-1.9383,0.81177,1.9911,0 +1.129,-1.9904,-2.0146,-1.9388,0.81187,1.9904,0 +1.13,-1.9898,-2.0142,-1.9393,0.81196,1.9898,0 +1.131,-1.9892,-2.0138,-1.9399,0.81206,1.9892,0 +1.132,-1.9886,-2.0134,-1.9404,0.81216,1.9886,0 +1.133,-1.988,-2.013,-1.9409,0.81225,1.988,0 +1.134,-1.9874,-2.0125,-1.9414,0.81235,1.9874,0 +1.135,-1.9868,-2.0121,-1.9419,0.81245,1.9868,0 +1.136,-1.9862,-2.0117,-1.9424,0.81254,1.9862,0 +1.137,-1.9856,-2.0113,-1.9429,0.81264,1.9856,0 +1.138,-1.985,-2.0109,-1.9434,0.81274,1.985,0 +1.139,-1.9844,-2.0105,-1.944,0.81283,1.9844,0 +1.14,-1.9838,-2.01,-1.9445,0.81293,1.9838,0 +1.141,-1.9832,-2.0096,-1.945,0.81303,1.9832,0 +1.142,-1.9826,-2.0092,-1.9455,0.81312,1.9826,0 +1.143,-1.982,-2.0088,-1.946,0.81322,1.982,0 +1.144,-1.9814,-2.0084,-1.9465,0.81331,1.9814,0 +1.145,-1.9808,-2.008,-1.947,0.81341,1.9808,0 +1.146,-1.9802,-2.0076,-1.9475,0.81351,1.9802,0 +1.147,-1.9796,-2.0071,-1.9481,0.8136,1.9796,0 +1.148,-1.979,-2.0067,-1.9486,0.8137,1.979,0 +1.149,-1.9784,-2.0063,-1.9491,0.8138,1.9784,0 +1.15,-1.9778,-2.0059,-1.9496,0.81389,1.9778,0 +1.151,-1.9772,-2.0055,-1.9501,0.81399,1.9772,0 +1.152,-1.9766,-2.0051,-1.9506,0.81409,1.9766,0 +1.153,-1.976,-2.0046,-1.9511,0.81418,1.976,0 +1.154,-1.9754,-2.0042,-1.9516,0.81428,1.9754,0 +1.155,-1.9748,-2.0038,-1.9522,0.81438,1.9748,0 +1.156,-1.9742,-2.0034,-1.9527,0.81447,1.9742,0 +1.157,-1.9736,-2.003,-1.9532,0.81457,1.9736,0 +1.158,-1.973,-2.0026,-1.9537,0.81466,1.973,0 +1.159,-1.9724,-2.0021,-1.9542,0.81476,1.9724,0 +1.16,-1.9718,-2.0017,-1.9547,0.81485,1.9718,0 +1.161,-1.9711,-2.0013,-1.9552,0.81494,1.9711,0 +1.162,-1.9705,-2.0009,-1.9557,0.81502,1.9705,0 +1.163,-1.9699,-2.0004,-1.9563,0.8151,1.9699,0 +1.164,-1.9693,-2,-1.9568,0.81518,1.9693,0 +1.165,-1.9686,-1.9996,-1.9573,0.81526,1.9686,0 +1.166,-1.968,-1.9991,-1.9578,0.81533,1.968,0 +1.167,-1.9674,-1.9987,-1.9583,0.8154,1.9674,0 +1.168,-1.9667,-1.9983,-1.9588,0.81547,1.9667,0 +1.169,-1.9661,-1.9978,-1.9593,0.81554,1.9661,0 +1.17,-1.9654,-1.9974,-1.9598,0.8156,1.9654,0 +1.171,-1.9648,-1.9969,-1.9603,0.81567,1.9648,0 +1.172,-1.9641,-1.9965,-1.9608,0.81574,1.9641,0 +1.173,-1.9635,-1.9961,-1.9613,0.8158,1.9635,0 +1.174,-1.9628,-1.9956,-1.9618,0.81587,1.9628,0 +1.175,-1.9622,-1.9952,-1.9624,0.81594,1.9622,0 +1.176,-1.9616,-1.9947,-1.9629,0.816,1.9616,0 +1.177,-1.9609,-1.9943,-1.9634,0.81607,1.9609,0 +1.178,-1.9603,-1.9938,-1.9639,0.81613,1.9603,0 +1.179,-1.9596,-1.9934,-1.9644,0.8162,1.9596,0 +1.18,-1.959,-1.993,-1.9649,0.81627,1.959,0 +1.181,-1.9583,-1.9925,-1.9654,0.81633,1.9583,0 +1.182,-1.9577,-1.9921,-1.9659,0.8164,1.9577,0 +1.183,-1.957,-1.9916,-1.9664,0.81647,1.957,0 +1.184,-1.9564,-1.9912,-1.9669,0.81653,1.9564,0 +1.185,-1.9557,-1.9908,-1.9674,0.8166,1.9557,0 +1.186,-1.9551,-1.9903,-1.9679,0.81667,1.9551,0 +1.187,-1.9544,-1.9899,-1.9685,0.81673,1.9544,0 +1.188,-1.9538,-1.9894,-1.969,0.8168,1.9538,0 +1.189,-1.9532,-1.989,-1.9695,0.81687,1.9532,0 +1.19,-1.9525,-1.9885,-1.97,0.81693,1.9525,0 +1.191,-1.9519,-1.9881,-1.9705,0.817,1.9519,0 +1.192,-1.9512,-1.9877,-1.971,0.81707,1.9512,0 +1.193,-1.9506,-1.9872,-1.9715,0.81713,1.9506,0 +1.194,-1.9499,-1.9868,-1.972,0.8172,1.9499,0 +1.195,-1.9493,-1.9863,-1.9725,0.81726,1.9493,0 +1.196,-1.9486,-1.9859,-1.973,0.81733,1.9486,0 +1.197,-1.948,-1.9855,-1.9735,0.8174,1.948,0 +1.198,-1.9473,-1.985,-1.974,0.81746,1.9473,0 +1.199,-1.9467,-1.9846,-1.9745,0.81753,1.9467,0 +1.2,-1.9461,-1.9841,-1.9751,0.8176,1.9461,0 +1.201,-1.9454,-1.9837,-1.9756,0.81766,1.9454,0 +1.202,-1.9448,-1.9833,-1.9761,0.81772,1.9448,0 +1.203,-1.9441,-1.9828,-1.9766,0.81778,1.9441,0 +1.204,-1.9434,-1.9824,-1.9771,0.81784,1.9434,0 +1.205,-1.9428,-1.9819,-1.9776,0.8179,1.9428,0 +1.206,-1.9421,-1.9815,-1.978,0.81796,1.9421,0 +1.207,-1.9415,-1.9811,-1.9785,0.81801,1.9415,0 +1.208,-1.9408,-1.9806,-1.979,0.81807,1.9408,0 +1.209,-1.9401,-1.9802,-1.9795,0.81812,1.9401,0 +1.21,-1.9395,-1.9798,-1.98,0.81817,1.9395,0 +1.211,-1.9388,-1.9793,-1.9805,0.81822,1.9388,0 +1.212,-1.9382,-1.9789,-1.981,0.81827,1.9382,0 +1.213,-1.9375,-1.9785,-1.9815,0.81832,1.9375,0 +1.214,-1.9368,-1.978,-1.9819,0.81838,1.9368,0 +1.215,-1.9362,-1.9776,-1.9824,0.81843,1.9362,0 +1.216,-1.9355,-1.9772,-1.9829,0.81848,1.9355,0 +1.217,-1.9348,-1.9767,-1.9834,0.81853,1.9348,0 +1.218,-1.9342,-1.9763,-1.9839,0.81858,1.9342,0 +1.219,-1.9335,-1.9759,-1.9844,0.81863,1.9335,0 +1.22,-1.9328,-1.9754,-1.9849,0.81868,1.9328,0 +1.221,-1.9322,-1.975,-1.9853,0.81873,1.9322,0 +1.222,-1.9315,-1.9745,-1.9858,0.81878,1.9315,0 +1.223,-1.9308,-1.9741,-1.9863,0.81883,1.9308,0 +1.224,-1.9302,-1.9737,-1.9868,0.81888,1.9302,0 +1.225,-1.9295,-1.9732,-1.9873,0.81894,1.9295,0 +1.226,-1.9289,-1.9728,-1.9878,0.81899,1.9289,0 +1.227,-1.9282,-1.9724,-1.9883,0.81904,1.9282,0 +1.228,-1.9275,-1.9719,-1.9887,0.81909,1.9275,0 +1.229,-1.9269,-1.9715,-1.9892,0.81914,1.9269,0 +1.23,-1.9262,-1.9711,-1.9897,0.81919,1.9262,0 +1.231,-1.9255,-1.9706,-1.9902,0.81924,1.9255,0 +1.232,-1.9249,-1.9702,-1.9907,0.81929,1.9249,0 +1.233,-1.9242,-1.9698,-1.9912,0.81934,1.9242,0 +1.234,-1.9235,-1.9693,-1.9917,0.81939,1.9235,0 +1.235,-1.9229,-1.9689,-1.9921,0.81945,1.9229,0 +1.236,-1.9222,-1.9685,-1.9926,0.8195,1.9222,0 +1.237,-1.9215,-1.968,-1.9931,0.81955,1.9215,0 +1.238,-1.9209,-1.9676,-1.9936,0.8196,1.9209,0 +1.239,-1.9202,-1.9672,-1.9941,0.81965,1.9202,0 +1.24,-1.9196,-1.9667,-1.9946,0.8197,1.9196,0 +1.241,-1.9189,-1.9663,-1.9951,0.81975,1.9189,0 +1.242,-1.9182,-1.9659,-1.9955,0.8198,1.9182,0 +1.243,-1.9176,-1.9654,-1.996,0.81985,1.9176,0 +1.244,-1.9169,-1.965,-1.9965,0.81989,1.9169,0 +1.245,-1.9162,-1.9646,-1.997,0.81993,1.9162,0 +1.246,-1.9156,-1.9641,-1.9974,0.81997,1.9156,0 +1.247,-1.9149,-1.9637,-1.9979,0.82001,1.9149,0 +1.248,-1.9143,-1.9633,-1.9983,0.82005,1.9143,0 +1.249,-1.9136,-1.9629,-1.9988,0.82008,1.9136,0 +1.25,-1.913,-1.9625,-1.9992,0.82011,1.913,0 +1.251,-1.9123,-1.962,-1.9997,0.82014,1.9123,0 +1.252,-1.9116,-1.9616,-2.0001,0.82017,1.9116,0 +1.253,-1.911,-1.9612,-2.0006,0.8202,1.911,0 +1.254,-1.9103,-1.9608,-2.001,0.82022,1.9103,0 +1.255,-1.9097,-1.9604,-2.0015,0.82025,1.9097,0 +1.256,-1.909,-1.96,-2.0019,0.82028,1.909,0 +1.257,-1.9084,-1.9596,-2.0023,0.82031,1.9084,0 +1.258,-1.9077,-1.9591,-2.0028,0.82034,1.9077,0 +1.259,-1.9071,-1.9587,-2.0032,0.82037,1.9071,0 +1.26,-1.9064,-1.9583,-2.0037,0.82039,1.9064,0 +1.261,-1.9057,-1.9579,-2.0041,0.82042,1.9057,0 +1.262,-1.9051,-1.9575,-2.0046,0.82045,1.9051,0 +1.263,-1.9044,-1.9571,-2.005,0.82048,1.9044,0 +1.264,-1.9038,-1.9567,-2.0054,0.82051,1.9038,0 +1.265,-1.9031,-1.9562,-2.0059,0.82054,1.9031,0 +1.266,-1.9025,-1.9558,-2.0063,0.82056,1.9025,0 +1.267,-1.9018,-1.9554,-2.0068,0.82059,1.9018,0 +1.268,-1.9012,-1.955,-2.0072,0.82062,1.9012,0 +1.269,-1.9005,-1.9546,-2.0077,0.82065,1.9005,0 +1.27,-1.8999,-1.9542,-2.0081,0.82068,1.8999,0 +1.271,-1.8992,-1.9538,-2.0085,0.82071,1.8992,0 +1.272,-1.8985,-1.9533,-2.009,0.82073,1.8985,0 +1.273,-1.8979,-1.9529,-2.0094,0.82076,1.8979,0 +1.274,-1.8972,-1.9525,-2.0099,0.82079,1.8972,0 +1.275,-1.8966,-1.9521,-2.0103,0.82082,1.8966,0 +1.276,-1.8959,-1.9517,-2.0108,0.82085,1.8959,0 +1.277,-1.8953,-1.9513,-2.0112,0.82088,1.8953,0 +1.278,-1.8946,-1.9508,-2.0116,0.8209,1.8946,0 +1.279,-1.894,-1.9504,-2.0121,0.82093,1.894,0 +1.28,-1.8933,-1.95,-2.0125,0.82096,1.8933,0 +1.281,-1.8926,-1.9496,-2.013,0.82099,1.8926,0 +1.282,-1.892,-1.9492,-2.0134,0.82102,1.892,0 +1.283,-1.8913,-1.9488,-2.0139,0.82105,1.8913,0 +1.284,-1.8907,-1.9484,-2.0143,0.82108,1.8907,0 +1.285,-1.89,-1.948,-2.0147,0.82111,1.89,0 +1.286,-1.8893,-1.9475,-2.0152,0.82114,1.8893,0 +1.287,-1.8887,-1.9471,-2.0156,0.82118,1.8887,0 +1.288,-1.888,-1.9467,-2.0161,0.82121,1.888,0 +1.289,-1.8873,-1.9463,-2.0165,0.82125,1.8873,0 +1.29,-1.8867,-1.9459,-2.017,0.82129,1.8867,0 +1.291,-1.886,-1.9455,-2.0174,0.82133,1.886,0 +1.292,-1.8853,-1.9451,-2.0178,0.82137,1.8853,0 +1.293,-1.8846,-1.9447,-2.0183,0.82142,1.8846,0 +1.294,-1.8839,-1.9443,-2.0187,0.82146,1.8839,0 +1.295,-1.8832,-1.944,-2.0191,0.8215,1.8832,0 +1.296,-1.8825,-1.9436,-2.0196,0.82155,1.8825,0 +1.297,-1.8819,-1.9432,-2.02,0.82159,1.8819,0 +1.298,-1.8812,-1.9428,-2.0205,0.82163,1.8812,0 +1.299,-1.8805,-1.9424,-2.0209,0.82167,1.8805,0 +1.3,-1.8798,-1.942,-2.0213,0.82172,1.8798,0 +1.301,-1.8791,-1.9416,-2.0218,0.82176,1.8791,0 +1.302,-1.8784,-1.9412,-2.0222,0.8218,1.8784,0 +1.303,-1.8777,-1.9408,-2.0226,0.82185,1.8777,0 +1.304,-1.8771,-1.9404,-2.0231,0.82189,1.8771,0 +1.305,-1.8764,-1.94,-2.0235,0.82193,1.8764,0 +1.306,-1.8757,-1.9396,-2.024,0.82198,1.8757,0 +1.307,-1.875,-1.9392,-2.0244,0.82202,1.875,0 +1.308,-1.8743,-1.9388,-2.0248,0.82206,1.8743,0 +1.309,-1.8736,-1.9384,-2.0253,0.82211,1.8736,0 +1.31,-1.8729,-1.938,-2.0257,0.82215,1.8729,0 +1.311,-1.8723,-1.9376,-2.0261,0.82219,1.8723,0 +1.312,-1.8716,-1.9372,-2.0266,0.82223,1.8716,0 +1.313,-1.8709,-1.9368,-2.027,0.82228,1.8709,0 +1.314,-1.8702,-1.9364,-2.0275,0.82232,1.8702,0 +1.315,-1.8695,-1.9361,-2.0279,0.82236,1.8695,0 +1.316,-1.8688,-1.9357,-2.0283,0.82241,1.8688,0 +1.317,-1.8681,-1.9353,-2.0288,0.82245,1.8681,0 +1.318,-1.8675,-1.9349,-2.0292,0.82249,1.8675,0 +1.319,-1.8668,-1.9345,-2.0297,0.82254,1.8668,0 +1.32,-1.8661,-1.9341,-2.0301,0.82258,1.8661,0 +1.321,-1.8654,-1.9337,-2.0305,0.82262,1.8654,0 +1.322,-1.8647,-1.9333,-2.031,0.82266,1.8647,0 +1.323,-1.864,-1.9329,-2.0314,0.82271,1.864,0 +1.324,-1.8633,-1.9325,-2.0318,0.82275,1.8633,0 +1.325,-1.8626,-1.9321,-2.0323,0.82279,1.8626,0 +1.326,-1.862,-1.9317,-2.0327,0.82283,1.862,0 +1.327,-1.8613,-1.9313,-2.0331,0.82287,1.8613,0 +1.328,-1.8606,-1.9309,-2.0336,0.82291,1.8606,0 +1.329,-1.8599,-1.9305,-2.034,0.82294,1.8599,0 +1.33,-1.8592,-1.9302,-2.0344,0.82297,1.8592,0 +1.331,-1.8585,-1.9298,-2.0348,0.82301,1.8585,0 +1.332,-1.8578,-1.9294,-2.0352,0.82303,1.8578,0 +1.333,-1.8571,-1.929,-2.0356,0.82306,1.8571,0 +1.334,-1.8565,-1.9286,-2.0361,0.82309,1.8565,0 +1.335,-1.8558,-1.9282,-2.0365,0.82311,1.8558,0 +1.336,-1.8551,-1.9279,-2.0369,0.82314,1.8551,0 +1.337,-1.8544,-1.9275,-2.0373,0.82317,1.8544,0 +1.338,-1.8537,-1.9271,-2.0377,0.82319,1.8537,0 +1.339,-1.853,-1.9267,-2.0381,0.82322,1.853,0 +1.34,-1.8523,-1.9263,-2.0385,0.82324,1.8523,0 +1.341,-1.8516,-1.926,-2.0389,0.82327,1.8516,0 +1.342,-1.8509,-1.9256,-2.0393,0.8233,1.8509,0 +1.343,-1.8503,-1.9252,-2.0397,0.82332,1.8503,0 +1.344,-1.8496,-1.9248,-2.0401,0.82335,1.8496,0 +1.345,-1.8489,-1.9244,-2.0405,0.82337,1.8489,0 +1.346,-1.8482,-1.9241,-2.0409,0.8234,1.8482,0 +1.347,-1.8475,-1.9237,-2.0413,0.82343,1.8475,0 +1.348,-1.8468,-1.9233,-2.0417,0.82345,1.8468,0 +1.349,-1.8461,-1.9229,-2.0422,0.82348,1.8461,0 +1.35,-1.8454,-1.9225,-2.0426,0.8235,1.8454,0 +1.351,-1.8447,-1.9222,-2.043,0.82353,1.8447,0 +1.352,-1.8441,-1.9218,-2.0434,0.82356,1.8441,0 +1.353,-1.8434,-1.9214,-2.0438,0.82358,1.8434,0 +1.354,-1.8427,-1.921,-2.0442,0.82361,1.8427,0 +1.355,-1.842,-1.9206,-2.0446,0.82364,1.842,0 +1.356,-1.8413,-1.9203,-2.045,0.82366,1.8413,0 +1.357,-1.8406,-1.9199,-2.0454,0.82369,1.8406,0 +1.358,-1.8399,-1.9195,-2.0458,0.82371,1.8399,0 +1.359,-1.8392,-1.9191,-2.0462,0.82374,1.8392,0 +1.36,-1.8385,-1.9187,-2.0466,0.82377,1.8385,0 +1.361,-1.8379,-1.9183,-2.047,0.82379,1.8379,0 +1.362,-1.8372,-1.918,-2.0474,0.82382,1.8372,0 +1.363,-1.8365,-1.9176,-2.0479,0.82384,1.8365,0 +1.364,-1.8358,-1.9172,-2.0483,0.82387,1.8358,0 +1.365,-1.8351,-1.9168,-2.0487,0.8239,1.8351,0 +1.366,-1.8344,-1.9164,-2.0491,0.82392,1.8344,0 +1.367,-1.8337,-1.9161,-2.0495,0.82395,1.8337,0 +1.368,-1.8331,-1.9157,-2.0499,0.82399,1.8331,0 +1.369,-1.8324,-1.9154,-2.0503,0.82402,1.8324,0 +1.37,-1.8317,-1.915,-2.0506,0.82406,1.8317,0 +1.371,-1.831,-1.9147,-2.051,0.8241,1.831,0 +1.372,-1.8304,-1.9143,-2.0514,0.82414,1.8304,0 +1.373,-1.8297,-1.914,-2.0518,0.82419,1.8297,0 +1.374,-1.8291,-1.9137,-2.0522,0.82424,1.8291,0 +1.375,-1.8284,-1.9134,-2.0525,0.82429,1.8284,0 +1.376,-1.8278,-1.9131,-2.0529,0.82435,1.8278,0 +1.377,-1.8271,-1.9127,-2.0533,0.8244,1.8271,0 +1.378,-1.8265,-1.9124,-2.0536,0.82446,1.8265,0 +1.379,-1.8258,-1.9121,-2.054,0.82451,1.8258,0 +1.38,-1.8252,-1.9118,-2.0543,0.82456,1.8252,0 +1.381,-1.8245,-1.9115,-2.0547,0.82462,1.8245,0 +1.382,-1.8239,-1.9112,-2.0551,0.82467,1.8239,0 +1.383,-1.8233,-1.9109,-2.0554,0.82473,1.8233,0 +1.384,-1.8226,-1.9106,-2.0558,0.82478,1.8226,0 +1.385,-1.822,-1.9103,-2.0562,0.82483,1.822,0 +1.386,-1.8213,-1.9099,-2.0565,0.82489,1.8213,0 +1.387,-1.8207,-1.9096,-2.0569,0.82494,1.8207,0 +1.388,-1.82,-1.9093,-2.0573,0.825,1.82,0 +1.389,-1.8194,-1.909,-2.0576,0.82505,1.8194,0 +1.39,-1.8187,-1.9087,-2.058,0.8251,1.8187,0 +1.391,-1.8181,-1.9084,-2.0584,0.82516,1.8181,0 +1.392,-1.8174,-1.9081,-2.0587,0.82521,1.8174,0 +1.393,-1.8168,-1.9078,-2.0591,0.82526,1.8168,0 +1.394,-1.8162,-1.9075,-2.0595,0.82532,1.8162,0 +1.395,-1.8155,-1.9071,-2.0598,0.82537,1.8155,0 +1.396,-1.8149,-1.9068,-2.0602,0.82543,1.8149,0 +1.397,-1.8142,-1.9065,-2.0606,0.82548,1.8142,0 +1.398,-1.8136,-1.9062,-2.0609,0.82553,1.8136,0 +1.399,-1.8129,-1.9059,-2.0613,0.82559,1.8129,0 +1.4,-1.8123,-1.9056,-2.0617,0.82564,1.8123,0 +1.401,-1.8116,-1.9053,-2.062,0.8257,1.8116,0 +1.402,-1.811,-1.905,-2.0624,0.82575,1.811,0 +1.403,-1.8103,-1.9047,-2.0627,0.8258,1.8103,0 +1.404,-1.8097,-1.9043,-2.0631,0.82586,1.8097,0 +1.405,-1.809,-1.904,-2.0635,0.82591,1.809,0 +1.406,-1.8084,-1.9037,-2.0638,0.82597,1.8084,0 +1.407,-1.8078,-1.9034,-2.0642,0.82602,1.8078,0 +1.408,-1.8071,-1.9031,-2.0646,0.82607,1.8071,0 +1.409,-1.8065,-1.9028,-2.0649,0.82613,1.8065,0 +1.41,-1.8058,-1.9025,-2.0653,0.82619,1.8058,0 +1.411,-1.8052,-1.9022,-2.0656,0.82624,1.8052,0 +1.412,-1.8046,-1.9019,-2.066,0.8263,1.8046,0 +1.413,-1.804,-1.9016,-2.0663,0.82636,1.804,0 +1.414,-1.8034,-1.9014,-2.0666,0.82641,1.8034,0 +1.415,-1.8028,-1.9011,-2.067,0.82647,1.8028,0 +1.416,-1.8022,-1.9008,-2.0673,0.82653,1.8022,0 +1.417,-1.8016,-1.9006,-2.0676,0.82659,1.8016,0 +1.418,-1.801,-1.9003,-2.0679,0.82665,1.801,0 +1.419,-1.8004,-1.9,-2.0683,0.82671,1.8004,0 +1.42,-1.7998,-1.8998,-2.0686,0.82677,1.7998,0 +1.421,-1.7992,-1.8995,-2.0689,0.82683,1.7992,0 +1.422,-1.7986,-1.8993,-2.0692,0.82689,1.7986,0 +1.423,-1.798,-1.899,-2.0695,0.82695,1.798,0 +1.424,-1.7974,-1.8987,-2.0699,0.82701,1.7974,0 +1.425,-1.7968,-1.8985,-2.0702,0.82707,1.7968,0 +1.426,-1.7962,-1.8982,-2.0705,0.82713,1.7962,0 +1.427,-1.7956,-1.898,-2.0708,0.82719,1.7956,0 +1.428,-1.795,-1.8977,-2.0712,0.82725,1.795,0 +1.429,-1.7944,-1.8974,-2.0715,0.82731,1.7944,0 +1.43,-1.7938,-1.8972,-2.0718,0.82737,1.7938,0 +1.431,-1.7932,-1.8969,-2.0721,0.82743,1.7932,0 +1.432,-1.7926,-1.8966,-2.0724,0.82749,1.7926,0 +1.433,-1.792,-1.8964,-2.0728,0.82755,1.792,0 +1.434,-1.7914,-1.8961,-2.0731,0.82761,1.7914,0 +1.435,-1.7908,-1.8959,-2.0734,0.82767,1.7908,0 +1.436,-1.7902,-1.8956,-2.0737,0.82773,1.7902,0 +1.437,-1.7896,-1.8953,-2.074,0.82779,1.7896,0 +1.438,-1.789,-1.8951,-2.0744,0.82785,1.789,0 +1.439,-1.7884,-1.8948,-2.0747,0.82791,1.7884,0 +1.44,-1.7878,-1.8946,-2.075,0.82797,1.7878,0 +1.441,-1.7872,-1.8943,-2.0753,0.82803,1.7872,0 +1.442,-1.7866,-1.894,-2.0756,0.82809,1.7866,0 +1.443,-1.786,-1.8938,-2.076,0.82815,1.786,0 +1.444,-1.7854,-1.8935,-2.0763,0.82821,1.7854,0 +1.445,-1.7848,-1.8932,-2.0766,0.82826,1.7848,0 +1.446,-1.7842,-1.893,-2.0769,0.82832,1.7842,0 +1.447,-1.7836,-1.8927,-2.0773,0.82838,1.7836,0 +1.448,-1.783,-1.8925,-2.0776,0.82844,1.783,0 +1.449,-1.7824,-1.8922,-2.0779,0.8285,1.7824,0 +1.45,-1.7818,-1.8919,-2.0782,0.82857,1.7818,0 +1.451,-1.7812,-1.8917,-2.0785,0.82863,1.7812,0 +1.452,-1.7806,-1.8915,-2.0788,0.82869,1.7806,0 +1.453,-1.7801,-1.8912,-2.0791,0.82875,1.7801,0 +1.454,-1.7795,-1.891,-2.0794,0.82882,1.7795,0 +1.455,-1.7789,-1.8907,-2.0797,0.82888,1.7789,0 +1.456,-1.7784,-1.8905,-2.08,0.82895,1.7784,0 +1.457,-1.7778,-1.8903,-2.0803,0.82902,1.7778,0 +1.458,-1.7773,-1.8901,-2.0806,0.82909,1.7773,0 +1.459,-1.7767,-1.8899,-2.0809,0.82916,1.7767,0 +1.46,-1.7762,-1.8897,-2.0812,0.82922,1.7762,0 +1.461,-1.7756,-1.8894,-2.0814,0.82929,1.7756,0 +1.462,-1.7751,-1.8892,-2.0817,0.82936,1.7751,0 +1.463,-1.7745,-1.889,-2.082,0.82943,1.7745,0 +1.464,-1.774,-1.8888,-2.0823,0.8295,1.774,0 +1.465,-1.7734,-1.8886,-2.0826,0.82957,1.7734,0 +1.466,-1.7729,-1.8884,-2.0829,0.82964,1.7729,0 +1.467,-1.7723,-1.8882,-2.0831,0.82971,1.7723,0 +1.468,-1.7718,-1.888,-2.0834,0.82977,1.7718,0 +1.469,-1.7712,-1.8877,-2.0837,0.82984,1.7712,0 +1.47,-1.7707,-1.8875,-2.084,0.82991,1.7707,0 +1.471,-1.7701,-1.8873,-2.0843,0.82998,1.7701,0 +1.472,-1.7696,-1.8871,-2.0845,0.83005,1.7696,0 +1.473,-1.769,-1.8869,-2.0848,0.83012,1.769,0 +1.474,-1.7685,-1.8867,-2.0851,0.83019,1.7685,0 +1.475,-1.7679,-1.8865,-2.0854,0.83026,1.7679,0 +1.476,-1.7674,-1.8862,-2.0857,0.83032,1.7674,0 +1.477,-1.7669,-1.886,-2.086,0.83039,1.7669,0 +1.478,-1.7663,-1.8858,-2.0862,0.83046,1.7663,0 +1.479,-1.7658,-1.8856,-2.0865,0.83053,1.7658,0 +1.48,-1.7652,-1.8854,-2.0868,0.8306,1.7652,0 +1.481,-1.7647,-1.8852,-2.0871,0.83067,1.7647,0 +1.482,-1.7641,-1.885,-2.0874,0.83074,1.7641,0 +1.483,-1.7636,-1.8848,-2.0876,0.8308,1.7636,0 +1.484,-1.763,-1.8845,-2.0879,0.83087,1.763,0 +1.485,-1.7625,-1.8843,-2.0882,0.83094,1.7625,0 +1.486,-1.7619,-1.8841,-2.0885,0.83101,1.7619,0 +1.487,-1.7614,-1.8839,-2.0888,0.83108,1.7614,0 +1.488,-1.7608,-1.8837,-2.0891,0.83115,1.7608,0 +1.489,-1.7603,-1.8835,-2.0893,0.83122,1.7603,0 +1.49,-1.7597,-1.8833,-2.0896,0.83129,1.7597,0 +1.491,-1.7592,-1.883,-2.0899,0.83136,1.7592,0 +1.492,-1.7586,-1.8828,-2.0902,0.83143,1.7586,0 +1.493,-1.7581,-1.8826,-2.0904,0.8315,1.7581,0 +1.494,-1.7576,-1.8825,-2.0907,0.83157,1.7576,0 +1.495,-1.7571,-1.8823,-2.091,0.83165,1.7571,0 +1.496,-1.7566,-1.8821,-2.0912,0.83172,1.7566,0 +1.497,-1.756,-1.8819,-2.0915,0.8318,1.756,0 +1.498,-1.7555,-1.8817,-2.0918,0.83188,1.7555,0 +1.499,-1.755,-1.8815,-2.092,0.83196,1.755,0 +1.5,-1.7545,-1.8814,-2.0922,0.83204,1.7545,0 +1.501,-1.7541,-1.8812,-2.0925,0.83212,1.7541,0 +1.502,-1.7536,-1.881,-2.0927,0.8322,1.7536,0 +1.503,-1.7531,-1.8809,-2.093,0.83228,1.7531,0 +1.504,-1.7526,-1.8807,-2.0932,0.83236,1.7526,0 +1.505,-1.7521,-1.8805,-2.0935,0.83244,1.7521,0 +1.506,-1.7516,-1.8804,-2.0937,0.83252,1.7516,0 +1.507,-1.7511,-1.8802,-2.094,0.8326,1.7511,0 +1.508,-1.7506,-1.88,-2.0942,0.83268,1.7506,0 +1.509,-1.7501,-1.8799,-2.0945,0.83276,1.7501,0 +1.51,-1.7496,-1.8797,-2.0947,0.83284,1.7496,0 +1.511,-1.7491,-1.8795,-2.095,0.83292,1.7491,0 +1.512,-1.7486,-1.8794,-2.0952,0.833,1.7486,0 +1.513,-1.7481,-1.8792,-2.0955,0.83308,1.7481,0 +1.514,-1.7476,-1.879,-2.0957,0.83316,1.7476,0 +1.515,-1.7471,-1.8789,-2.096,0.83324,1.7471,0 +1.516,-1.7466,-1.8787,-2.0962,0.83332,1.7466,0 +1.517,-1.7461,-1.8785,-2.0964,0.8334,1.7461,0 +1.518,-1.7457,-1.8784,-2.0967,0.83348,1.7457,0 +1.519,-1.7452,-1.8782,-2.0969,0.83356,1.7452,0 +1.52,-1.7447,-1.878,-2.0972,0.83364,1.7447,0 +1.521,-1.7442,-1.8779,-2.0974,0.83373,1.7442,0 +1.522,-1.7437,-1.8777,-2.0977,0.83381,1.7437,0 +1.523,-1.7432,-1.8775,-2.0979,0.83389,1.7432,0 +1.524,-1.7427,-1.8774,-2.0982,0.83397,1.7427,0 +1.525,-1.7422,-1.8772,-2.0984,0.83405,1.7422,0 +1.526,-1.7417,-1.877,-2.0987,0.83413,1.7417,0 +1.527,-1.7412,-1.8769,-2.0989,0.83421,1.7412,0 +1.528,-1.7407,-1.8767,-2.0992,0.83429,1.7407,0 +1.529,-1.7402,-1.8765,-2.0994,0.83437,1.7402,0 +1.53,-1.7397,-1.8764,-2.0997,0.83445,1.7397,0 +1.531,-1.7392,-1.8762,-2.0999,0.83453,1.7392,0 +1.532,-1.7387,-1.8761,-2.1002,0.83461,1.7387,0 +1.533,-1.7383,-1.8759,-2.1004,0.83469,1.7383,0 +1.534,-1.7378,-1.8757,-2.1006,0.83476,1.7378,0 +1.535,-1.7373,-1.8756,-2.1009,0.83484,1.7373,0 +1.536,-1.7368,-1.8754,-2.1011,0.83491,1.7368,0 +1.537,-1.7364,-1.8753,-2.1013,0.83499,1.7364,0 +1.538,-1.7359,-1.8751,-2.1015,0.83506,1.7359,0 +1.539,-1.7355,-1.875,-2.1018,0.83513,1.7355,0 +1.54,-1.735,-1.8748,-2.102,0.8352,1.735,0 +1.541,-1.7346,-1.8747,-2.1022,0.83526,1.7346,0 +1.542,-1.7341,-1.8745,-2.1024,0.83533,1.7341,0 +1.543,-1.7337,-1.8744,-2.1026,0.8354,1.7337,0 +1.544,-1.7333,-1.8743,-2.1028,0.83546,1.7333,0 +1.545,-1.7328,-1.8741,-2.103,0.83553,1.7328,0 +1.546,-1.7324,-1.874,-2.1032,0.8356,1.7324,0 +1.547,-1.7319,-1.8738,-2.1034,0.83567,1.7319,0 +1.548,-1.7315,-1.8737,-2.1036,0.83573,1.7315,0 +1.549,-1.7311,-1.8735,-2.1038,0.8358,1.7311,0 +1.55,-1.7306,-1.8734,-2.1041,0.83587,1.7306,0 +1.551,-1.7302,-1.8733,-2.1043,0.83593,1.7302,0 +1.552,-1.7298,-1.8731,-2.1045,0.836,1.7298,0 +1.553,-1.7293,-1.873,-2.1047,0.83607,1.7293,0 +1.554,-1.7289,-1.8728,-2.1049,0.83613,1.7289,0 +1.555,-1.7284,-1.8727,-2.1051,0.8362,1.7284,0 +1.556,-1.728,-1.8726,-2.1053,0.83627,1.728,0 +1.557,-1.7276,-1.8724,-2.1055,0.83633,1.7276,0 +1.558,-1.7271,-1.8723,-2.1057,0.8364,1.7271,0 +1.559,-1.7267,-1.8721,-2.1059,0.83647,1.7267,0 +1.56,-1.7263,-1.872,-2.1061,0.83654,1.7263,0 +1.561,-1.7258,-1.8719,-2.1063,0.8366,1.7258,0 +1.562,-1.7254,-1.8717,-2.1065,0.83667,1.7254,0 +1.563,-1.7249,-1.8716,-2.1068,0.83674,1.7249,0 +1.564,-1.7245,-1.8714,-2.107,0.8368,1.7245,0 +1.565,-1.7241,-1.8713,-2.1072,0.83687,1.7241,0 +1.566,-1.7236,-1.8712,-2.1074,0.83694,1.7236,0 +1.567,-1.7232,-1.871,-2.1076,0.837,1.7232,0 +1.568,-1.7228,-1.8709,-2.1078,0.83707,1.7228,0 +1.569,-1.7223,-1.8707,-2.108,0.83714,1.7223,0 +1.57,-1.7219,-1.8706,-2.1082,0.8372,1.7219,0 +1.571,-1.7214,-1.8704,-2.1084,0.83727,1.7214,0 +1.572,-1.721,-1.8703,-2.1086,0.83734,1.721,0 +1.573,-1.7206,-1.8702,-2.1088,0.83741,1.7206,0 +1.574,-1.7201,-1.87,-2.109,0.83748,1.7201,0 +1.575,-1.7197,-1.8699,-2.1092,0.83755,1.7197,0 +1.576,-1.7193,-1.8698,-2.1094,0.83763,1.7193,0 +1.577,-1.7189,-1.8697,-2.1096,0.83771,1.7189,0 +1.578,-1.7186,-1.8696,-2.1098,0.83779,1.7186,0 +1.579,-1.7182,-1.8695,-2.11,0.83788,1.7182,0 +1.58,-1.7179,-1.8694,-2.1102,0.83797,1.7179,0 +1.581,-1.7175,-1.8693,-2.1103,0.83807,1.7175,0 +1.582,-1.7172,-1.8693,-2.1105,0.83816,1.7172,0 +1.583,-1.7169,-1.8692,-2.1106,0.83826,1.7169,0 +1.584,-1.7166,-1.8692,-2.1108,0.83837,1.7166,0 +1.585,-1.7162,-1.8691,-2.111,0.83847,1.7162,0 +1.586,-1.7159,-1.869,-2.1111,0.83857,1.7159,0 +1.587,-1.7156,-1.869,-2.1113,0.83867,1.7156,0 +1.588,-1.7153,-1.8689,-2.1114,0.83877,1.7153,0 +1.589,-1.715,-1.8689,-2.1116,0.83887,1.715,0 +1.59,-1.7147,-1.8688,-2.1118,0.83897,1.7147,0 +1.591,-1.7144,-1.8688,-2.1119,0.83907,1.7144,0 +1.592,-1.714,-1.8687,-2.1121,0.83917,1.714,0 +1.593,-1.7137,-1.8686,-2.1122,0.83927,1.7137,0 +1.594,-1.7134,-1.8686,-2.1124,0.83937,1.7134,0 +1.595,-1.7131,-1.8685,-2.1125,0.83947,1.7131,0 +1.596,-1.7128,-1.8685,-2.1127,0.83957,1.7128,0 +1.597,-1.7125,-1.8684,-2.1129,0.83968,1.7125,0 +1.598,-1.7121,-1.8683,-2.113,0.83978,1.7121,0 +1.599,-1.7118,-1.8683,-2.1132,0.83988,1.7118,0 +1.6,-1.7115,-1.8682,-2.1133,0.83998,1.7115,0 +1.601,-1.7112,-1.8682,-2.1135,0.84008,1.7112,0 +1.602,-1.7109,-1.8681,-2.1137,0.84018,1.7109,0 +1.603,-1.7106,-1.8681,-2.1138,0.84028,1.7106,0 +1.604,-1.7102,-1.868,-2.114,0.84038,1.7102,0 +1.605,-1.7099,-1.8679,-2.1141,0.84048,1.7099,0 +1.606,-1.7096,-1.8679,-2.1143,0.84058,1.7096,0 +1.607,-1.7093,-1.8678,-2.1145,0.84068,1.7093,0 +1.608,-1.709,-1.8678,-2.1146,0.84078,1.709,0 +1.609,-1.7087,-1.8677,-2.1148,0.84088,1.7087,0 +1.61,-1.7084,-1.8676,-2.1149,0.84099,1.7084,0 +1.611,-1.708,-1.8676,-2.1151,0.84109,1.708,0 +1.612,-1.7077,-1.8675,-2.1152,0.84119,1.7077,0 +1.613,-1.7074,-1.8675,-2.1154,0.84129,1.7074,0 +1.614,-1.7071,-1.8674,-2.1156,0.84139,1.7071,0 +1.615,-1.7068,-1.8674,-2.1157,0.84149,1.7068,0 +1.616,-1.7065,-1.8673,-2.1159,0.84159,1.7065,0 +1.617,-1.7062,-1.8672,-2.116,0.84169,1.7062,0 +1.618,-1.7059,-1.8672,-2.1162,0.84179,1.7059,0 +1.619,-1.7056,-1.8671,-2.1163,0.84188,1.7056,0 +1.62,-1.7053,-1.8671,-2.1165,0.84198,1.7053,0 +1.621,-1.705,-1.8671,-2.1166,0.84207,1.705,0 +1.622,-1.7047,-1.867,-2.1168,0.84217,1.7047,0 +1.623,-1.7044,-1.867,-2.1169,0.84226,1.7044,0 +1.624,-1.7042,-1.8669,-2.117,0.84236,1.7042,0 +1.625,-1.7039,-1.8669,-2.1172,0.84245,1.7039,0 +1.626,-1.7036,-1.8668,-2.1173,0.84254,1.7036,0 +1.627,-1.7034,-1.8668,-2.1174,0.84264,1.7034,0 +1.628,-1.7031,-1.8668,-2.1176,0.84273,1.7031,0 +1.629,-1.7028,-1.8667,-2.1177,0.84282,1.7028,0 +1.63,-1.7026,-1.8667,-2.1178,0.84292,1.7026,0 +1.631,-1.7023,-1.8666,-2.118,0.84301,1.7023,0 +1.632,-1.702,-1.8666,-2.1181,0.8431,1.702,0 +1.633,-1.7017,-1.8666,-2.1182,0.84319,1.7017,0 +1.634,-1.7015,-1.8665,-2.1184,0.84329,1.7015,0 +1.635,-1.7012,-1.8665,-2.1185,0.84338,1.7012,0 +1.636,-1.7009,-1.8664,-2.1186,0.84347,1.7009,0 +1.637,-1.7007,-1.8664,-2.1188,0.84357,1.7007,0 +1.638,-1.7004,-1.8663,-2.1189,0.84366,1.7004,0 +1.639,-1.7001,-1.8663,-2.119,0.84375,1.7001,0 +1.64,-1.6999,-1.8663,-2.1192,0.84385,1.6999,0 +1.641,-1.6996,-1.8662,-2.1193,0.84394,1.6996,0 +1.642,-1.6993,-1.8662,-2.1194,0.84403,1.6993,0 +1.643,-1.699,-1.8661,-2.1196,0.84413,1.699,0 +1.644,-1.6988,-1.8661,-2.1197,0.84422,1.6988,0 +1.645,-1.6985,-1.8661,-2.1198,0.84431,1.6985,0 +1.646,-1.6982,-1.866,-2.12,0.84441,1.6982,0 +1.647,-1.698,-1.866,-2.1201,0.8445,1.698,0 +1.648,-1.6977,-1.8659,-2.1202,0.84459,1.6977,0 +1.649,-1.6974,-1.8659,-2.1204,0.84468,1.6974,0 +1.65,-1.6972,-1.8659,-2.1205,0.84478,1.6972,0 +1.651,-1.6969,-1.8658,-2.1207,0.84487,1.6969,0 +1.652,-1.6966,-1.8658,-2.1208,0.84496,1.6966,0 +1.653,-1.6963,-1.8657,-2.1209,0.84506,1.6963,0 +1.654,-1.6961,-1.8657,-2.1211,0.84515,1.6961,0 +1.655,-1.6958,-1.8656,-2.1212,0.84524,1.6958,0 +1.656,-1.6955,-1.8656,-2.1213,0.84533,1.6955,0 +1.657,-1.6953,-1.8656,-2.1215,0.84542,1.6953,0 +1.658,-1.695,-1.8655,-2.1216,0.8455,1.695,0 +1.659,-1.6948,-1.8655,-2.1217,0.84557,1.6948,0 +1.66,-1.6945,-1.8654,-2.1218,0.84564,1.6945,0 +1.661,-1.6943,-1.8654,-2.1219,0.8457,1.6943,0 +1.662,-1.694,-1.8653,-2.122,0.84576,1.694,0 +1.663,-1.6938,-1.8652,-2.1221,0.8458,1.6938,0 +1.664,-1.6935,-1.8652,-2.1223,0.84585,1.6935,0 +1.665,-1.6933,-1.8651,-2.1224,0.84588,1.6933,0 +1.666,-1.6931,-1.8651,-2.1224,0.84591,1.6931,0 +1.667,-1.6929,-1.865,-2.1225,0.84594,1.6929,0 +1.668,-1.6926,-1.8649,-2.1226,0.84597,1.6926,0 +1.669,-1.6924,-1.8649,-2.1227,0.846,1.6924,0 +1.67,-1.6922,-1.8648,-2.1228,0.84604,1.6922,0 +1.671,-1.692,-1.8647,-2.1229,0.84607,1.692,0 +1.672,-1.6918,-1.8647,-2.123,0.8461,1.6918,0 +1.673,-1.6915,-1.8646,-2.1231,0.84613,1.6915,0 +1.674,-1.6913,-1.8645,-2.1232,0.84616,1.6913,0 +1.675,-1.6911,-1.8645,-2.1233,0.84619,1.6911,0 +1.676,-1.6909,-1.8644,-2.1234,0.84622,1.6909,0 +1.677,-1.6906,-1.8643,-2.1235,0.84625,1.6906,0 +1.678,-1.6904,-1.8643,-2.1236,0.84628,1.6904,0 +1.679,-1.6902,-1.8642,-2.1237,0.84631,1.6902,0 +1.68,-1.69,-1.8641,-2.1238,0.84634,1.69,0 +1.681,-1.6897,-1.8641,-2.1239,0.84637,1.6897,0 +1.682,-1.6895,-1.864,-2.124,0.8464,1.6895,0 +1.683,-1.6893,-1.8639,-2.1241,0.84643,1.6893,0 +1.684,-1.6891,-1.8639,-2.1242,0.84646,1.6891,0 +1.685,-1.6888,-1.8638,-2.1243,0.84649,1.6888,0 +1.686,-1.6886,-1.8637,-2.1244,0.84652,1.6886,0 +1.687,-1.6884,-1.8637,-2.1245,0.84656,1.6884,0 +1.688,-1.6882,-1.8636,-2.1246,0.84659,1.6882,0 +1.689,-1.688,-1.8635,-2.1247,0.84662,1.688,0 +1.69,-1.6877,-1.8635,-2.1248,0.84665,1.6877,0 +1.691,-1.6875,-1.8634,-2.1249,0.84668,1.6875,0 +1.692,-1.6873,-1.8634,-2.1249,0.84671,1.6873,0 +1.693,-1.6871,-1.8633,-2.125,0.84674,1.6871,0 +1.694,-1.6868,-1.8632,-2.1251,0.84677,1.6868,0 +1.695,-1.6866,-1.8632,-2.1252,0.8468,1.6866,0 +1.696,-1.6864,-1.8631,-2.1253,0.84683,1.6864,0 +1.697,-1.6862,-1.863,-2.1254,0.84686,1.6862,0 +1.698,-1.686,-1.863,-2.1255,0.84689,1.686,0 +1.699,-1.6858,-1.8629,-2.1256,0.84691,1.6858,0 +1.7,-1.6856,-1.8629,-2.1257,0.84693,1.6856,0 +1.701,-1.6854,-1.8628,-2.1257,0.84695,1.6854,0 +1.702,-1.6853,-1.8628,-2.1258,0.84696,1.6853,0 +1.703,-1.6852,-1.8627,-2.1258,0.84697,1.6852,0 +1.704,-1.6851,-1.8627,-2.1259,0.84698,1.6851,0 +1.705,-1.6851,-1.8627,-2.1259,0.84698,1.6851,0 +1.706,-1.685,-1.8627,-2.1259,0.84697,1.685,0 +1.707,-1.685,-1.8626,-2.1259,0.84697,1.685,0 +1.708,-1.685,-1.8626,-2.1259,0.84696,1.685,0 +1.709,-1.6849,-1.8626,-2.1259,0.84695,1.6849,0 +1.71,-1.6849,-1.8626,-2.1259,0.84695,1.6849,0 +1.711,-1.6849,-1.8626,-2.1259,0.84694,1.6849,0 +1.712,-1.6849,-1.8626,-2.1259,0.84693,1.6849,0 +1.713,-1.6849,-1.8626,-2.126,0.84692,1.6849,0 +1.714,-1.6848,-1.8625,-2.126,0.84692,1.6848,0 +1.715,-1.6848,-1.8625,-2.126,0.84691,1.6848,0 +1.716,-1.6848,-1.8625,-2.126,0.8469,1.6848,0 +1.717,-1.6848,-1.8625,-2.126,0.84689,1.6848,0 +1.718,-1.6848,-1.8625,-2.126,0.84688,1.6848,0 +1.719,-1.6847,-1.8625,-2.126,0.84688,1.6847,0 +1.72,-1.6847,-1.8625,-2.126,0.84687,1.6847,0 +1.721,-1.6847,-1.8625,-2.126,0.84686,1.6847,0 +1.722,-1.6847,-1.8624,-2.126,0.84685,1.6847,0 +1.723,-1.6847,-1.8624,-2.126,0.84685,1.6847,0 +1.724,-1.6846,-1.8624,-2.126,0.84684,1.6846,0 +1.725,-1.6846,-1.8624,-2.126,0.84683,1.6846,0 +1.726,-1.6846,-1.8624,-2.126,0.84682,1.6846,0 +1.727,-1.6846,-1.8624,-2.126,0.84682,1.6846,0 +1.728,-1.6846,-1.8624,-2.126,0.84681,1.6846,0 +1.729,-1.6846,-1.8624,-2.126,0.8468,1.6846,0 +1.73,-1.6845,-1.8623,-2.126,0.84679,1.6845,0 +1.731,-1.6845,-1.8623,-2.1261,0.84679,1.6845,0 +1.732,-1.6845,-1.8623,-2.1261,0.84678,1.6845,0 +1.733,-1.6845,-1.8623,-2.1261,0.84677,1.6845,0 +1.734,-1.6845,-1.8623,-2.1261,0.84676,1.6845,0 +1.735,-1.6844,-1.8623,-2.1261,0.84676,1.6844,0 +1.736,-1.6844,-1.8623,-2.1261,0.84675,1.6844,0 +1.737,-1.6844,-1.8622,-2.1261,0.84674,1.6844,0 +1.738,-1.6844,-1.8622,-2.1261,0.84673,1.6844,0 +1.739,-1.6844,-1.8622,-2.1261,0.84673,1.6844,0 +1.74,-1.6843,-1.8622,-2.1261,0.84672,1.6843,0 +1.741,-1.6843,-1.8622,-2.1261,0.84671,1.6843,0 +1.742,-1.6843,-1.8622,-2.1261,0.8467,1.6843,0 +1.743,-1.6843,-1.8622,-2.1261,0.84669,1.6843,0 +1.744,-1.6843,-1.8622,-2.1261,0.84669,1.6843,0 +1.745,-1.6842,-1.8621,-2.1261,0.84668,1.6842,0 +1.746,-1.6842,-1.8621,-2.1261,0.84667,1.6842,0 +1.747,-1.6842,-1.8621,-2.1261,0.84666,1.6842,0 +1.748,-1.6842,-1.8621,-2.1261,0.84666,1.6842,0 +1.749,-1.6842,-1.8621,-2.1262,0.84665,1.6842,0 +1.75,-1.6841,-1.8621,-2.1262,0.84664,1.6841,0 +1.751,-1.6841,-1.8621,-2.1262,0.84663,1.6841,0 +1.752,-1.6841,-1.8621,-2.1262,0.84663,1.6841,0 +1.753,-1.6841,-1.862,-2.1262,0.84662,1.6841,0 +1.754,-1.6841,-1.862,-2.1262,0.84661,1.6841,0 +1.755,-1.684,-1.862,-2.1262,0.8466,1.684,0 +1.756,-1.684,-1.862,-2.1262,0.8466,1.684,0 +1.757,-1.684,-1.862,-2.1262,0.84659,1.684,0 +1.758,-1.684,-1.862,-2.1262,0.84658,1.684,0 +1.759,-1.684,-1.862,-2.1262,0.84657,1.684,0 +1.76,-1.6839,-1.8619,-2.1262,0.84657,1.6839,0 +1.761,-1.6839,-1.8619,-2.1262,0.84656,1.6839,0 +1.762,-1.6839,-1.8619,-2.1262,0.84655,1.6839,0 +1.763,-1.6839,-1.8619,-2.1262,0.84654,1.6839,0 +1.764,-1.6839,-1.8619,-2.1262,0.84654,1.6839,0 +1.765,-1.6838,-1.8619,-2.1262,0.84653,1.6838,0 +1.766,-1.6838,-1.8619,-2.1262,0.84652,1.6838,0 +1.767,-1.6838,-1.8619,-2.1263,0.84651,1.6838,0 +1.768,-1.6838,-1.8618,-2.1263,0.84651,1.6838,0 +1.769,-1.6838,-1.8618,-2.1263,0.8465,1.6838,0 +1.77,-1.6837,-1.8618,-2.1263,0.84649,1.6837,0 +1.771,-1.6837,-1.8618,-2.1263,0.84648,1.6837,0 +1.772,-1.6837,-1.8618,-2.1263,0.84647,1.6837,0 +1.773,-1.6837,-1.8618,-2.1263,0.84647,1.6837,0 +1.774,-1.6837,-1.8618,-2.1263,0.84646,1.6837,0 +1.775,-1.6836,-1.8617,-2.1263,0.84645,1.6836,0 +1.776,-1.6836,-1.8617,-2.1263,0.84644,1.6836,0 +1.777,-1.6836,-1.8617,-2.1263,0.84644,1.6836,0 +1.778,-1.6836,-1.8617,-2.1263,0.84643,1.6836,0 +1.779,-1.6836,-1.8617,-2.1263,0.84642,1.6836,0 +1.78,-1.6835,-1.8617,-2.1263,0.84641,1.6835,0 +1.781,-1.6835,-1.8617,-2.1263,0.84641,1.6835,0 +1.782,-1.6835,-1.8617,-2.1263,0.8464,1.6835,0 +1.783,-1.6835,-1.8616,-2.1263,0.84639,1.6835,0 +1.784,-1.6835,-1.8616,-2.1263,0.84638,1.6835,0 +1.785,-1.6834,-1.8616,-2.1264,0.84638,1.6834,0 +1.786,-1.6834,-1.8616,-2.1264,0.84637,1.6834,0 +1.787,-1.6834,-1.8616,-2.1264,0.84636,1.6834,0 +1.788,-1.6834,-1.8616,-2.1264,0.84635,1.6834,0 +1.789,-1.6834,-1.8616,-2.1264,0.84635,1.6834,0 +1.79,-1.6833,-1.8616,-2.1264,0.84634,1.6833,0 +1.791,-1.6833,-1.8615,-2.1264,0.84633,1.6833,0 +1.792,-1.6833,-1.8615,-2.1264,0.84632,1.6833,0 +1.793,-1.6833,-1.8615,-2.1264,0.84632,1.6833,0 +1.794,-1.6833,-1.8615,-2.1264,0.84631,1.6833,0 +1.795,-1.6832,-1.8615,-2.1264,0.8463,1.6832,0 +1.796,-1.6832,-1.8615,-2.1264,0.84629,1.6832,0 +1.797,-1.6832,-1.8615,-2.1264,0.84628,1.6832,0 +1.798,-1.6832,-1.8614,-2.1264,0.84628,1.6832,0 +1.799,-1.6832,-1.8614,-2.1264,0.84627,1.6832,0 +1.8,-1.6832,-1.8614,-2.1264,0.84626,1.6832,0 +1.801,-1.6831,-1.8614,-2.1264,0.84625,1.6831,0 +1.802,-1.6831,-1.8614,-2.1264,0.84625,1.6831,0 +1.803,-1.6831,-1.8614,-2.1265,0.84624,1.6831,0 +1.804,-1.6831,-1.8614,-2.1265,0.84623,1.6831,0 +1.805,-1.6831,-1.8614,-2.1265,0.84622,1.6831,0 +1.806,-1.683,-1.8613,-2.1265,0.84622,1.683,0 +1.807,-1.683,-1.8613,-2.1265,0.84621,1.683,0 +1.808,-1.683,-1.8613,-2.1265,0.8462,1.683,0 +1.809,-1.683,-1.8613,-2.1265,0.84619,1.683,0 +1.81,-1.683,-1.8613,-2.1265,0.84619,1.683,0 +1.811,-1.6829,-1.8613,-2.1265,0.84618,1.6829,0 +1.812,-1.6829,-1.8613,-2.1265,0.84617,1.6829,0 +1.813,-1.6829,-1.8612,-2.1265,0.84616,1.6829,0 +1.814,-1.6829,-1.8612,-2.1265,0.84616,1.6829,0 +1.815,-1.6829,-1.8612,-2.1265,0.84615,1.6829,0 +1.816,-1.6828,-1.8612,-2.1265,0.84614,1.6828,0 +1.817,-1.6828,-1.8612,-2.1265,0.84613,1.6828,0 +1.818,-1.6828,-1.8612,-2.1265,0.84613,1.6828,0 +1.819,-1.6828,-1.8612,-2.1265,0.84612,1.6828,0 +1.82,-1.6828,-1.8612,-2.1265,0.84611,1.6828,0 +1.821,-1.6827,-1.8611,-2.1266,0.8461,1.6827,0 +1.822,-1.6827,-1.8611,-2.1266,0.84609,1.6827,0 +1.823,-1.6827,-1.8611,-2.1266,0.84609,1.6827,0 +1.824,-1.6827,-1.8611,-2.1266,0.84608,1.6827,0 +1.825,-1.6827,-1.8611,-2.1266,0.84607,1.6827,0 +1.826,-1.6826,-1.8611,-2.1266,0.84606,1.6826,0 +1.827,-1.6826,-1.8611,-2.1266,0.84606,1.6826,0 +1.828,-1.6826,-1.8611,-2.1266,0.84605,1.6826,0 +1.829,-1.6826,-1.861,-2.1266,0.84604,1.6826,0 +1.83,-1.6826,-1.861,-2.1266,0.84603,1.6826,0 +1.831,-1.6825,-1.861,-2.1266,0.84603,1.6825,0 +1.832,-1.6825,-1.861,-2.1266,0.84602,1.6825,0 +1.833,-1.6825,-1.861,-2.1266,0.84601,1.6825,0 +1.834,-1.6825,-1.861,-2.1266,0.846,1.6825,0 +1.835,-1.6825,-1.861,-2.1266,0.846,1.6825,0 +1.836,-1.6824,-1.8609,-2.1266,0.84599,1.6824,0 +1.837,-1.6824,-1.8609,-2.1266,0.84598,1.6824,0 +1.838,-1.6824,-1.8609,-2.1266,0.84597,1.6824,0 +1.839,-1.6824,-1.8609,-2.1267,0.84597,1.6824,0 +1.84,-1.6824,-1.8609,-2.1267,0.84596,1.6824,0 +1.841,-1.6823,-1.8609,-2.1267,0.84595,1.6823,0 +1.842,-1.6823,-1.8609,-2.1267,0.84594,1.6823,0 +1.843,-1.6823,-1.8609,-2.1267,0.84594,1.6823,0 +1.844,-1.6823,-1.8608,-2.1267,0.84593,1.6823,0 +1.845,-1.6823,-1.8608,-2.1267,0.84592,1.6823,0 +1.846,-1.6822,-1.8608,-2.1267,0.84591,1.6822,0 +1.847,-1.6822,-1.8608,-2.1267,0.8459,1.6822,0 +1.848,-1.6822,-1.8608,-2.1267,0.8459,1.6822,0 +1.849,-1.6822,-1.8608,-2.1267,0.84589,1.6822,0 +1.85,-1.6822,-1.8608,-2.1267,0.84588,1.6822,0 +1.851,-1.6821,-1.8607,-2.1267,0.84587,1.6821,0 +1.852,-1.6821,-1.8607,-2.1267,0.84587,1.6821,0 +1.853,-1.6821,-1.8607,-2.1267,0.84586,1.6821,0 +1.854,-1.6821,-1.8607,-2.1267,0.84585,1.6821,0 +1.855,-1.6821,-1.8607,-2.1267,0.84584,1.6821,0 +1.856,-1.682,-1.8607,-2.1267,0.84584,1.682,0 +1.857,-1.682,-1.8607,-2.1268,0.84583,1.682,0 +1.858,-1.682,-1.8607,-2.1268,0.84582,1.682,0 +1.859,-1.682,-1.8606,-2.1268,0.84581,1.682,0 +1.86,-1.682,-1.8606,-2.1268,0.84581,1.682,0 +1.861,-1.6819,-1.8606,-2.1268,0.8458,1.6819,0 +1.862,-1.6819,-1.8606,-2.1268,0.84579,1.6819,0 +1.863,-1.6819,-1.8606,-2.1268,0.84578,1.6819,0 +1.864,-1.6819,-1.8606,-2.1268,0.84578,1.6819,0 +1.865,-1.6819,-1.8606,-2.1268,0.84577,1.6819,0 +1.866,-1.6818,-1.8606,-2.1268,0.84576,1.6818,0 +1.867,-1.6818,-1.8605,-2.1268,0.84575,1.6818,0 +1.868,-1.6818,-1.8605,-2.1268,0.84575,1.6818,0 +1.869,-1.6818,-1.8605,-2.1268,0.84574,1.6818,0 +1.87,-1.6818,-1.8605,-2.1268,0.84573,1.6818,0 +1.871,-1.6817,-1.8605,-2.1268,0.84572,1.6817,0 +1.872,-1.6817,-1.8605,-2.1268,0.84572,1.6817,0 +1.873,-1.6817,-1.8605,-2.1268,0.84571,1.6817,0 +1.874,-1.6817,-1.8604,-2.1268,0.8457,1.6817,0 +1.875,-1.6817,-1.8604,-2.1269,0.84569,1.6817,0 +1.876,-1.6817,-1.8604,-2.1269,0.84568,1.6817,0 +1.877,-1.6816,-1.8604,-2.1269,0.84568,1.6816,0 +1.878,-1.6816,-1.8604,-2.1269,0.84567,1.6816,0 +1.879,-1.6816,-1.8604,-2.1269,0.84566,1.6816,0 +1.88,-1.6816,-1.8604,-2.1269,0.84565,1.6816,0 +1.881,-1.6816,-1.8604,-2.1269,0.84565,1.6816,0 +1.882,-1.6815,-1.8603,-2.1269,0.84564,1.6815,0 +1.883,-1.6815,-1.8603,-2.1269,0.84563,1.6815,0 +1.884,-1.6815,-1.8603,-2.1269,0.84562,1.6815,0 +1.885,-1.6815,-1.8603,-2.1269,0.84562,1.6815,0 +1.886,-1.6815,-1.8603,-2.1269,0.84561,1.6815,0 +1.887,-1.6814,-1.8603,-2.1269,0.8456,1.6814,0 +1.888,-1.6814,-1.8603,-2.1269,0.84559,1.6814,0 +1.889,-1.6814,-1.8603,-2.1269,0.84559,1.6814,0 +1.89,-1.6814,-1.8602,-2.1269,0.84558,1.6814,0 +1.891,-1.6814,-1.8602,-2.1269,0.84557,1.6814,0 +1.892,-1.6813,-1.8602,-2.1269,0.84556,1.6813,0 +1.893,-1.6813,-1.8602,-2.127,0.84556,1.6813,0 +1.894,-1.6813,-1.8602,-2.127,0.84555,1.6813,0 +1.895,-1.6813,-1.8602,-2.127,0.84554,1.6813,0 +1.896,-1.6813,-1.8602,-2.127,0.84553,1.6813,0 +1.897,-1.6812,-1.8601,-2.127,0.84553,1.6812,0 +1.898,-1.6812,-1.8601,-2.127,0.84552,1.6812,0 +1.899,-1.6812,-1.8601,-2.127,0.84551,1.6812,0 +1.9,-1.6812,-1.8601,-2.127,0.8455,1.6812,0 +1.901,-1.6812,-1.8601,-2.127,0.84549,1.6812,0 +1.902,-1.6811,-1.8601,-2.127,0.84549,1.6811,0 +1.903,-1.6811,-1.8601,-2.127,0.84548,1.6811,0 +1.904,-1.6811,-1.8601,-2.127,0.84547,1.6811,0 +1.905,-1.6811,-1.86,-2.127,0.84546,1.6811,0 +1.906,-1.6811,-1.86,-2.127,0.84546,1.6811,0 +1.907,-1.681,-1.86,-2.127,0.84545,1.681,0 +1.908,-1.681,-1.86,-2.127,0.84544,1.681,0 +1.909,-1.681,-1.86,-2.127,0.84543,1.681,0 +1.91,-1.681,-1.86,-2.127,0.84543,1.681,0 +1.911,-1.681,-1.86,-2.127,0.84542,1.681,0 +1.912,-1.6809,-1.8599,-2.1271,0.84541,1.6809,0 +1.913,-1.6809,-1.8599,-2.1271,0.8454,1.6809,0 +1.914,-1.6809,-1.8599,-2.1271,0.8454,1.6809,0 +1.915,-1.6809,-1.8599,-2.1271,0.84539,1.6809,0 +1.916,-1.6809,-1.8599,-2.1271,0.84538,1.6809,0 +1.917,-1.6808,-1.8599,-2.1271,0.84537,1.6808,0 +1.918,-1.6808,-1.8599,-2.1271,0.84537,1.6808,0 +1.919,-1.6808,-1.8599,-2.1271,0.84536,1.6808,0 +1.92,-1.6808,-1.8598,-2.1271,0.84535,1.6808,0 +1.921,-1.6808,-1.8598,-2.1271,0.84534,1.6808,0 +1.922,-1.6807,-1.8598,-2.1271,0.84534,1.6807,0 +1.923,-1.6807,-1.8598,-2.1271,0.84533,1.6807,0 +1.924,-1.6807,-1.8598,-2.1271,0.84532,1.6807,0 +1.925,-1.6807,-1.8598,-2.1271,0.84531,1.6807,0 +1.926,-1.6807,-1.8598,-2.1271,0.8453,1.6807,0 +1.927,-1.6806,-1.8598,-2.1271,0.8453,1.6806,0 +1.928,-1.6806,-1.8597,-2.1271,0.84529,1.6806,0 +1.929,-1.6806,-1.8597,-2.1271,0.84528,1.6806,0 +1.93,-1.6806,-1.8597,-2.1272,0.84527,1.6806,0 +1.931,-1.6806,-1.8597,-2.1272,0.84527,1.6806,0 +1.932,-1.6805,-1.8597,-2.1272,0.84526,1.6805,0 +1.933,-1.6805,-1.8597,-2.1272,0.84525,1.6805,0 +1.934,-1.6805,-1.8597,-2.1272,0.84524,1.6805,0 +1.935,-1.6805,-1.8596,-2.1272,0.84524,1.6805,0 +1.936,-1.6805,-1.8596,-2.1272,0.84523,1.6805,0 +1.937,-1.6804,-1.8596,-2.1272,0.84522,1.6804,0 +1.938,-1.6804,-1.8596,-2.1272,0.84521,1.6804,0 +1.939,-1.6804,-1.8596,-2.1272,0.84521,1.6804,0 +1.94,-1.6804,-1.8596,-2.1272,0.8452,1.6804,0 +1.941,-1.6804,-1.8596,-2.1272,0.84519,1.6804,0 +1.942,-1.6803,-1.8596,-2.1272,0.84518,1.6803,0 +1.943,-1.6803,-1.8595,-2.1272,0.84518,1.6803,0 +1.944,-1.6803,-1.8595,-2.1272,0.84517,1.6803,0 +1.945,-1.6803,-1.8595,-2.1272,0.84516,1.6803,0 +1.946,-1.6803,-1.8595,-2.1272,0.84515,1.6803,0 +1.947,-1.6803,-1.8595,-2.1272,0.84515,1.6803,0 +1.948,-1.6802,-1.8595,-2.1273,0.84514,1.6802,0 +1.949,-1.6802,-1.8595,-2.1273,0.84513,1.6802,0 +1.95,-1.6802,-1.8594,-2.1273,0.84512,1.6802,0 +1.951,-1.6802,-1.8594,-2.1273,0.84511,1.6802,0 +1.952,-1.6802,-1.8594,-2.1273,0.84511,1.6802,0 +1.953,-1.6801,-1.8594,-2.1273,0.8451,1.6801,0 +1.954,-1.6801,-1.8594,-2.1273,0.84509,1.6801,0 +1.955,-1.6801,-1.8594,-2.1273,0.84508,1.6801,0 +1.956,-1.6801,-1.8594,-2.1273,0.84508,1.6801,0 +1.957,-1.6801,-1.8594,-2.1273,0.84507,1.6801,0 +1.958,-1.68,-1.8593,-2.1273,0.84506,1.68,0 +1.959,-1.68,-1.8593,-2.1273,0.84505,1.68,0 +1.96,-1.68,-1.8593,-2.1273,0.84505,1.68,0 +1.961,-1.68,-1.8593,-2.1273,0.84504,1.68,0 +1.962,-1.68,-1.8593,-2.1273,0.84503,1.68,0 +1.963,-1.6799,-1.8593,-2.1273,0.84502,1.6799,0 +1.964,-1.6799,-1.8593,-2.1273,0.84502,1.6799,0 +1.965,-1.6799,-1.8593,-2.1273,0.84501,1.6799,0 +1.966,-1.6799,-1.8592,-2.1274,0.845,1.6799,0 +1.967,-1.6799,-1.8592,-2.1274,0.84499,1.6799,0 +1.968,-1.6798,-1.8592,-2.1274,0.84499,1.6798,0 +1.969,-1.6798,-1.8592,-2.1274,0.84498,1.6798,0 +1.97,-1.6798,-1.8592,-2.1274,0.84497,1.6798,0 +1.971,-1.6798,-1.8592,-2.1274,0.84496,1.6798,0 +1.972,-1.6798,-1.8592,-2.1274,0.84496,1.6798,0 +1.973,-1.6797,-1.8591,-2.1274,0.84495,1.6797,0 +1.974,-1.6797,-1.8591,-2.1274,0.84494,1.6797,0 +1.975,-1.6797,-1.8591,-2.1274,0.84493,1.6797,0 +1.976,-1.6797,-1.8591,-2.1274,0.84493,1.6797,0 +1.977,-1.6797,-1.8591,-2.1274,0.84492,1.6797,0 +1.978,-1.6796,-1.8591,-2.1274,0.84491,1.6796,0 +1.979,-1.6796,-1.8591,-2.1274,0.8449,1.6796,0 +1.98,-1.6796,-1.8591,-2.1274,0.84489,1.6796,0 +1.981,-1.6796,-1.859,-2.1274,0.84489,1.6796,0 +1.982,-1.6796,-1.859,-2.1274,0.84488,1.6796,0 +1.983,-1.6795,-1.859,-2.1274,0.84487,1.6795,0 +1.984,-1.6795,-1.859,-2.1275,0.84486,1.6795,0 +1.985,-1.6795,-1.859,-2.1275,0.84486,1.6795,0 +1.986,-1.6795,-1.859,-2.1275,0.84485,1.6795,0 +1.987,-1.6795,-1.859,-2.1275,0.84484,1.6795,0 +1.988,-1.6794,-1.8589,-2.1275,0.84483,1.6794,0 +1.989,-1.6794,-1.8589,-2.1275,0.84483,1.6794,0 +1.99,-1.6794,-1.8589,-2.1275,0.84482,1.6794,0 +1.991,-1.6794,-1.8589,-2.1275,0.84481,1.6794,0 +1.992,-1.6794,-1.8589,-2.1275,0.8448,1.6794,0 +1.993,-1.6793,-1.8589,-2.1275,0.8448,1.6793,0 +1.994,-1.6793,-1.8589,-2.1275,0.84479,1.6793,0 +1.995,-1.6793,-1.8589,-2.1275,0.84478,1.6793,0 +1.996,-1.6793,-1.8588,-2.1275,0.84477,1.6793,0 +1.997,-1.6793,-1.8588,-2.1275,0.84477,1.6793,0 +1.998,-1.6792,-1.8588,-2.1275,0.84476,1.6792,0 +1.999,-1.6792,-1.8588,-2.1275,0.84475,1.6792,0 +2,-1.6792,-1.8588,-2.1275,0.84474,1.6792,0 +2.001,-1.6792,-1.8588,-2.1275,0.84474,1.6792,0 +2.002,-1.6792,-1.8588,-2.1276,0.84473,1.6792,0 +2.003,-1.6791,-1.8588,-2.1276,0.84472,1.6791,0 +2.004,-1.6791,-1.8587,-2.1276,0.84471,1.6791,0 +2.005,-1.6791,-1.8587,-2.1276,0.8447,1.6791,0 +2.006,-1.6791,-1.8587,-2.1276,0.8447,1.6791,0 +2.007,-1.6791,-1.8587,-2.1276,0.84469,1.6791,0 +2.008,-1.679,-1.8587,-2.1276,0.84468,1.679,0 +2.009,-1.679,-1.8587,-2.1276,0.84467,1.679,0 +2.01,-1.679,-1.8587,-2.1276,0.84467,1.679,0 +2.011,-1.679,-1.8586,-2.1276,0.84466,1.679,0 +2.012,-1.679,-1.8586,-2.1276,0.84465,1.679,0 +2.013,-1.6789,-1.8586,-2.1276,0.84464,1.6789,0 +2.014,-1.6789,-1.8586,-2.1276,0.84464,1.6789,0 +2.015,-1.6789,-1.8586,-2.1276,0.84463,1.6789,0 +2.016,-1.6789,-1.8586,-2.1276,0.84462,1.6789,0 +2.017,-1.6789,-1.8586,-2.1276,0.84461,1.6789,0 +2.018,-1.6789,-1.8586,-2.1276,0.84461,1.6789,0 +2.019,-1.6788,-1.8585,-2.1276,0.8446,1.6788,0 +2.02,-1.6788,-1.8585,-2.1277,0.84459,1.6788,0 +2.021,-1.6788,-1.8585,-2.1277,0.84458,1.6788,0 +2.022,-1.6788,-1.8585,-2.1277,0.84458,1.6788,0 +2.023,-1.6788,-1.8585,-2.1277,0.84457,1.6788,0 +2.024,-1.6787,-1.8585,-2.1277,0.84456,1.6787,0 +2.025,-1.6787,-1.8585,-2.1277,0.84455,1.6787,0 +2.026,-1.6787,-1.8585,-2.1277,0.84455,1.6787,0 +2.027,-1.6787,-1.8584,-2.1277,0.84454,1.6787,0 +2.028,-1.6787,-1.8584,-2.1277,0.84453,1.6787,0 +2.029,-1.6786,-1.8584,-2.1277,0.84452,1.6786,0 +2.03,-1.6786,-1.8584,-2.1277,0.84451,1.6786,0 +2.031,-1.6786,-1.8584,-2.1277,0.84451,1.6786,0 +2.032,-1.6786,-1.8584,-2.1277,0.8445,1.6786,0 +2.033,-1.6786,-1.8584,-2.1277,0.84449,1.6786,0 +2.034,-1.6785,-1.8583,-2.1277,0.84448,1.6785,0 +2.035,-1.6785,-1.8583,-2.1277,0.84447,1.6785,0 +2.036,-1.6785,-1.8583,-2.1277,0.84446,1.6785,0 +2.037,-1.6785,-1.8583,-2.1277,0.84443,1.6785,0 +2.038,-1.6785,-1.8583,-2.1277,0.8444,1.6785,0 +2.039,-1.6785,-1.8582,-2.1277,0.84436,1.6785,0 +2.04,-1.6785,-1.8582,-2.1277,0.84431,1.6785,0 +2.041,-1.6784,-1.8581,-2.1277,0.84425,1.6784,0 +2.042,-1.6784,-1.8581,-2.1277,0.84419,1.6784,0 +2.043,-1.6784,-1.858,-2.1277,0.84412,1.6784,0 +2.044,-1.6784,-1.858,-2.1276,0.84404,1.6784,0 +2.045,-1.6784,-1.8579,-2.1276,0.84396,1.6784,0 +2.046,-1.6784,-1.8579,-2.1276,0.84387,1.6784,0 +2.047,-1.6784,-1.8578,-2.1276,0.84379,1.6784,0 +2.048,-1.6784,-1.8577,-2.1276,0.84371,1.6784,0 +2.049,-1.6784,-1.8577,-2.1275,0.84362,1.6784,0 +2.05,-1.6784,-1.8576,-2.1275,0.84354,1.6784,0 +2.051,-1.6784,-1.8576,-2.1275,0.84346,1.6784,0 +2.052,-1.6784,-1.8575,-2.1275,0.84337,1.6784,0 +2.053,-1.6784,-1.8574,-2.1274,0.84329,1.6784,0 +2.054,-1.6784,-1.8574,-2.1274,0.84321,1.6784,0 +2.055,-1.6784,-1.8573,-2.1274,0.84312,1.6784,0 +2.056,-1.6784,-1.8573,-2.1274,0.84304,1.6784,0 +2.057,-1.6784,-1.8572,-2.1274,0.84296,1.6784,0 +2.058,-1.6784,-1.8571,-2.1273,0.84287,1.6784,0 +2.059,-1.6784,-1.8571,-2.1273,0.84279,1.6784,0 +2.06,-1.6784,-1.857,-2.1273,0.84271,1.6784,0 +2.061,-1.6784,-1.857,-2.1273,0.84262,1.6784,0 +2.062,-1.6784,-1.8569,-2.1272,0.84254,1.6784,0 +2.063,-1.6784,-1.8568,-2.1272,0.84246,1.6784,0 +2.064,-1.6784,-1.8568,-2.1272,0.84237,1.6784,0 +2.065,-1.6784,-1.8567,-2.1272,0.84229,1.6784,0 +2.066,-1.6784,-1.8567,-2.1271,0.84221,1.6784,0 +2.067,-1.6784,-1.8566,-2.1271,0.84213,1.6784,0 +2.068,-1.6784,-1.8565,-2.1271,0.84204,1.6784,0 +2.069,-1.6784,-1.8565,-2.1271,0.84196,1.6784,0 +2.07,-1.6784,-1.8564,-2.1271,0.84188,1.6784,0 +2.071,-1.6784,-1.8564,-2.127,0.84179,1.6784,0 +2.072,-1.6784,-1.8563,-2.127,0.84171,1.6784,0 +2.073,-1.6784,-1.8562,-2.127,0.84163,1.6784,0 +2.074,-1.6784,-1.8562,-2.127,0.84154,1.6784,0 +2.075,-1.6784,-1.8561,-2.1269,0.84146,1.6784,0 +2.076,-1.6784,-1.856,-2.1269,0.84138,1.6784,0 +2.077,-1.6784,-1.856,-2.1269,0.84129,1.6784,0 +2.078,-1.6784,-1.8559,-2.1269,0.84121,1.6784,0 +2.079,-1.6784,-1.8559,-2.1269,0.84113,1.6784,0 +2.08,-1.6784,-1.8558,-2.1268,0.84104,1.6784,0 +2.081,-1.6784,-1.8557,-2.1268,0.84096,1.6784,0 +2.082,-1.6784,-1.8557,-2.1268,0.84088,1.6784,0 +2.083,-1.6784,-1.8556,-2.1268,0.84079,1.6784,0 +2.084,-1.6784,-1.8556,-2.1267,0.84071,1.6784,0 +2.085,-1.6784,-1.8555,-2.1267,0.84063,1.6784,0 +2.086,-1.6784,-1.8554,-2.1267,0.84054,1.6784,0 +2.087,-1.6784,-1.8554,-2.1267,0.84046,1.6784,0 +2.088,-1.6784,-1.8553,-2.1266,0.84038,1.6784,0 +2.089,-1.6784,-1.8553,-2.1266,0.8403,1.6784,0 +2.09,-1.6784,-1.8552,-2.1266,0.84021,1.6784,0 +2.091,-1.6784,-1.8551,-2.1266,0.84013,1.6784,0 +2.092,-1.6784,-1.8551,-2.1266,0.84005,1.6784,0 +2.093,-1.6784,-1.855,-2.1265,0.83996,1.6784,0 +2.094,-1.6784,-1.855,-2.1265,0.83988,1.6784,0 +2.095,-1.6784,-1.8549,-2.1265,0.8398,1.6784,0 +2.096,-1.6784,-1.8548,-2.1265,0.83971,1.6784,0 +2.097,-1.6784,-1.8548,-2.1264,0.83963,1.6784,0 +2.098,-1.6784,-1.8547,-2.1264,0.83955,1.6784,0 +2.099,-1.6784,-1.8547,-2.1264,0.83946,1.6784,0 +2.1,-1.6784,-1.8546,-2.1264,0.83938,1.6784,0 +2.101,-1.6784,-1.8545,-2.1264,0.8393,1.6784,0 +2.102,-1.6784,-1.8545,-2.1263,0.83921,1.6784,0 +2.103,-1.6784,-1.8544,-2.1263,0.83913,1.6784,0 +2.104,-1.6784,-1.8544,-2.1263,0.83905,1.6784,0 +2.105,-1.6784,-1.8543,-2.1263,0.83896,1.6784,0 +2.106,-1.6784,-1.8542,-2.1262,0.83888,1.6784,0 +2.107,-1.6784,-1.8542,-2.1262,0.8388,1.6784,0 +2.108,-1.6784,-1.8541,-2.1262,0.83872,1.6784,0 +2.109,-1.6784,-1.8541,-2.1262,0.83863,1.6784,0 +2.11,-1.6784,-1.854,-2.1261,0.83855,1.6784,0 +2.111,-1.6784,-1.8539,-2.1261,0.83847,1.6784,0 +2.112,-1.6784,-1.8539,-2.1261,0.83838,1.6784,0 +2.113,-1.6784,-1.8538,-2.1261,0.8383,1.6784,0 +2.114,-1.6784,-1.8538,-2.1261,0.83822,1.6784,0 +2.115,-1.6784,-1.8537,-2.126,0.83813,1.6784,0 +2.116,-1.6784,-1.8536,-2.126,0.83805,1.6784,0 +2.117,-1.6784,-1.8536,-2.126,0.83797,1.6784,0 +2.118,-1.6784,-1.8535,-2.126,0.83788,1.6784,0 +2.119,-1.6784,-1.8534,-2.1259,0.83779,1.6784,0 +2.12,-1.6785,-1.8534,-2.1259,0.83769,1.6785,0 +2.121,-1.6785,-1.8533,-2.1259,0.83758,1.6785,0 +2.122,-1.6785,-1.8532,-2.1258,0.83747,1.6785,0 +2.123,-1.6786,-1.8532,-2.1258,0.83735,1.6786,0 +2.124,-1.6786,-1.8531,-2.1257,0.83723,1.6786,0 +2.125,-1.6787,-1.853,-2.1257,0.8371,1.6787,0 +2.126,-1.6787,-1.853,-2.1256,0.83696,1.6787,0 +2.127,-1.6788,-1.8529,-2.1255,0.83681,1.6788,0 +2.128,-1.6789,-1.8528,-2.1255,0.83667,1.6789,0 +2.129,-1.6789,-1.8527,-2.1254,0.83652,1.6789,0 +2.13,-1.679,-1.8526,-2.1253,0.83637,1.679,0 +2.131,-1.6791,-1.8526,-2.1253,0.83622,1.6791,0 +2.132,-1.6792,-1.8525,-2.1252,0.83608,1.6792,0 +2.133,-1.6792,-1.8524,-2.1251,0.83593,1.6792,0 +2.134,-1.6793,-1.8523,-2.125,0.83578,1.6793,0 +2.135,-1.6794,-1.8523,-2.125,0.83563,1.6794,0 +2.136,-1.6794,-1.8522,-2.1249,0.83549,1.6794,0 +2.137,-1.6795,-1.8521,-2.1248,0.83534,1.6795,0 +2.138,-1.6796,-1.852,-2.1248,0.83519,1.6796,0 +2.139,-1.6797,-1.8519,-2.1247,0.83504,1.6797,0 +2.14,-1.6797,-1.8519,-2.1246,0.83489,1.6797,0 +2.141,-1.6798,-1.8518,-2.1246,0.83475,1.6798,0 +2.142,-1.6799,-1.8517,-2.1245,0.8346,1.6799,0 +2.143,-1.6799,-1.8516,-2.1244,0.83445,1.6799,0 +2.144,-1.68,-1.8515,-2.1244,0.8343,1.68,0 +2.145,-1.6801,-1.8515,-2.1243,0.83416,1.6801,0 +2.146,-1.6802,-1.8514,-2.1242,0.83401,1.6802,0 +2.147,-1.6802,-1.8513,-2.1241,0.83386,1.6802,0 +2.148,-1.6803,-1.8512,-2.1241,0.83371,1.6803,0 +2.149,-1.6804,-1.8512,-2.124,0.83356,1.6804,0 +2.15,-1.6805,-1.8511,-2.1239,0.83342,1.6805,0 +2.151,-1.6805,-1.851,-2.1239,0.83327,1.6805,0 +2.152,-1.6806,-1.8509,-2.1238,0.83312,1.6806,0 +2.153,-1.6807,-1.8508,-2.1237,0.83297,1.6807,0 +2.154,-1.6807,-1.8508,-2.1237,0.83283,1.6807,0 +2.155,-1.6808,-1.8507,-2.1236,0.83268,1.6808,0 +2.156,-1.6809,-1.8506,-2.1235,0.83253,1.6809,0 +2.157,-1.681,-1.8505,-2.1235,0.83238,1.681,0 +2.158,-1.681,-1.8504,-2.1234,0.83223,1.681,0 +2.159,-1.6811,-1.8504,-2.1233,0.83209,1.6811,0 +2.16,-1.6812,-1.8503,-2.1232,0.83194,1.6812,0 +2.161,-1.6812,-1.8502,-2.1232,0.83179,1.6812,0 +2.162,-1.6813,-1.8501,-2.1231,0.83164,1.6813,0 +2.163,-1.6814,-1.8501,-2.123,0.8315,1.6814,0 +2.164,-1.6815,-1.85,-2.123,0.83135,1.6815,0 +2.165,-1.6815,-1.8499,-2.1229,0.8312,1.6815,0 +2.166,-1.6816,-1.8498,-2.1228,0.83105,1.6816,0 +2.167,-1.6817,-1.8497,-2.1228,0.83091,1.6817,0 +2.168,-1.6818,-1.8497,-2.1227,0.83076,1.6818,0 +2.169,-1.6818,-1.8496,-2.1226,0.83061,1.6818,0 +2.17,-1.6819,-1.8495,-2.1226,0.83046,1.6819,0 +2.171,-1.682,-1.8494,-2.1225,0.83031,1.682,0 +2.172,-1.682,-1.8493,-2.1224,0.83017,1.682,0 +2.173,-1.6821,-1.8493,-2.1223,0.83002,1.6821,0 +2.174,-1.6822,-1.8492,-2.1223,0.82987,1.6822,0 +2.175,-1.6823,-1.8491,-2.1222,0.82972,1.6823,0 +2.176,-1.6823,-1.849,-2.1221,0.82958,1.6823,0 +2.177,-1.6824,-1.849,-2.1221,0.82943,1.6824,0 +2.178,-1.6825,-1.8489,-2.122,0.82928,1.6825,0 +2.179,-1.6825,-1.8488,-2.1219,0.82913,1.6825,0 +2.18,-1.6826,-1.8487,-2.1219,0.82898,1.6826,0 +2.181,-1.6827,-1.8486,-2.1218,0.82884,1.6827,0 +2.182,-1.6828,-1.8486,-2.1217,0.82869,1.6828,0 +2.183,-1.6828,-1.8485,-2.1217,0.82854,1.6828,0 +2.184,-1.6829,-1.8484,-2.1216,0.82839,1.6829,0 +2.185,-1.683,-1.8483,-2.1215,0.82825,1.683,0 +2.186,-1.6831,-1.8482,-2.1214,0.8281,1.6831,0 +2.187,-1.6831,-1.8482,-2.1214,0.82795,1.6831,0 +2.188,-1.6832,-1.8481,-2.1213,0.8278,1.6832,0 +2.189,-1.6833,-1.848,-2.1212,0.82765,1.6833,0 +2.19,-1.6833,-1.8479,-2.1212,0.82751,1.6833,0 +2.191,-1.6834,-1.8479,-2.1211,0.82736,1.6834,0 +2.192,-1.6835,-1.8478,-2.121,0.82721,1.6835,0 +2.193,-1.6836,-1.8477,-2.121,0.82706,1.6836,0 +2.194,-1.6836,-1.8476,-2.1209,0.82692,1.6836,0 +2.195,-1.6837,-1.8475,-2.1208,0.82677,1.6837,0 +2.196,-1.6838,-1.8475,-2.1208,0.82662,1.6838,0 +2.197,-1.6838,-1.8474,-2.1207,0.82647,1.6838,0 +2.198,-1.6839,-1.8473,-2.1206,0.82633,1.6839,0 +2.199,-1.684,-1.8472,-2.1205,0.82618,1.684,0 +2.2,-1.6841,-1.8471,-2.1205,0.82603,1.6841,0 +2.201,-1.6841,-1.8471,-2.1204,0.82588,1.6841,0 +2.202,-1.6842,-1.847,-2.1203,0.82572,1.6842,0 +2.203,-1.6843,-1.8469,-2.1202,0.82554,1.6843,0 +2.204,-1.6844,-1.8468,-2.1202,0.82537,1.6844,0 +2.205,-1.6845,-1.8467,-2.1201,0.82518,1.6845,0 +2.206,-1.6846,-1.8466,-2.12,0.82498,1.6846,0 +2.207,-1.6847,-1.8465,-2.1198,0.82477,1.6847,0 +2.208,-1.6849,-1.8464,-2.1197,0.82455,1.6849,0 +2.209,-1.685,-1.8463,-2.1196,0.82433,1.685,0 +2.21,-1.6851,-1.8462,-2.1195,0.82409,1.6851,0 +2.211,-1.6853,-1.8461,-2.1194,0.82385,1.6853,0 +2.212,-1.6854,-1.846,-2.1192,0.82362,1.6854,0 +2.213,-1.6856,-1.8459,-2.1191,0.82338,1.6856,0 +2.214,-1.6857,-1.8457,-2.119,0.82314,1.6857,0 +2.215,-1.6859,-1.8456,-2.1189,0.8229,1.6859,0 +2.216,-1.686,-1.8455,-2.1187,0.82266,1.686,0 +2.217,-1.6861,-1.8454,-2.1186,0.82242,1.6861,0 +2.218,-1.6863,-1.8453,-2.1185,0.82218,1.6863,0 +2.219,-1.6864,-1.8452,-2.1184,0.82194,1.6864,0 +2.22,-1.6866,-1.8451,-2.1182,0.8217,1.6866,0 +2.221,-1.6867,-1.845,-2.1181,0.82146,1.6867,0 +2.222,-1.6869,-1.8448,-2.118,0.82122,1.6869,0 +2.223,-1.687,-1.8447,-2.1179,0.82098,1.687,0 +2.224,-1.6872,-1.8446,-2.1177,0.82074,1.6872,0 +2.225,-1.6873,-1.8445,-2.1176,0.82051,1.6873,0 +2.226,-1.6874,-1.8444,-2.1175,0.82027,1.6874,0 +2.227,-1.6876,-1.8443,-2.1173,0.82003,1.6876,0 +2.228,-1.6877,-1.8442,-2.1172,0.81979,1.6877,0 +2.229,-1.6879,-1.844,-2.1171,0.81955,1.6879,0 +2.23,-1.688,-1.8439,-2.117,0.81931,1.688,0 +2.231,-1.6882,-1.8438,-2.1168,0.81907,1.6882,0 +2.232,-1.6883,-1.8437,-2.1167,0.81883,1.6883,0 +2.233,-1.6884,-1.8436,-2.1166,0.81859,1.6884,0 +2.234,-1.6886,-1.8435,-2.1165,0.81835,1.6886,0 +2.235,-1.6887,-1.8434,-2.1163,0.81811,1.6887,0 +2.236,-1.6889,-1.8433,-2.1162,0.81787,1.6889,0 +2.237,-1.689,-1.8431,-2.1161,0.81764,1.689,0 +2.238,-1.6892,-1.843,-2.116,0.8174,1.6892,0 +2.239,-1.6893,-1.8429,-2.1158,0.81716,1.6893,0 +2.24,-1.6895,-1.8428,-2.1157,0.81692,1.6895,0 +2.241,-1.6896,-1.8427,-2.1156,0.81668,1.6896,0 +2.242,-1.6897,-1.8426,-2.1154,0.81644,1.6897,0 +2.243,-1.6899,-1.8425,-2.1153,0.8162,1.6899,0 +2.244,-1.69,-1.8424,-2.1152,0.81596,1.69,0 +2.245,-1.6902,-1.8422,-2.1151,0.81572,1.6902,0 +2.246,-1.6903,-1.8421,-2.1149,0.81548,1.6903,0 +2.247,-1.6905,-1.842,-2.1148,0.81524,1.6905,0 +2.248,-1.6906,-1.8419,-2.1147,0.815,1.6906,0 +2.249,-1.6907,-1.8418,-2.1146,0.81476,1.6907,0 +2.25,-1.6909,-1.8417,-2.1144,0.81453,1.6909,0 +2.251,-1.691,-1.8416,-2.1143,0.81429,1.691,0 +2.252,-1.6912,-1.8415,-2.1142,0.81405,1.6912,0 +2.253,-1.6913,-1.8413,-2.1141,0.81381,1.6913,0 +2.254,-1.6915,-1.8412,-2.1139,0.81357,1.6915,0 +2.255,-1.6916,-1.8411,-2.1138,0.81333,1.6916,0 +2.256,-1.6918,-1.841,-2.1137,0.81309,1.6918,0 +2.257,-1.6919,-1.8409,-2.1136,0.81285,1.6919,0 +2.258,-1.692,-1.8408,-2.1134,0.81261,1.692,0 +2.259,-1.6922,-1.8407,-2.1133,0.81237,1.6922,0 +2.26,-1.6923,-1.8406,-2.1132,0.81213,1.6923,0 +2.261,-1.6925,-1.8404,-2.113,0.81189,1.6925,0 +2.262,-1.6926,-1.8403,-2.1129,0.81166,1.6926,0 +2.263,-1.6928,-1.8402,-2.1128,0.81142,1.6928,0 +2.264,-1.6929,-1.8401,-2.1127,0.81118,1.6929,0 +2.265,-1.693,-1.84,-2.1125,0.81094,1.693,0 +2.266,-1.6932,-1.8399,-2.1124,0.8107,1.6932,0 +2.267,-1.6933,-1.8398,-2.1123,0.81046,1.6933,0 +2.268,-1.6935,-1.8397,-2.1122,0.81022,1.6935,0 +2.269,-1.6936,-1.8395,-2.112,0.80998,1.6936,0 +2.27,-1.6938,-1.8394,-2.1119,0.80974,1.6938,0 +2.271,-1.6939,-1.8393,-2.1118,0.8095,1.6939,0 +2.272,-1.6941,-1.8392,-2.1117,0.80926,1.6941,0 +2.273,-1.6942,-1.8391,-2.1115,0.80902,1.6942,0 +2.274,-1.6943,-1.839,-2.1114,0.80878,1.6943,0 +2.275,-1.6945,-1.8389,-2.1113,0.80855,1.6945,0 +2.276,-1.6946,-1.8387,-2.1112,0.80831,1.6946,0 +2.277,-1.6948,-1.8386,-2.111,0.80807,1.6948,0 +2.278,-1.6949,-1.8385,-2.1109,0.80783,1.6949,0 +2.279,-1.6951,-1.8384,-2.1108,0.80759,1.6951,0 +2.28,-1.6952,-1.8383,-2.1106,0.80735,1.6952,0 +2.281,-1.6953,-1.8382,-2.1105,0.80711,1.6953,0 +2.282,-1.6955,-1.8381,-2.1104,0.80687,1.6955,0 +2.283,-1.6956,-1.838,-2.1103,0.80663,1.6956,0 +2.284,-1.6958,-1.8378,-2.1101,0.80639,1.6958,0 +2.285,-1.6959,-1.8377,-2.11,0.80614,1.6959,0 +2.286,-1.6961,-1.8376,-2.1099,0.80589,1.6961,0 +2.287,-1.6963,-1.8375,-2.1097,0.80564,1.6963,0 +2.288,-1.6964,-1.8374,-2.1096,0.80538,1.6964,0 +2.289,-1.6966,-1.8373,-2.1094,0.80511,1.6966,0 +2.29,-1.6968,-1.8372,-2.1093,0.80484,1.6968,0 +2.291,-1.697,-1.837,-2.1091,0.80457,1.697,0 +2.292,-1.6972,-1.8369,-2.109,0.80429,1.6972,0 +2.293,-1.6973,-1.8368,-2.1088,0.804,1.6973,0 +2.294,-1.6975,-1.8367,-2.1086,0.80372,1.6975,0 +2.295,-1.6977,-1.8366,-2.1084,0.80343,1.6977,0 +2.296,-1.6979,-1.8365,-2.1083,0.80314,1.6979,0 +2.297,-1.6981,-1.8363,-2.1081,0.80286,1.6981,0 +2.298,-1.6983,-1.8362,-2.1079,0.80257,1.6983,0 +2.299,-1.6985,-1.8361,-2.1078,0.80229,1.6985,0 +2.3,-1.6987,-1.836,-2.1076,0.802,1.6987,0 +2.301,-1.6989,-1.8359,-2.1074,0.80171,1.6989,0 +2.302,-1.6991,-1.8358,-2.1073,0.80143,1.6991,0 +2.303,-1.6993,-1.8356,-2.1071,0.80114,1.6993,0 +2.304,-1.6995,-1.8355,-2.1069,0.80085,1.6995,0 +2.305,-1.6997,-1.8354,-2.1068,0.80057,1.6997,0 +2.306,-1.6999,-1.8353,-2.1066,0.80028,1.6999,0 +2.307,-1.7001,-1.8352,-2.1064,0.8,1.7001,0 +2.308,-1.7003,-1.835,-2.1063,0.79971,1.7003,0 +2.309,-1.7005,-1.8349,-2.1061,0.79942,1.7005,0 +2.31,-1.7007,-1.8348,-2.1059,0.79914,1.7007,0 +2.311,-1.7009,-1.8347,-2.1057,0.79885,1.7009,0 +2.312,-1.7011,-1.8346,-2.1056,0.79857,1.7011,0 +2.313,-1.7013,-1.8345,-2.1054,0.79828,1.7013,0 +2.314,-1.7015,-1.8343,-2.1052,0.79799,1.7015,0 +2.315,-1.7017,-1.8342,-2.1051,0.79771,1.7017,0 +2.316,-1.7019,-1.8341,-2.1049,0.79742,1.7019,0 +2.317,-1.7021,-1.834,-2.1047,0.79714,1.7021,0 +2.318,-1.7023,-1.8339,-2.1046,0.79685,1.7023,0 +2.319,-1.7025,-1.8338,-2.1044,0.79656,1.7025,0 +2.32,-1.7027,-1.8336,-2.1042,0.79628,1.7027,0 +2.321,-1.7029,-1.8335,-2.1041,0.79599,1.7029,0 +2.322,-1.7031,-1.8334,-2.1039,0.7957,1.7031,0 +2.323,-1.7033,-1.8333,-2.1037,0.79542,1.7033,0 +2.324,-1.7035,-1.8332,-2.1036,0.79513,1.7035,0 +2.325,-1.7037,-1.8331,-2.1034,0.79485,1.7037,0 +2.326,-1.7039,-1.8329,-2.1032,0.79456,1.7039,0 +2.327,-1.7041,-1.8328,-2.103,0.79427,1.7041,0 +2.328,-1.7043,-1.8327,-2.1029,0.79399,1.7043,0 +2.329,-1.7045,-1.8326,-2.1027,0.7937,1.7045,0 +2.33,-1.7047,-1.8325,-2.1025,0.79342,1.7047,0 +2.331,-1.7049,-1.8324,-2.1024,0.79313,1.7049,0 +2.332,-1.7051,-1.8322,-2.1022,0.79284,1.7051,0 +2.333,-1.7053,-1.8321,-2.102,0.79256,1.7053,0 +2.334,-1.7055,-1.832,-2.1019,0.79227,1.7055,0 +2.335,-1.7057,-1.8319,-2.1017,0.79198,1.7057,0 +2.336,-1.7059,-1.8318,-2.1015,0.7917,1.7059,0 +2.337,-1.7061,-1.8316,-2.1014,0.79141,1.7061,0 +2.338,-1.7063,-1.8315,-2.1012,0.79113,1.7063,0 +2.339,-1.7065,-1.8314,-2.101,0.79084,1.7065,0 +2.34,-1.7067,-1.8313,-2.1009,0.79055,1.7067,0 +2.341,-1.7069,-1.8312,-2.1007,0.79027,1.7069,0 +2.342,-1.7071,-1.8311,-2.1005,0.78998,1.7071,0 +2.343,-1.7072,-1.8309,-2.1003,0.7897,1.7072,0 +2.344,-1.7074,-1.8308,-2.1002,0.78941,1.7074,0 +2.345,-1.7076,-1.8307,-2.1,0.78912,1.7076,0 +2.346,-1.7078,-1.8306,-2.0998,0.78884,1.7078,0 +2.347,-1.708,-1.8305,-2.0997,0.78855,1.708,0 +2.348,-1.7082,-1.8304,-2.0995,0.78827,1.7082,0 +2.349,-1.7084,-1.8302,-2.0993,0.78798,1.7084,0 +2.35,-1.7086,-1.8301,-2.0992,0.78769,1.7086,0 +2.351,-1.7088,-1.83,-2.099,0.78741,1.7088,0 +2.352,-1.709,-1.8299,-2.0988,0.78712,1.709,0 +2.353,-1.7092,-1.8298,-2.0987,0.78683,1.7092,0 +2.354,-1.7094,-1.8297,-2.0985,0.78655,1.7094,0 +2.355,-1.7096,-1.8295,-2.0983,0.78626,1.7096,0 +2.356,-1.7098,-1.8294,-2.0982,0.78598,1.7098,0 +2.357,-1.71,-1.8293,-2.098,0.78569,1.71,0 +2.358,-1.7102,-1.8292,-2.0978,0.7854,1.7102,0 +2.359,-1.7104,-1.8291,-2.0976,0.78512,1.7104,0 +2.36,-1.7106,-1.8289,-2.0975,0.78483,1.7106,0 +2.361,-1.7108,-1.8288,-2.0973,0.78455,1.7108,0 +2.362,-1.711,-1.8287,-2.0971,0.78426,1.711,0 +2.363,-1.7112,-1.8286,-2.097,0.78397,1.7112,0 +2.364,-1.7114,-1.8285,-2.0968,0.78369,1.7114,0 +2.365,-1.7116,-1.8284,-2.0966,0.7834,1.7116,0 +2.366,-1.7118,-1.8282,-2.0965,0.78312,1.7118,0 +2.367,-1.712,-1.8281,-2.0963,0.78282,1.712,0 +2.368,-1.7122,-1.828,-2.0961,0.78253,1.7122,0 +2.369,-1.7124,-1.8279,-2.0959,0.78222,1.7124,0 +2.37,-1.7127,-1.8278,-2.0957,0.78191,1.7127,0 +2.371,-1.7129,-1.8276,-2.0955,0.78158,1.7129,0 +2.372,-1.7131,-1.8275,-2.0953,0.78126,1.7131,0 +2.373,-1.7134,-1.8274,-2.0951,0.78092,1.7134,0 +2.374,-1.7136,-1.8273,-2.0949,0.78057,1.7136,0 +2.375,-1.7139,-1.8272,-2.0947,0.78022,1.7139,0 +2.376,-1.7142,-1.827,-2.0944,0.77986,1.7142,0 +2.377,-1.7145,-1.8269,-2.0942,0.7795,1.7145,0 +2.378,-1.7147,-1.8268,-2.094,0.77914,1.7147,0 +2.379,-1.715,-1.8266,-2.0937,0.77878,1.715,0 +2.38,-1.7153,-1.8265,-2.0935,0.77842,1.7153,0 +2.381,-1.7155,-1.8264,-2.0933,0.77805,1.7155,0 +2.382,-1.7158,-1.8263,-2.093,0.77769,1.7158,0 +2.383,-1.7161,-1.8261,-2.0928,0.77733,1.7161,0 +2.384,-1.7164,-1.826,-2.0925,0.77697,1.7164,0 +2.385,-1.7166,-1.8259,-2.0923,0.7766,1.7166,0 +2.386,-1.7169,-1.8258,-2.0921,0.77624,1.7169,0 +2.387,-1.7172,-1.8256,-2.0918,0.77588,1.7172,0 +2.388,-1.7175,-1.8255,-2.0916,0.77552,1.7175,0 +2.389,-1.7177,-1.8254,-2.0914,0.77516,1.7177,0 +2.39,-1.718,-1.8253,-2.0911,0.77479,1.718,0 +2.391,-1.7183,-1.8251,-2.0909,0.77443,1.7183,0 +2.392,-1.7186,-1.825,-2.0907,0.77407,1.7186,0 +2.393,-1.7188,-1.8249,-2.0904,0.77371,1.7188,0 +2.394,-1.7191,-1.8248,-2.0902,0.77335,1.7191,0 +2.395,-1.7194,-1.8246,-2.09,0.77298,1.7194,0 +2.396,-1.7197,-1.8245,-2.0897,0.77262,1.7197,0 +2.397,-1.7199,-1.8244,-2.0895,0.77226,1.7199,0 +2.398,-1.7202,-1.8242,-2.0892,0.7719,1.7202,0 +2.399,-1.7205,-1.8241,-2.089,0.77153,1.7205,0 +2.4,-1.7208,-1.824,-2.0888,0.77117,1.7208,0 +2.401,-1.721,-1.8239,-2.0885,0.77081,1.721,0 +2.402,-1.7213,-1.8237,-2.0883,0.77045,1.7213,0 +2.403,-1.7216,-1.8236,-2.0881,0.77009,1.7216,0 +2.404,-1.7219,-1.8235,-2.0878,0.76972,1.7219,0 +2.405,-1.7221,-1.8234,-2.0876,0.76936,1.7221,0 +2.406,-1.7224,-1.8232,-2.0874,0.769,1.7224,0 +2.407,-1.7227,-1.8231,-2.0871,0.76864,1.7227,0 +2.408,-1.7229,-1.823,-2.0869,0.76828,1.7229,0 +2.409,-1.7232,-1.8229,-2.0867,0.76791,1.7232,0 +2.41,-1.7235,-1.8227,-2.0864,0.76755,1.7235,0 +2.411,-1.7238,-1.8226,-2.0862,0.76719,1.7238,0 +2.412,-1.724,-1.8225,-2.0859,0.76683,1.724,0 +2.413,-1.7243,-1.8223,-2.0857,0.76646,1.7243,0 +2.414,-1.7246,-1.8222,-2.0855,0.7661,1.7246,0 +2.415,-1.7249,-1.8221,-2.0852,0.76574,1.7249,0 +2.416,-1.7251,-1.822,-2.085,0.76538,1.7251,0 +2.417,-1.7254,-1.8218,-2.0848,0.76502,1.7254,0 +2.418,-1.7257,-1.8217,-2.0845,0.76465,1.7257,0 +2.419,-1.726,-1.8216,-2.0843,0.76429,1.726,0 +2.42,-1.7262,-1.8215,-2.0841,0.76393,1.7262,0 +2.421,-1.7265,-1.8213,-2.0838,0.76357,1.7265,0 +2.422,-1.7268,-1.8212,-2.0836,0.76321,1.7268,0 +2.423,-1.7271,-1.8211,-2.0834,0.76284,1.7271,0 +2.424,-1.7273,-1.821,-2.0831,0.76248,1.7273,0 +2.425,-1.7276,-1.8208,-2.0829,0.76212,1.7276,0 +2.426,-1.7279,-1.8207,-2.0826,0.76176,1.7279,0 +2.427,-1.7282,-1.8206,-2.0824,0.76139,1.7282,0 +2.428,-1.7284,-1.8205,-2.0822,0.76103,1.7284,0 +2.429,-1.7287,-1.8203,-2.0819,0.76067,1.7287,0 +2.43,-1.729,-1.8202,-2.0817,0.76031,1.729,0 +2.431,-1.7293,-1.8201,-2.0815,0.75995,1.7293,0 +2.432,-1.7295,-1.8199,-2.0812,0.75958,1.7295,0 +2.433,-1.7298,-1.8198,-2.081,0.75922,1.7298,0 +2.434,-1.7301,-1.8197,-2.0808,0.75886,1.7301,0 +2.435,-1.7303,-1.8196,-2.0805,0.7585,1.7303,0 +2.436,-1.7306,-1.8194,-2.0803,0.75814,1.7306,0 +2.437,-1.7309,-1.8193,-2.0801,0.75777,1.7309,0 +2.438,-1.7312,-1.8192,-2.0798,0.75741,1.7312,0 +2.439,-1.7314,-1.8191,-2.0796,0.75705,1.7314,0 +2.44,-1.7317,-1.8189,-2.0793,0.75669,1.7317,0 +2.441,-1.732,-1.8188,-2.0791,0.75632,1.732,0 +2.442,-1.7323,-1.8187,-2.0789,0.75596,1.7323,0 +2.443,-1.7325,-1.8186,-2.0786,0.7556,1.7325,0 +2.444,-1.7328,-1.8184,-2.0784,0.75524,1.7328,0 +2.445,-1.7331,-1.8183,-2.0782,0.75488,1.7331,0 +2.446,-1.7334,-1.8182,-2.0779,0.75451,1.7334,0 +2.447,-1.7336,-1.8181,-2.0777,0.75415,1.7336,0 +2.448,-1.7339,-1.8179,-2.0775,0.75379,1.7339,0 +2.449,-1.7342,-1.8178,-2.0772,0.75343,1.7342,0 +2.45,-1.7345,-1.8177,-2.077,0.75306,1.7345,0 +2.451,-1.7347,-1.8175,-2.0767,0.7527,1.7347,0 +2.452,-1.735,-1.8174,-2.0765,0.75233,1.735,0 +2.453,-1.7353,-1.8173,-2.0762,0.75196,1.7353,0 +2.454,-1.7356,-1.8172,-2.076,0.75158,1.7356,0 +2.455,-1.7359,-1.8171,-2.0757,0.7512,1.7359,0 +2.456,-1.7362,-1.8169,-2.0755,0.75082,1.7362,0 +2.457,-1.7364,-1.8168,-2.0752,0.75044,1.7364,0 +2.458,-1.7367,-1.8167,-2.075,0.75006,1.7367,0 +2.459,-1.737,-1.8166,-2.0747,0.74967,1.737,0 +2.46,-1.7373,-1.8164,-2.0744,0.74928,1.7373,0 +2.461,-1.7376,-1.8163,-2.0742,0.74889,1.7376,0 +2.462,-1.7379,-1.8162,-2.0739,0.7485,1.7379,0 +2.463,-1.7382,-1.8161,-2.0736,0.74811,1.7382,0 +2.464,-1.7385,-1.816,-2.0733,0.74772,1.7385,0 +2.465,-1.7388,-1.8158,-2.0731,0.74733,1.7388,0 +2.466,-1.7391,-1.8157,-2.0728,0.74695,1.7391,0 +2.467,-1.7394,-1.8156,-2.0725,0.74656,1.7394,0 +2.468,-1.7397,-1.8155,-2.0723,0.74617,1.7397,0 +2.469,-1.74,-1.8154,-2.072,0.74578,1.74,0 +2.47,-1.7403,-1.8152,-2.0717,0.74539,1.7403,0 +2.471,-1.7405,-1.8151,-2.0715,0.745,1.7405,0 +2.472,-1.7408,-1.815,-2.0712,0.74461,1.7408,0 +2.473,-1.7411,-1.8149,-2.0709,0.74422,1.7411,0 +2.474,-1.7414,-1.8148,-2.0707,0.74383,1.7414,0 +2.475,-1.7417,-1.8146,-2.0704,0.74345,1.7417,0 +2.476,-1.742,-1.8145,-2.0701,0.74306,1.742,0 +2.477,-1.7423,-1.8144,-2.0699,0.74267,1.7423,0 +2.478,-1.7426,-1.8143,-2.0696,0.74228,1.7426,0 +2.479,-1.7429,-1.8142,-2.0693,0.74189,1.7429,0 +2.48,-1.7432,-1.814,-2.069,0.7415,1.7432,0 +2.481,-1.7435,-1.8139,-2.0688,0.74111,1.7435,0 +2.482,-1.7438,-1.8138,-2.0685,0.74072,1.7438,0 +2.483,-1.7441,-1.8137,-2.0682,0.74033,1.7441,0 +2.484,-1.7444,-1.8136,-2.068,0.73995,1.7444,0 +2.485,-1.7447,-1.8134,-2.0677,0.73956,1.7447,0 +2.486,-1.7449,-1.8133,-2.0674,0.73917,1.7449,0 +2.487,-1.7452,-1.8132,-2.0672,0.73878,1.7452,0 +2.488,-1.7455,-1.8131,-2.0669,0.73839,1.7455,0 +2.489,-1.7458,-1.813,-2.0666,0.738,1.7458,0 +2.49,-1.7461,-1.8128,-2.0664,0.73761,1.7461,0 +2.491,-1.7464,-1.8127,-2.0661,0.73722,1.7464,0 +2.492,-1.7467,-1.8126,-2.0658,0.73684,1.7467,0 +2.493,-1.747,-1.8125,-2.0656,0.73645,1.747,0 +2.494,-1.7473,-1.8124,-2.0653,0.73606,1.7473,0 +2.495,-1.7476,-1.8122,-2.065,0.73567,1.7476,0 +2.496,-1.7479,-1.8121,-2.0647,0.73528,1.7479,0 +2.497,-1.7482,-1.812,-2.0645,0.73489,1.7482,0 +2.498,-1.7485,-1.8119,-2.0642,0.7345,1.7485,0 +2.499,-1.7488,-1.8118,-2.0639,0.73411,1.7488,0 +2.5,-1.7491,-1.8116,-2.0637,0.73372,1.7491,0 +2.501,-1.7493,-1.8115,-2.0634,0.73334,1.7493,0 +2.502,-1.7496,-1.8114,-2.0631,0.73295,1.7496,0 +2.503,-1.7499,-1.8113,-2.0629,0.73256,1.7499,0 +2.504,-1.7502,-1.8112,-2.0626,0.73217,1.7502,0 +2.505,-1.7505,-1.811,-2.0623,0.73178,1.7505,0 +2.506,-1.7508,-1.8109,-2.0621,0.73139,1.7508,0 +2.507,-1.7511,-1.8108,-2.0618,0.731,1.7511,0 +2.508,-1.7514,-1.8107,-2.0615,0.73061,1.7514,0 +2.509,-1.7517,-1.8106,-2.0613,0.73022,1.7517,0 +2.51,-1.752,-1.8104,-2.061,0.72984,1.752,0 +2.511,-1.7523,-1.8103,-2.0607,0.72945,1.7523,0 +2.512,-1.7526,-1.8102,-2.0604,0.72906,1.7526,0 +2.513,-1.7529,-1.8101,-2.0602,0.72867,1.7529,0 +2.514,-1.7532,-1.81,-2.0599,0.72828,1.7532,0 +2.515,-1.7535,-1.8098,-2.0596,0.72789,1.7535,0 +2.516,-1.7537,-1.8097,-2.0594,0.7275,1.7537,0 +2.517,-1.754,-1.8096,-2.0591,0.72711,1.754,0 +2.518,-1.7543,-1.8095,-2.0588,0.72672,1.7543,0 +2.519,-1.7546,-1.8094,-2.0586,0.72634,1.7546,0 +2.52,-1.7549,-1.8092,-2.0583,0.72595,1.7549,0 +2.521,-1.7552,-1.8091,-2.058,0.72556,1.7552,0 +2.522,-1.7555,-1.809,-2.0578,0.72517,1.7555,0 +2.523,-1.7558,-1.8089,-2.0575,0.72478,1.7558,0 +2.524,-1.7561,-1.8088,-2.0572,0.72439,1.7561,0 +2.525,-1.7564,-1.8086,-2.0569,0.724,1.7564,0 +2.526,-1.7567,-1.8085,-2.0567,0.72361,1.7567,0 +2.527,-1.757,-1.8084,-2.0564,0.72323,1.757,0 +2.528,-1.7573,-1.8083,-2.0561,0.72284,1.7573,0 +2.529,-1.7576,-1.8082,-2.0559,0.72245,1.7576,0 +2.53,-1.7579,-1.808,-2.0556,0.72206,1.7579,0 +2.531,-1.7581,-1.8079,-2.0553,0.72167,1.7581,0 +2.532,-1.7584,-1.8078,-2.0551,0.72128,1.7584,0 +2.533,-1.7587,-1.8077,-2.0548,0.72089,1.7587,0 +2.534,-1.759,-1.8076,-2.0545,0.7205,1.759,0 +2.535,-1.7593,-1.8075,-2.0542,0.7201,1.7593,0 +2.536,-1.7596,-1.8073,-2.054,0.7197,1.7596,0 +2.537,-1.7599,-1.8072,-2.0537,0.7193,1.7599,0 +2.538,-1.7602,-1.8071,-2.0534,0.7189,1.7602,0 +2.539,-1.7605,-1.807,-2.0531,0.71849,1.7605,0 +2.54,-1.7608,-1.8069,-2.0528,0.71808,1.7608,0 +2.541,-1.7612,-1.8068,-2.0525,0.71767,1.7612,0 +2.542,-1.7615,-1.8067,-2.0522,0.71726,1.7615,0 +2.543,-1.7618,-1.8065,-2.0519,0.71684,1.7618,0 +2.544,-1.7621,-1.8064,-2.0516,0.71643,1.7621,0 +2.545,-1.7624,-1.8063,-2.0513,0.71601,1.7624,0 +2.546,-1.7627,-1.8062,-2.051,0.7156,1.7627,0 +2.547,-1.763,-1.8061,-2.0507,0.71518,1.763,0 +2.548,-1.7633,-1.806,-2.0504,0.71477,1.7633,0 +2.549,-1.7636,-1.8059,-2.0501,0.71435,1.7636,0 +2.55,-1.764,-1.8058,-2.0498,0.71394,1.764,0 +2.551,-1.7643,-1.8057,-2.0494,0.71353,1.7643,0 +2.552,-1.7646,-1.8056,-2.0491,0.71311,1.7646,0 +2.553,-1.7649,-1.8055,-2.0488,0.7127,1.7649,0 +2.554,-1.7652,-1.8053,-2.0485,0.71228,1.7652,0 +2.555,-1.7655,-1.8052,-2.0482,0.71187,1.7655,0 +2.556,-1.7658,-1.8051,-2.0479,0.71145,1.7658,0 +2.557,-1.7661,-1.805,-2.0476,0.71104,1.7661,0 +2.558,-1.7664,-1.8049,-2.0473,0.71062,1.7664,0 +2.559,-1.7668,-1.8048,-2.047,0.71021,1.7668,0 +2.56,-1.7671,-1.8047,-2.0467,0.70979,1.7671,0 +2.561,-1.7674,-1.8046,-2.0464,0.70938,1.7674,0 +2.562,-1.7677,-1.8045,-2.0461,0.70896,1.7677,0 +2.563,-1.768,-1.8044,-2.0458,0.70855,1.768,0 +2.564,-1.7683,-1.8042,-2.0455,0.70813,1.7683,0 +2.565,-1.7686,-1.8041,-2.0452,0.70772,1.7686,0 +2.566,-1.7689,-1.804,-2.0449,0.70731,1.7689,0 +2.567,-1.7692,-1.8039,-2.0446,0.70689,1.7692,0 +2.568,-1.7696,-1.8038,-2.0443,0.70648,1.7696,0 +2.569,-1.7699,-1.8037,-2.044,0.70606,1.7699,0 +2.57,-1.7702,-1.8036,-2.0437,0.70565,1.7702,0 +2.571,-1.7705,-1.8035,-2.0434,0.70523,1.7705,0 +2.572,-1.7708,-1.8034,-2.043,0.70482,1.7708,0 +2.573,-1.7711,-1.8033,-2.0427,0.7044,1.7711,0 +2.574,-1.7714,-1.8031,-2.0424,0.70399,1.7714,0 +2.575,-1.7717,-1.803,-2.0421,0.70357,1.7717,0 +2.576,-1.772,-1.8029,-2.0418,0.70316,1.772,0 +2.577,-1.7724,-1.8028,-2.0415,0.70274,1.7724,0 +2.578,-1.7727,-1.8027,-2.0412,0.70233,1.7727,0 +2.579,-1.773,-1.8026,-2.0409,0.70192,1.773,0 +2.58,-1.7733,-1.8025,-2.0406,0.7015,1.7733,0 +2.581,-1.7736,-1.8024,-2.0403,0.70109,1.7736,0 +2.582,-1.7739,-1.8023,-2.04,0.70067,1.7739,0 +2.583,-1.7742,-1.8022,-2.0397,0.70026,1.7742,0 +2.584,-1.7745,-1.802,-2.0394,0.69984,1.7745,0 +2.585,-1.7748,-1.8019,-2.0391,0.69943,1.7748,0 +2.586,-1.7752,-1.8018,-2.0388,0.69901,1.7752,0 +2.587,-1.7755,-1.8017,-2.0385,0.6986,1.7755,0 +2.588,-1.7758,-1.8016,-2.0382,0.69818,1.7758,0 +2.589,-1.7761,-1.8015,-2.0379,0.69777,1.7761,0 +2.59,-1.7764,-1.8014,-2.0376,0.69735,1.7764,0 +2.591,-1.7767,-1.8013,-2.0373,0.69694,1.7767,0 +2.592,-1.777,-1.8012,-2.037,0.69652,1.777,0 +2.593,-1.7773,-1.8011,-2.0366,0.69611,1.7773,0 +2.594,-1.7776,-1.8009,-2.0363,0.6957,1.7776,0 +2.595,-1.778,-1.8008,-2.036,0.69528,1.778,0 +2.596,-1.7783,-1.8007,-2.0357,0.69487,1.7783,0 +2.597,-1.7786,-1.8006,-2.0354,0.69445,1.7786,0 +2.598,-1.7789,-1.8005,-2.0351,0.69404,1.7789,0 +2.599,-1.7792,-1.8004,-2.0348,0.69362,1.7792,0 +2.6,-1.7795,-1.8003,-2.0345,0.69321,1.7795,0 +2.601,-1.7798,-1.8002,-2.0342,0.69279,1.7798,0 +2.602,-1.7801,-1.8001,-2.0339,0.69238,1.7801,0 +2.603,-1.7804,-1.8,-2.0336,0.69196,1.7804,0 +2.604,-1.7808,-1.7998,-2.0333,0.69155,1.7808,0 +2.605,-1.7811,-1.7997,-2.033,0.69113,1.7811,0 +2.606,-1.7814,-1.7996,-2.0327,0.69072,1.7814,0 +2.607,-1.7817,-1.7995,-2.0324,0.69031,1.7817,0 +2.608,-1.782,-1.7994,-2.0321,0.68989,1.782,0 +2.609,-1.7823,-1.7993,-2.0318,0.68948,1.7823,0 +2.61,-1.7826,-1.7992,-2.0315,0.68906,1.7826,0 +2.611,-1.7829,-1.7991,-2.0312,0.68865,1.7829,0 +2.612,-1.7832,-1.799,-2.0309,0.68823,1.7832,0 +2.613,-1.7836,-1.7989,-2.0306,0.68782,1.7836,0 +2.614,-1.7839,-1.7987,-2.0302,0.6874,1.7839,0 +2.615,-1.7842,-1.7986,-2.0299,0.68699,1.7842,0 +2.616,-1.7845,-1.7985,-2.0296,0.68657,1.7845,0 +2.617,-1.7848,-1.7984,-2.0293,0.68615,1.7848,0 +2.618,-1.7851,-1.7983,-2.029,0.68572,1.7851,0 +2.619,-1.7854,-1.7982,-2.0287,0.68528,1.7854,0 +2.62,-1.7858,-1.7981,-2.0284,0.68484,1.7858,0 +2.621,-1.7861,-1.798,-2.028,0.6844,1.7861,0 +2.622,-1.7864,-1.7979,-2.0277,0.68395,1.7864,0 +2.623,-1.7867,-1.7978,-2.0273,0.68349,1.7867,0 +2.624,-1.7871,-1.7976,-2.027,0.68303,1.7871,0 +2.625,-1.7874,-1.7975,-2.0266,0.68257,1.7874,0 +2.626,-1.7877,-1.7974,-2.0263,0.6821,1.7877,0 +2.627,-1.788,-1.7973,-2.0259,0.68164,1.788,0 +2.628,-1.7884,-1.7972,-2.0256,0.68117,1.7884,0 +2.629,-1.7887,-1.7971,-2.0252,0.68071,1.7887,0 +2.63,-1.789,-1.797,-2.0249,0.68024,1.789,0 +2.631,-1.7893,-1.7969,-2.0245,0.67977,1.7893,0 +2.632,-1.7897,-1.7968,-2.0241,0.67931,1.7897,0 +2.633,-1.79,-1.7966,-2.0238,0.67884,1.79,0 +2.634,-1.7903,-1.7965,-2.0234,0.67838,1.7903,0 +2.635,-1.7907,-1.7964,-2.0231,0.67791,1.7907,0 +2.636,-1.791,-1.7963,-2.0227,0.67745,1.791,0 +2.637,-1.7913,-1.7962,-2.0224,0.67698,1.7913,0 +2.638,-1.7916,-1.7961,-2.022,0.67651,1.7916,0 +2.639,-1.792,-1.796,-2.0217,0.67605,1.792,0 +2.64,-1.7923,-1.7959,-2.0213,0.67558,1.7923,0 +2.641,-1.7926,-1.7958,-2.021,0.67512,1.7926,0 +2.642,-1.793,-1.7956,-2.0206,0.67465,1.793,0 +2.643,-1.7933,-1.7955,-2.0202,0.67418,1.7933,0 +2.644,-1.7936,-1.7954,-2.0199,0.67372,1.7936,0 +2.645,-1.7939,-1.7953,-2.0195,0.67325,1.7939,0 +2.646,-1.7943,-1.7952,-2.0192,0.67279,1.7943,0 +2.647,-1.7946,-1.7951,-2.0188,0.67232,1.7946,0 +2.648,-1.7949,-1.795,-2.0185,0.67186,1.7949,0 +2.649,-1.7952,-1.7949,-2.0181,0.67139,1.7952,0 +2.65,-1.7956,-1.7948,-2.0178,0.67092,1.7956,0 +2.651,-1.7959,-1.7946,-2.0174,0.67046,1.7959,0 +2.652,-1.7962,-1.7945,-2.0171,0.66999,1.7962,0 +2.653,-1.7966,-1.7944,-2.0167,0.66953,1.7966,0 +2.654,-1.7969,-1.7943,-2.0163,0.66906,1.7969,0 +2.655,-1.7972,-1.7942,-2.016,0.66859,1.7972,0 +2.656,-1.7975,-1.7941,-2.0156,0.66813,1.7975,0 +2.657,-1.7979,-1.794,-2.0153,0.66766,1.7979,0 +2.658,-1.7982,-1.7939,-2.0149,0.6672,1.7982,0 +2.659,-1.7985,-1.7938,-2.0146,0.66673,1.7985,0 +2.66,-1.7988,-1.7936,-2.0142,0.66627,1.7988,0 +2.661,-1.7992,-1.7935,-2.0139,0.6658,1.7992,0 +2.662,-1.7995,-1.7934,-2.0135,0.66533,1.7995,0 +2.663,-1.7998,-1.7933,-2.0132,0.66487,1.7998,0 +2.664,-1.8002,-1.7932,-2.0128,0.6644,1.8002,0 +2.665,-1.8005,-1.7931,-2.0124,0.66394,1.8005,0 +2.666,-1.8008,-1.793,-2.0121,0.66347,1.8008,0 +2.667,-1.8011,-1.7929,-2.0117,0.663,1.8011,0 +2.668,-1.8015,-1.7928,-2.0114,0.66254,1.8015,0 +2.669,-1.8018,-1.7926,-2.011,0.66207,1.8018,0 +2.67,-1.8021,-1.7925,-2.0107,0.66161,1.8021,0 +2.671,-1.8025,-1.7924,-2.0103,0.66114,1.8025,0 +2.672,-1.8028,-1.7923,-2.01,0.66068,1.8028,0 +2.673,-1.8031,-1.7922,-2.0096,0.66021,1.8031,0 +2.674,-1.8034,-1.7921,-2.0093,0.65974,1.8034,0 +2.675,-1.8038,-1.792,-2.0089,0.65928,1.8038,0 +2.676,-1.8041,-1.7919,-2.0085,0.65881,1.8041,0 +2.677,-1.8044,-1.7917,-2.0082,0.65835,1.8044,0 +2.678,-1.8047,-1.7916,-2.0078,0.65788,1.8047,0 +2.679,-1.8051,-1.7915,-2.0075,0.65741,1.8051,0 +2.68,-1.8054,-1.7914,-2.0071,0.65695,1.8054,0 +2.681,-1.8057,-1.7913,-2.0068,0.65648,1.8057,0 +2.682,-1.8061,-1.7912,-2.0064,0.65602,1.8061,0 +2.683,-1.8064,-1.7911,-2.0061,0.65555,1.8064,0 +2.684,-1.8067,-1.791,-2.0057,0.65508,1.8067,0 +2.685,-1.807,-1.7909,-2.0054,0.65462,1.807,0 +2.686,-1.8074,-1.7907,-2.005,0.65415,1.8074,0 +2.687,-1.8077,-1.7906,-2.0046,0.65369,1.8077,0 +2.688,-1.808,-1.7905,-2.0043,0.65322,1.808,0 +2.689,-1.8084,-1.7904,-2.0039,0.65276,1.8084,0 +2.69,-1.8087,-1.7903,-2.0036,0.65229,1.8087,0 +2.691,-1.809,-1.7902,-2.0032,0.65182,1.809,0 +2.692,-1.8093,-1.7901,-2.0029,0.65136,1.8093,0 +2.693,-1.8097,-1.79,-2.0025,0.65089,1.8097,0 +2.694,-1.81,-1.7899,-2.0022,0.65043,1.81,0 +2.695,-1.8103,-1.7897,-2.0018,0.64996,1.8103,0 +2.696,-1.8106,-1.7896,-2.0014,0.64949,1.8106,0 +2.697,-1.811,-1.7895,-2.0011,0.64903,1.811,0 +2.698,-1.8113,-1.7894,-2.0007,0.64856,1.8113,0 +2.699,-1.8116,-1.7893,-2.0004,0.6481,1.8116,0 +2.7,-1.812,-1.7892,-2,0.64763,1.812,0 +2.701,-1.8123,-1.7891,-1.9997,0.64716,1.8123,0 +2.702,-1.8126,-1.789,-1.9993,0.64669,1.8126,0 +2.703,-1.8129,-1.7889,-1.9989,0.64622,1.8129,0 +2.704,-1.8133,-1.7888,-1.9985,0.64575,1.8133,0 +2.705,-1.8136,-1.7887,-1.9982,0.64528,1.8136,0 +2.706,-1.8139,-1.7886,-1.9978,0.6448,1.8139,0 +2.707,-1.8143,-1.7885,-1.9974,0.64433,1.8143,0 +2.708,-1.8146,-1.7884,-1.997,0.64385,1.8146,0 +2.709,-1.815,-1.7883,-1.9966,0.64338,1.815,0 +2.71,-1.8153,-1.7883,-1.9962,0.6429,1.8153,0 +2.711,-1.8156,-1.7882,-1.9959,0.64243,1.8156,0 +2.712,-1.816,-1.7881,-1.9955,0.64195,1.816,0 +2.713,-1.8163,-1.788,-1.9951,0.64148,1.8163,0 +2.714,-1.8166,-1.7879,-1.9947,0.641,1.8166,0 +2.715,-1.817,-1.7878,-1.9943,0.64053,1.817,0 +2.716,-1.8173,-1.7877,-1.9939,0.64005,1.8173,0 +2.717,-1.8176,-1.7876,-1.9935,0.63958,1.8176,0 +2.718,-1.818,-1.7876,-1.9931,0.6391,1.818,0 +2.719,-1.8183,-1.7875,-1.9928,0.63863,1.8183,0 +2.72,-1.8186,-1.7874,-1.9924,0.63815,1.8186,0 +2.721,-1.819,-1.7873,-1.992,0.63768,1.819,0 +2.722,-1.8193,-1.7872,-1.9916,0.6372,1.8193,0 +2.723,-1.8196,-1.7871,-1.9912,0.63673,1.8196,0 +2.724,-1.82,-1.787,-1.9908,0.63625,1.82,0 +2.725,-1.8203,-1.7869,-1.9904,0.63577,1.8203,0 +2.726,-1.8207,-1.7869,-1.99,0.6353,1.8207,0 +2.727,-1.821,-1.7868,-1.9897,0.63482,1.821,0 +2.728,-1.8213,-1.7867,-1.9893,0.63435,1.8213,0 +2.729,-1.8217,-1.7866,-1.9889,0.63387,1.8217,0 +2.73,-1.822,-1.7865,-1.9885,0.6334,1.822,0 +2.731,-1.8223,-1.7864,-1.9881,0.63292,1.8223,0 +2.732,-1.8227,-1.7863,-1.9877,0.63245,1.8227,0 +2.733,-1.823,-1.7862,-1.9873,0.63197,1.823,0 +2.734,-1.8233,-1.7862,-1.9869,0.6315,1.8233,0 +2.735,-1.8237,-1.7861,-1.9866,0.63102,1.8237,0 +2.736,-1.824,-1.786,-1.9862,0.63055,1.824,0 +2.737,-1.8243,-1.7859,-1.9858,0.63007,1.8243,0 +2.738,-1.8247,-1.7858,-1.9854,0.6296,1.8247,0 +2.739,-1.825,-1.7857,-1.985,0.62912,1.825,0 +2.74,-1.8253,-1.7856,-1.9846,0.62865,1.8253,0 +2.741,-1.8257,-1.7855,-1.9842,0.62817,1.8257,0 +2.742,-1.826,-1.7854,-1.9838,0.6277,1.826,0 +2.743,-1.8264,-1.7854,-1.9835,0.62722,1.8264,0 +2.744,-1.8267,-1.7853,-1.9831,0.62674,1.8267,0 +2.745,-1.827,-1.7852,-1.9827,0.62627,1.827,0 +2.746,-1.8274,-1.7851,-1.9823,0.62579,1.8274,0 +2.747,-1.8277,-1.785,-1.9819,0.62532,1.8277,0 +2.748,-1.828,-1.7849,-1.9815,0.62484,1.828,0 +2.749,-1.8284,-1.7848,-1.9811,0.62437,1.8284,0 +2.75,-1.8287,-1.7847,-1.9807,0.62389,1.8287,0 +2.751,-1.829,-1.7847,-1.9804,0.62342,1.829,0 +2.752,-1.8294,-1.7846,-1.98,0.62294,1.8294,0 +2.753,-1.8297,-1.7845,-1.9796,0.62247,1.8297,0 +2.754,-1.83,-1.7844,-1.9792,0.62199,1.83,0 +2.755,-1.8304,-1.7843,-1.9788,0.62152,1.8304,0 +2.756,-1.8307,-1.7842,-1.9784,0.62104,1.8307,0 +2.757,-1.831,-1.7841,-1.978,0.62057,1.831,0 +2.758,-1.8314,-1.784,-1.9776,0.62009,1.8314,0 +2.759,-1.8317,-1.784,-1.9773,0.61962,1.8317,0 +2.76,-1.8321,-1.7839,-1.9769,0.61914,1.8321,0 +2.761,-1.8324,-1.7838,-1.9765,0.61867,1.8324,0 +2.762,-1.8327,-1.7837,-1.9761,0.61819,1.8327,0 +2.763,-1.8331,-1.7836,-1.9757,0.61771,1.8331,0 +2.764,-1.8334,-1.7835,-1.9753,0.61724,1.8334,0 +2.765,-1.8337,-1.7834,-1.9749,0.61676,1.8337,0 +2.766,-1.8341,-1.7833,-1.9745,0.61629,1.8341,0 +2.767,-1.8344,-1.7833,-1.9741,0.61581,1.8344,0 +2.768,-1.8347,-1.7832,-1.9738,0.61534,1.8347,0 +2.769,-1.8351,-1.7831,-1.9734,0.61486,1.8351,0 +2.77,-1.8354,-1.783,-1.973,0.61439,1.8354,0 +2.771,-1.8357,-1.7829,-1.9726,0.61391,1.8357,0 +2.772,-1.8361,-1.7828,-1.9722,0.61344,1.8361,0 +2.773,-1.8364,-1.7827,-1.9718,0.61296,1.8364,0 +2.774,-1.8368,-1.7826,-1.9714,0.61249,1.8368,0 +2.775,-1.8371,-1.7826,-1.971,0.61201,1.8371,0 +2.776,-1.8374,-1.7825,-1.9707,0.61154,1.8374,0 +2.777,-1.8378,-1.7824,-1.9703,0.61106,1.8378,0 +2.778,-1.8381,-1.7823,-1.9699,0.61059,1.8381,0 +2.779,-1.8384,-1.7822,-1.9695,0.61011,1.8384,0 +2.78,-1.8388,-1.7821,-1.9691,0.60964,1.8388,0 +2.781,-1.8391,-1.782,-1.9687,0.60916,1.8391,0 +2.782,-1.8394,-1.7819,-1.9683,0.60868,1.8394,0 +2.783,-1.8398,-1.7819,-1.9679,0.6082,1.8398,0 +2.784,-1.8401,-1.7818,-1.9675,0.60771,1.8401,0 +2.785,-1.8405,-1.7817,-1.9671,0.60722,1.8405,0 +2.786,-1.8408,-1.7816,-1.9667,0.60673,1.8408,0 +2.787,-1.8411,-1.7815,-1.9663,0.60623,1.8411,0 +2.788,-1.8415,-1.7815,-1.9659,0.60573,1.8415,0 +2.789,-1.8418,-1.7814,-1.9654,0.60523,1.8418,0 +2.79,-1.8422,-1.7813,-1.965,0.60472,1.8422,0 +2.791,-1.8425,-1.7812,-1.9646,0.60421,1.8425,0 +2.792,-1.8429,-1.7812,-1.9641,0.6037,1.8429,0 +2.793,-1.8432,-1.7811,-1.9637,0.60319,1.8432,0 +2.794,-1.8436,-1.781,-1.9632,0.60268,1.8436,0 +2.795,-1.8439,-1.781,-1.9628,0.60217,1.8439,0 +2.796,-1.8443,-1.7809,-1.9624,0.60166,1.8443,0 +2.797,-1.8446,-1.7808,-1.9619,0.60115,1.8446,0 +2.798,-1.845,-1.7807,-1.9615,0.60064,1.845,0 +2.799,-1.8453,-1.7807,-1.9611,0.60012,1.8453,0 +2.8,-1.8457,-1.7806,-1.9606,0.59961,1.8457,0 +2.801,-1.846,-1.7805,-1.9602,0.5991,1.846,0 +2.802,-1.8464,-1.7804,-1.9597,0.59859,1.8464,0 +2.803,-1.8467,-1.7804,-1.9593,0.59808,1.8467,0 +2.804,-1.8471,-1.7803,-1.9589,0.59757,1.8471,0 +2.805,-1.8474,-1.7802,-1.9584,0.59706,1.8474,0 +2.806,-1.8478,-1.7802,-1.958,0.59655,1.8478,0 +2.807,-1.8481,-1.7801,-1.9575,0.59604,1.8481,0 +2.808,-1.8485,-1.78,-1.9571,0.59552,1.8485,0 +2.809,-1.8488,-1.7799,-1.9567,0.59501,1.8488,0 +2.81,-1.8492,-1.7799,-1.9562,0.5945,1.8492,0 +2.811,-1.8495,-1.7798,-1.9558,0.59399,1.8495,0 +2.812,-1.8499,-1.7797,-1.9553,0.59348,1.8499,0 +2.813,-1.8502,-1.7797,-1.9549,0.59297,1.8502,0 +2.814,-1.8505,-1.7796,-1.9545,0.59246,1.8505,0 +2.815,-1.8509,-1.7795,-1.954,0.59195,1.8509,0 +2.816,-1.8512,-1.7794,-1.9536,0.59144,1.8512,0 +2.817,-1.8516,-1.7794,-1.9531,0.59093,1.8516,0 +2.818,-1.8519,-1.7793,-1.9527,0.59041,1.8519,0 +2.819,-1.8523,-1.7792,-1.9523,0.5899,1.8523,0 +2.82,-1.8526,-1.7792,-1.9518,0.58939,1.8526,0 +2.821,-1.853,-1.7791,-1.9514,0.58888,1.853,0 +2.822,-1.8533,-1.779,-1.9509,0.58837,1.8533,0 +2.823,-1.8537,-1.7789,-1.9505,0.58786,1.8537,0 +2.824,-1.854,-1.7789,-1.9501,0.58735,1.854,0 +2.825,-1.8544,-1.7788,-1.9496,0.58684,1.8544,0 +2.826,-1.8547,-1.7787,-1.9492,0.58633,1.8547,0 +2.827,-1.8551,-1.7787,-1.9488,0.58581,1.8551,0 +2.828,-1.8554,-1.7786,-1.9483,0.5853,1.8554,0 +2.829,-1.8558,-1.7785,-1.9479,0.58479,1.8558,0 +2.83,-1.8561,-1.7784,-1.9474,0.58428,1.8561,0 +2.831,-1.8565,-1.7784,-1.947,0.58377,1.8565,0 +2.832,-1.8568,-1.7783,-1.9466,0.58326,1.8568,0 +2.833,-1.8572,-1.7782,-1.9461,0.58275,1.8572,0 +2.834,-1.8575,-1.7782,-1.9457,0.58224,1.8575,0 +2.835,-1.8579,-1.7781,-1.9452,0.58173,1.8579,0 +2.836,-1.8582,-1.778,-1.9448,0.58121,1.8582,0 +2.837,-1.8586,-1.7779,-1.9444,0.5807,1.8586,0 +2.838,-1.8589,-1.7779,-1.9439,0.58019,1.8589,0 +2.839,-1.8593,-1.7778,-1.9435,0.57968,1.8593,0 +2.84,-1.8596,-1.7777,-1.943,0.57917,1.8596,0 +2.841,-1.86,-1.7776,-1.9426,0.57866,1.86,0 +2.842,-1.8603,-1.7776,-1.9422,0.57815,1.8603,0 +2.843,-1.8607,-1.7775,-1.9417,0.57764,1.8607,0 +2.844,-1.861,-1.7774,-1.9413,0.57713,1.861,0 +2.845,-1.8614,-1.7774,-1.9408,0.57661,1.8614,0 +2.846,-1.8617,-1.7773,-1.9404,0.5761,1.8617,0 +2.847,-1.8621,-1.7772,-1.94,0.57559,1.8621,0 +2.848,-1.8624,-1.7771,-1.9395,0.57508,1.8624,0 +2.849,-1.8628,-1.7771,-1.9391,0.57457,1.8628,0 +2.85,-1.8631,-1.777,-1.9386,0.57406,1.8631,0 +2.851,-1.8635,-1.7769,-1.9382,0.57355,1.8635,0 +2.852,-1.8638,-1.7769,-1.9378,0.57304,1.8638,0 +2.853,-1.8642,-1.7768,-1.9373,0.57253,1.8642,0 +2.854,-1.8645,-1.7767,-1.9369,0.57202,1.8645,0 +2.855,-1.8649,-1.7766,-1.9365,0.5715,1.8649,0 +2.856,-1.8652,-1.7766,-1.936,0.57099,1.8652,0 +2.857,-1.8656,-1.7765,-1.9356,0.57048,1.8656,0 +2.858,-1.8659,-1.7764,-1.9351,0.56997,1.8659,0 +2.859,-1.8663,-1.7764,-1.9347,0.56946,1.8663,0 +2.86,-1.8666,-1.7763,-1.9343,0.56895,1.8666,0 +2.861,-1.8669,-1.7762,-1.9338,0.56844,1.8669,0 +2.862,-1.8673,-1.7761,-1.9334,0.56793,1.8673,0 +2.863,-1.8676,-1.7761,-1.9329,0.56742,1.8676,0 +2.864,-1.868,-1.776,-1.9325,0.5669,1.868,0 +2.865,-1.8683,-1.7759,-1.9321,0.5664,1.8683,0 +2.866,-1.8687,-1.7759,-1.9316,0.56589,1.8687,0 +2.867,-1.869,-1.7758,-1.9312,0.56538,1.869,0 +2.868,-1.8694,-1.7757,-1.9307,0.56488,1.8694,0 +2.869,-1.8697,-1.7757,-1.9303,0.56438,1.8697,0 +2.87,-1.87,-1.7756,-1.9299,0.56388,1.87,0 +2.871,-1.8704,-1.7756,-1.9294,0.56338,1.8704,0 +2.872,-1.8707,-1.7755,-1.929,0.56289,1.8707,0 +2.873,-1.871,-1.7755,-1.9285,0.5624,1.871,0 +2.874,-1.8714,-1.7754,-1.9281,0.56191,1.8714,0 +2.875,-1.8717,-1.7754,-1.9276,0.56142,1.8717,0 +2.876,-1.872,-1.7753,-1.9272,0.56093,1.872,0 +2.877,-1.8723,-1.7753,-1.9267,0.56043,1.8723,0 +2.878,-1.8727,-1.7752,-1.9263,0.55994,1.8727,0 +2.879,-1.873,-1.7752,-1.9258,0.55945,1.873,0 +2.88,-1.8733,-1.7752,-1.9254,0.55896,1.8733,0 +2.881,-1.8736,-1.7751,-1.925,0.55847,1.8736,0 +2.882,-1.874,-1.7751,-1.9245,0.55798,1.874,0 +2.883,-1.8743,-1.775,-1.9241,0.55749,1.8743,0 +2.884,-1.8746,-1.775,-1.9236,0.557,1.8746,0 +2.885,-1.875,-1.7749,-1.9232,0.55651,1.875,0 +2.886,-1.8753,-1.7749,-1.9227,0.55602,1.8753,0 +2.887,-1.8756,-1.7748,-1.9223,0.55553,1.8756,0 +2.888,-1.8759,-1.7748,-1.9218,0.55504,1.8759,0 +2.889,-1.8763,-1.7747,-1.9214,0.55455,1.8763,0 +2.89,-1.8766,-1.7747,-1.921,0.55406,1.8766,0 +2.891,-1.8769,-1.7747,-1.9205,0.55357,1.8769,0 +2.892,-1.8772,-1.7746,-1.9201,0.55308,1.8772,0 +2.893,-1.8776,-1.7746,-1.9196,0.55259,1.8776,0 +2.894,-1.8779,-1.7745,-1.9192,0.5521,1.8779,0 +2.895,-1.8782,-1.7745,-1.9187,0.55161,1.8782,0 +2.896,-1.8785,-1.7744,-1.9183,0.55111,1.8785,0 +2.897,-1.8789,-1.7744,-1.9178,0.55062,1.8789,0 +2.898,-1.8792,-1.7743,-1.9174,0.55013,1.8792,0 +2.899,-1.8795,-1.7743,-1.9169,0.54964,1.8795,0 +2.9,-1.8799,-1.7742,-1.9165,0.54915,1.8799,0 +2.901,-1.8802,-1.7742,-1.9161,0.54866,1.8802,0 +2.902,-1.8805,-1.7742,-1.9156,0.54817,1.8805,0 +2.903,-1.8808,-1.7741,-1.9152,0.54768,1.8808,0 +2.904,-1.8812,-1.7741,-1.9147,0.54719,1.8812,0 +2.905,-1.8815,-1.774,-1.9143,0.5467,1.8815,0 +2.906,-1.8818,-1.774,-1.9138,0.54621,1.8818,0 +2.907,-1.8821,-1.7739,-1.9134,0.54572,1.8821,0 +2.908,-1.8825,-1.7739,-1.9129,0.54523,1.8825,0 +2.909,-1.8828,-1.7738,-1.9125,0.54474,1.8828,0 +2.91,-1.8831,-1.7738,-1.912,0.54425,1.8831,0 +2.911,-1.8834,-1.7737,-1.9116,0.54376,1.8834,0 +2.912,-1.8838,-1.7737,-1.9112,0.54327,1.8838,0 +2.913,-1.8841,-1.7737,-1.9107,0.54278,1.8841,0 +2.914,-1.8844,-1.7736,-1.9103,0.54228,1.8844,0 +2.915,-1.8847,-1.7736,-1.9098,0.54179,1.8847,0 +2.916,-1.8851,-1.7735,-1.9094,0.5413,1.8851,0 +2.917,-1.8854,-1.7735,-1.9089,0.54081,1.8854,0 +2.918,-1.8857,-1.7734,-1.9085,0.54032,1.8857,0 +2.919,-1.8861,-1.7734,-1.908,0.53983,1.8861,0 +2.92,-1.8864,-1.7733,-1.9076,0.53934,1.8864,0 +2.921,-1.8867,-1.7733,-1.9072,0.53885,1.8867,0 +2.922,-1.887,-1.7732,-1.9067,0.53836,1.887,0 +2.923,-1.8874,-1.7732,-1.9063,0.53787,1.8874,0 +2.924,-1.8877,-1.7732,-1.9058,0.53738,1.8877,0 +2.925,-1.888,-1.7731,-1.9054,0.53689,1.888,0 +2.926,-1.8883,-1.7731,-1.9049,0.5364,1.8883,0 +2.927,-1.8887,-1.773,-1.9045,0.53591,1.8887,0 +2.928,-1.889,-1.773,-1.904,0.53542,1.889,0 +2.929,-1.8893,-1.7729,-1.9036,0.53493,1.8893,0 +2.93,-1.8896,-1.7729,-1.9031,0.53444,1.8896,0 +2.931,-1.89,-1.7728,-1.9027,0.53395,1.89,0 +2.932,-1.8903,-1.7728,-1.9023,0.53346,1.8903,0 +2.933,-1.8906,-1.7727,-1.9018,0.53296,1.8906,0 +2.934,-1.891,-1.7727,-1.9014,0.53247,1.891,0 +2.935,-1.8913,-1.7727,-1.9009,0.53198,1.8913,0 +2.936,-1.8916,-1.7726,-1.9005,0.53149,1.8916,0 +2.937,-1.8919,-1.7726,-1.9,0.531,1.8919,0 +2.938,-1.8923,-1.7725,-1.8996,0.53051,1.8923,0 +2.939,-1.8926,-1.7725,-1.8991,0.53002,1.8926,0 +2.94,-1.8929,-1.7724,-1.8987,0.52953,1.8929,0 +2.941,-1.8932,-1.7724,-1.8982,0.52904,1.8932,0 +2.942,-1.8936,-1.7723,-1.8978,0.52855,1.8936,0 +2.943,-1.8939,-1.7723,-1.8974,0.52806,1.8939,0 +2.944,-1.8942,-1.7722,-1.8969,0.52757,1.8942,0 +2.945,-1.8945,-1.7722,-1.8965,0.52708,1.8945,0 +2.946,-1.8949,-1.7722,-1.896,0.52659,1.8949,0 +2.947,-1.8952,-1.7721,-1.8956,0.5261,1.8952,0 +2.948,-1.8955,-1.7721,-1.8951,0.52561,1.8955,0 +2.949,-1.8958,-1.772,-1.8947,0.52512,1.8958,0 +2.95,-1.8961,-1.772,-1.8942,0.52463,1.8961,0 +2.951,-1.8965,-1.7719,-1.8938,0.52415,1.8965,0 +2.952,-1.8968,-1.7719,-1.8934,0.52366,1.8968,0 +2.953,-1.8971,-1.7719,-1.8929,0.52317,1.8971,0 +2.954,-1.8974,-1.7718,-1.8925,0.52269,1.8974,0 +2.955,-1.8977,-1.7718,-1.892,0.52221,1.8977,0 +2.956,-1.8979,-1.7717,-1.8916,0.52173,1.8979,0 +2.957,-1.8982,-1.7717,-1.8912,0.52125,1.8982,0 +2.958,-1.8985,-1.7716,-1.8907,0.52077,1.8985,0 +2.959,-1.8988,-1.7716,-1.8903,0.52028,1.8988,0 +2.96,-1.8991,-1.7716,-1.8898,0.5198,1.8991,0 +2.961,-1.8994,-1.7715,-1.8894,0.51932,1.8994,0 +2.962,-1.8997,-1.7715,-1.8889,0.51884,1.8997,0 +2.963,-1.8999,-1.7714,-1.8885,0.51836,1.8999,0 +2.964,-1.9002,-1.7714,-1.8881,0.51788,1.9002,0 +2.965,-1.9005,-1.7714,-1.8876,0.5174,1.9005,0 +2.966,-1.9008,-1.7713,-1.8872,0.51692,1.9008,0 +2.967,-1.9011,-1.7713,-1.8867,0.51644,1.9011,0 +2.968,-1.9014,-1.7712,-1.8863,0.51596,1.9014,0 +2.969,-1.9016,-1.7712,-1.8859,0.51548,1.9016,0 +2.97,-1.9019,-1.7712,-1.8854,0.515,1.9019,0 +2.971,-1.9022,-1.7711,-1.885,0.51452,1.9022,0 +2.972,-1.9025,-1.7711,-1.8845,0.51403,1.9025,0 +2.973,-1.9028,-1.7711,-1.8841,0.51355,1.9028,0 +2.974,-1.9031,-1.771,-1.8837,0.51307,1.9031,0 +2.975,-1.9034,-1.771,-1.8832,0.51259,1.9034,0 +2.976,-1.9036,-1.7709,-1.8828,0.51211,1.9036,0 +2.977,-1.9039,-1.7709,-1.8823,0.51163,1.9039,0 +2.978,-1.9042,-1.7709,-1.8819,0.51115,1.9042,0 +2.979,-1.9045,-1.7708,-1.8815,0.51067,1.9045,0 +2.98,-1.9048,-1.7708,-1.881,0.51019,1.9048,0 +2.981,-1.9051,-1.7707,-1.8806,0.50971,1.9051,0 +2.982,-1.9054,-1.7707,-1.8801,0.50923,1.9054,0 +2.983,-1.9056,-1.7707,-1.8797,0.50875,1.9056,0 +2.984,-1.9059,-1.7706,-1.8792,0.50827,1.9059,0 +2.985,-1.9062,-1.7706,-1.8788,0.50778,1.9062,0 +2.986,-1.9065,-1.7705,-1.8784,0.5073,1.9065,0 +2.987,-1.9068,-1.7705,-1.8779,0.50682,1.9068,0 +2.988,-1.9071,-1.7705,-1.8775,0.50634,1.9071,0 +2.989,-1.9073,-1.7704,-1.877,0.50586,1.9073,0 +2.99,-1.9076,-1.7704,-1.8766,0.50538,1.9076,0 +2.991,-1.9079,-1.7703,-1.8762,0.5049,1.9079,0 +2.992,-1.9082,-1.7703,-1.8757,0.50442,1.9082,0 +2.993,-1.9085,-1.7703,-1.8753,0.50394,1.9085,0 +2.994,-1.9088,-1.7702,-1.8748,0.50346,1.9088,0 +2.995,-1.9091,-1.7702,-1.8744,0.50298,1.9091,0 +2.996,-1.9093,-1.7701,-1.874,0.5025,1.9093,0 +2.997,-1.9096,-1.7701,-1.8735,0.50202,1.9096,0 +2.998,-1.9099,-1.7701,-1.8731,0.50153,1.9099,0 +2.999,-1.9102,-1.77,-1.8726,0.50105,1.9102,0 +3,-1.9105,-1.77,-1.8722,0.50057,1.9105,0 +3.001,-1.9108,-1.7699,-1.8717,0.50009,1.9108,0 +3.002,-1.911,-1.7699,-1.8713,0.49961,1.911,0 +3.003,-1.9113,-1.7699,-1.8709,0.49913,1.9113,0 +3.004,-1.9116,-1.7698,-1.8704,0.49865,1.9116,0 +3.005,-1.9119,-1.7698,-1.87,0.49817,1.9119,0 +3.006,-1.9122,-1.7697,-1.8695,0.49769,1.9122,0 +3.007,-1.9125,-1.7697,-1.8691,0.49721,1.9125,0 +3.008,-1.9128,-1.7697,-1.8687,0.49673,1.9128,0 +3.009,-1.913,-1.7696,-1.8682,0.49625,1.913,0 +3.01,-1.9133,-1.7696,-1.8678,0.49577,1.9133,0 +3.011,-1.9136,-1.7695,-1.8673,0.49528,1.9136,0 +3.012,-1.9139,-1.7695,-1.8669,0.4948,1.9139,0 +3.013,-1.9142,-1.7695,-1.8665,0.49432,1.9142,0 +3.014,-1.9145,-1.7694,-1.866,0.49384,1.9145,0 +3.015,-1.9148,-1.7694,-1.8656,0.49336,1.9148,0 +3.016,-1.915,-1.7693,-1.8651,0.49288,1.915,0 +3.017,-1.9153,-1.7693,-1.8647,0.4924,1.9153,0 +3.018,-1.9156,-1.7693,-1.8643,0.49192,1.9156,0 +3.019,-1.9159,-1.7692,-1.8638,0.49144,1.9159,0 +3.02,-1.9162,-1.7692,-1.8634,0.49096,1.9162,0 +3.021,-1.9165,-1.7691,-1.8629,0.49048,1.9165,0 +3.022,-1.9167,-1.7691,-1.8625,0.49,1.9167,0 +3.023,-1.917,-1.7691,-1.862,0.48952,1.917,0 +3.024,-1.9173,-1.769,-1.8616,0.48903,1.9173,0 +3.025,-1.9176,-1.769,-1.8612,0.48855,1.9176,0 +3.026,-1.9179,-1.7689,-1.8607,0.48807,1.9179,0 +3.027,-1.9182,-1.7689,-1.8603,0.48759,1.9182,0 +3.028,-1.9185,-1.7689,-1.8598,0.48711,1.9185,0 +3.029,-1.9187,-1.7688,-1.8594,0.48663,1.9187,0 +3.03,-1.919,-1.7688,-1.859,0.48615,1.919,0 +3.031,-1.9193,-1.7687,-1.8585,0.48567,1.9193,0 +3.032,-1.9196,-1.7687,-1.8581,0.4852,1.9196,0 +3.033,-1.9199,-1.7687,-1.8577,0.48474,1.9199,0 +3.034,-1.9201,-1.7686,-1.8572,0.48428,1.9201,0 +3.035,-1.9204,-1.7686,-1.8568,0.48382,1.9204,0 +3.036,-1.9207,-1.7686,-1.8564,0.48337,1.9207,0 +3.037,-1.9209,-1.7686,-1.856,0.48292,1.9209,0 +3.038,-1.9212,-1.7685,-1.8555,0.48247,1.9212,0 +3.039,-1.9214,-1.7685,-1.8551,0.48204,1.9214,0 +3.04,-1.9217,-1.7685,-1.8547,0.4816,1.9217,0 +3.041,-1.9219,-1.7685,-1.8543,0.48117,1.9219,0 +3.042,-1.9221,-1.7684,-1.8539,0.48073,1.9221,0 +3.043,-1.9224,-1.7684,-1.8535,0.4803,1.9224,0 +3.044,-1.9226,-1.7684,-1.8531,0.47986,1.9226,0 +3.045,-1.9229,-1.7684,-1.8527,0.47943,1.9229,0 +3.046,-1.9231,-1.7683,-1.8522,0.479,1.9231,0 +3.047,-1.9234,-1.7683,-1.8518,0.47856,1.9234,0 +3.048,-1.9236,-1.7683,-1.8514,0.47813,1.9236,0 +3.049,-1.9239,-1.7683,-1.851,0.47769,1.9239,0 +3.05,-1.9241,-1.7683,-1.8506,0.47726,1.9241,0 +3.051,-1.9244,-1.7682,-1.8502,0.47682,1.9244,0 +3.052,-1.9246,-1.7682,-1.8498,0.47639,1.9246,0 +3.053,-1.9248,-1.7682,-1.8494,0.47596,1.9248,0 +3.054,-1.9251,-1.7682,-1.8489,0.47552,1.9251,0 +3.055,-1.9253,-1.7682,-1.8485,0.47509,1.9253,0 +3.056,-1.9256,-1.7681,-1.8481,0.47465,1.9256,0 +3.057,-1.9258,-1.7681,-1.8477,0.47422,1.9258,0 +3.058,-1.9261,-1.7681,-1.8473,0.47378,1.9261,0 +3.059,-1.9263,-1.7681,-1.8469,0.47335,1.9263,0 +3.06,-1.9266,-1.768,-1.8465,0.47291,1.9266,0 +3.061,-1.9268,-1.768,-1.8461,0.47248,1.9268,0 +3.062,-1.9271,-1.768,-1.8456,0.47205,1.9271,0 +3.063,-1.9273,-1.768,-1.8452,0.47161,1.9273,0 +3.064,-1.9275,-1.768,-1.8448,0.47118,1.9275,0 +3.065,-1.9278,-1.7679,-1.8444,0.47074,1.9278,0 +3.066,-1.928,-1.7679,-1.844,0.47031,1.928,0 +3.067,-1.9283,-1.7679,-1.8436,0.46987,1.9283,0 +3.068,-1.9285,-1.7679,-1.8432,0.46944,1.9285,0 +3.069,-1.9288,-1.7678,-1.8428,0.46901,1.9288,0 +3.07,-1.929,-1.7678,-1.8423,0.46857,1.929,0 +3.071,-1.9293,-1.7678,-1.8419,0.46814,1.9293,0 +3.072,-1.9295,-1.7678,-1.8415,0.4677,1.9295,0 +3.073,-1.9298,-1.7678,-1.8411,0.46727,1.9298,0 +3.074,-1.93,-1.7677,-1.8407,0.46683,1.93,0 +3.075,-1.9303,-1.7677,-1.8403,0.4664,1.9303,0 +3.076,-1.9305,-1.7677,-1.8399,0.46597,1.9305,0 +3.077,-1.9307,-1.7677,-1.8395,0.46553,1.9307,0 +3.078,-1.931,-1.7676,-1.839,0.4651,1.931,0 +3.079,-1.9312,-1.7676,-1.8386,0.46466,1.9312,0 +3.08,-1.9315,-1.7676,-1.8382,0.46423,1.9315,0 +3.081,-1.9317,-1.7676,-1.8378,0.46379,1.9317,0 +3.082,-1.932,-1.7676,-1.8374,0.46336,1.932,0 +3.083,-1.9322,-1.7675,-1.837,0.46292,1.9322,0 +3.084,-1.9325,-1.7675,-1.8366,0.46249,1.9325,0 +3.085,-1.9327,-1.7675,-1.8362,0.46206,1.9327,0 +3.086,-1.933,-1.7675,-1.8357,0.46162,1.933,0 +3.087,-1.9332,-1.7675,-1.8353,0.46119,1.9332,0 +3.088,-1.9334,-1.7674,-1.8349,0.46075,1.9334,0 +3.089,-1.9337,-1.7674,-1.8345,0.46032,1.9337,0 +3.09,-1.9339,-1.7674,-1.8341,0.45988,1.9339,0 +3.091,-1.9342,-1.7674,-1.8337,0.45945,1.9342,0 +3.092,-1.9344,-1.7673,-1.8333,0.45902,1.9344,0 +3.093,-1.9347,-1.7673,-1.8329,0.45858,1.9347,0 +3.094,-1.9349,-1.7673,-1.8324,0.45815,1.9349,0 +3.095,-1.9352,-1.7673,-1.832,0.45771,1.9352,0 +3.096,-1.9354,-1.7673,-1.8316,0.45728,1.9354,0 +3.097,-1.9357,-1.7672,-1.8312,0.45684,1.9357,0 +3.098,-1.9359,-1.7672,-1.8308,0.45641,1.9359,0 +3.099,-1.9361,-1.7672,-1.8304,0.45597,1.9361,0 +3.1,-1.9364,-1.7672,-1.83,0.45554,1.9364,0 +3.101,-1.9366,-1.7671,-1.8296,0.45511,1.9366,0 +3.102,-1.9369,-1.7671,-1.8291,0.45467,1.9369,0 +3.103,-1.9371,-1.7671,-1.8287,0.45424,1.9371,0 +3.104,-1.9374,-1.7671,-1.8283,0.4538,1.9374,0 +3.105,-1.9376,-1.7671,-1.8279,0.45337,1.9376,0 +3.106,-1.9379,-1.767,-1.8275,0.45293,1.9379,0 +3.107,-1.9381,-1.767,-1.8271,0.4525,1.9381,0 +3.108,-1.9384,-1.767,-1.8267,0.45207,1.9384,0 +3.109,-1.9386,-1.767,-1.8263,0.45163,1.9386,0 +3.11,-1.9388,-1.7669,-1.8258,0.4512,1.9388,0 +3.111,-1.9391,-1.7669,-1.8254,0.45076,1.9391,0 +3.112,-1.9393,-1.7669,-1.825,0.45033,1.9393,0 +3.113,-1.9396,-1.7669,-1.8246,0.44989,1.9396,0 +3.114,-1.9398,-1.7669,-1.8242,0.44947,1.9398,0 +3.115,-1.9401,-1.7668,-1.8238,0.44904,1.9401,0 +3.116,-1.9403,-1.7668,-1.8234,0.44862,1.9403,0 +3.117,-1.9405,-1.7668,-1.823,0.44821,1.9405,0 +3.118,-1.9407,-1.7668,-1.8226,0.4478,1.9407,0 +3.119,-1.9409,-1.7668,-1.8222,0.44739,1.9409,0 +3.12,-1.9412,-1.7667,-1.8218,0.44699,1.9412,0 +3.121,-1.9414,-1.7667,-1.8215,0.44659,1.9414,0 +3.122,-1.9416,-1.7667,-1.8211,0.4462,1.9416,0 +3.123,-1.9418,-1.7667,-1.8207,0.44582,1.9418,0 +3.124,-1.9419,-1.7667,-1.8204,0.44543,1.9419,0 +3.125,-1.9421,-1.7666,-1.82,0.44504,1.9421,0 +3.126,-1.9423,-1.7666,-1.8196,0.44465,1.9423,0 +3.127,-1.9425,-1.7666,-1.8193,0.44427,1.9425,0 +3.128,-1.9427,-1.7666,-1.8189,0.44388,1.9427,0 +3.129,-1.9429,-1.7666,-1.8185,0.44349,1.9429,0 +3.13,-1.9431,-1.7665,-1.8181,0.4431,1.9431,0 +3.131,-1.9433,-1.7665,-1.8178,0.44272,1.9433,0 +3.132,-1.9435,-1.7665,-1.8174,0.44233,1.9435,0 +3.133,-1.9437,-1.7665,-1.817,0.44194,1.9437,0 +3.134,-1.9439,-1.7665,-1.8167,0.44155,1.9439,0 +3.135,-1.9441,-1.7665,-1.8163,0.44117,1.9441,0 +3.136,-1.9443,-1.7664,-1.8159,0.44078,1.9443,0 +3.137,-1.9445,-1.7664,-1.8156,0.44039,1.9445,0 +3.138,-1.9447,-1.7664,-1.8152,0.44,1.9447,0 +3.139,-1.9449,-1.7664,-1.8148,0.43962,1.9449,0 +3.14,-1.9451,-1.7664,-1.8145,0.43923,1.9451,0 +3.141,-1.9453,-1.7663,-1.8141,0.43884,1.9453,0 +3.142,-1.9455,-1.7663,-1.8137,0.43845,1.9455,0 +3.143,-1.9457,-1.7663,-1.8134,0.43807,1.9457,0 +3.144,-1.9459,-1.7663,-1.813,0.43768,1.9459,0 +3.145,-1.9461,-1.7663,-1.8126,0.43729,1.9461,0 +3.146,-1.9462,-1.7662,-1.8122,0.4369,1.9462,0 +3.147,-1.9464,-1.7662,-1.8119,0.43652,1.9464,0 +3.148,-1.9466,-1.7662,-1.8115,0.43613,1.9466,0 +3.149,-1.9468,-1.7662,-1.8111,0.43574,1.9468,0 +3.15,-1.947,-1.7662,-1.8108,0.43535,1.947,0 +3.151,-1.9472,-1.7662,-1.8104,0.43497,1.9472,0 +3.152,-1.9474,-1.7661,-1.81,0.43458,1.9474,0 +3.153,-1.9476,-1.7661,-1.8097,0.43419,1.9476,0 +3.154,-1.9478,-1.7661,-1.8093,0.4338,1.9478,0 +3.155,-1.948,-1.7661,-1.8089,0.43341,1.948,0 +3.156,-1.9482,-1.7661,-1.8086,0.43303,1.9482,0 +3.157,-1.9484,-1.766,-1.8082,0.43264,1.9484,0 +3.158,-1.9486,-1.766,-1.8078,0.43225,1.9486,0 +3.159,-1.9488,-1.766,-1.8075,0.43186,1.9488,0 +3.16,-1.949,-1.766,-1.8071,0.43148,1.949,0 +3.161,-1.9492,-1.766,-1.8067,0.43109,1.9492,0 +3.162,-1.9494,-1.7659,-1.8063,0.4307,1.9494,0 +3.163,-1.9496,-1.7659,-1.806,0.43031,1.9496,0 +3.164,-1.9498,-1.7659,-1.8056,0.42993,1.9498,0 +3.165,-1.95,-1.7659,-1.8052,0.42954,1.95,0 +3.166,-1.9502,-1.7659,-1.8049,0.42915,1.9502,0 +3.167,-1.9504,-1.7659,-1.8045,0.42876,1.9504,0 +3.168,-1.9505,-1.7658,-1.8041,0.42838,1.9505,0 +3.169,-1.9507,-1.7658,-1.8038,0.42799,1.9507,0 +3.17,-1.9509,-1.7658,-1.8034,0.4276,1.9509,0 +3.171,-1.9511,-1.7658,-1.803,0.42721,1.9511,0 +3.172,-1.9513,-1.7658,-1.8027,0.42683,1.9513,0 +3.173,-1.9515,-1.7657,-1.8023,0.42644,1.9515,0 +3.174,-1.9517,-1.7657,-1.8019,0.42605,1.9517,0 +3.175,-1.9519,-1.7657,-1.8016,0.42566,1.9519,0 +3.176,-1.9521,-1.7657,-1.8012,0.42528,1.9521,0 +3.177,-1.9523,-1.7657,-1.8008,0.42489,1.9523,0 +3.178,-1.9525,-1.7656,-1.8004,0.4245,1.9525,0 +3.179,-1.9527,-1.7656,-1.8001,0.42411,1.9527,0 +3.18,-1.9529,-1.7656,-1.7997,0.42373,1.9529,0 +3.181,-1.9531,-1.7656,-1.7993,0.42334,1.9531,0 +3.182,-1.9533,-1.7656,-1.799,0.42295,1.9533,0 +3.183,-1.9535,-1.7656,-1.7986,0.42256,1.9535,0 +3.184,-1.9537,-1.7655,-1.7982,0.42218,1.9537,0 +3.185,-1.9539,-1.7655,-1.7979,0.42179,1.9539,0 +3.186,-1.9541,-1.7655,-1.7975,0.4214,1.9541,0 +3.187,-1.9543,-1.7655,-1.7971,0.42101,1.9543,0 +3.188,-1.9545,-1.7655,-1.7968,0.42063,1.9545,0 +3.189,-1.9547,-1.7654,-1.7964,0.42024,1.9547,0 +3.19,-1.9548,-1.7654,-1.796,0.41985,1.9548,0 +3.191,-1.955,-1.7654,-1.7957,0.41946,1.955,0 +3.192,-1.9552,-1.7654,-1.7953,0.41908,1.9552,0 +3.193,-1.9554,-1.7654,-1.7949,0.41869,1.9554,0 +3.194,-1.9556,-1.7653,-1.7945,0.4183,1.9556,0 +3.195,-1.9558,-1.7653,-1.7942,0.41791,1.9558,0 +3.196,-1.956,-1.7653,-1.7938,0.41753,1.956,0 +3.197,-1.9562,-1.7653,-1.7934,0.41714,1.9562,0 +3.198,-1.9564,-1.7653,-1.7931,0.41674,1.9564,0 +3.199,-1.9566,-1.7652,-1.7927,0.41635,1.9566,0 +3.2,-1.9568,-1.7652,-1.7923,0.41596,1.9568,0 +3.201,-1.957,-1.7652,-1.7919,0.41556,1.957,0 +3.202,-1.9571,-1.7652,-1.7916,0.41516,1.9571,0 +3.203,-1.9573,-1.7652,-1.7912,0.41476,1.9573,0 +3.204,-1.9575,-1.7651,-1.7908,0.41435,1.9575,0 +3.205,-1.9577,-1.7651,-1.7904,0.41395,1.9577,0 +3.206,-1.9578,-1.7651,-1.7901,0.41354,1.9578,0 +3.207,-1.958,-1.7651,-1.7897,0.41313,1.958,0 +3.208,-1.9582,-1.765,-1.7893,0.41273,1.9582,0 +3.209,-1.9584,-1.765,-1.7889,0.41232,1.9584,0 +3.21,-1.9585,-1.765,-1.7885,0.41191,1.9585,0 +3.211,-1.9587,-1.7649,-1.7882,0.41151,1.9587,0 +3.212,-1.9589,-1.7649,-1.7878,0.4111,1.9589,0 +3.213,-1.9591,-1.7649,-1.7874,0.41069,1.9591,0 +3.214,-1.9592,-1.7649,-1.787,0.41029,1.9592,0 +3.215,-1.9594,-1.7648,-1.7866,0.40988,1.9594,0 +3.216,-1.9596,-1.7648,-1.7863,0.40947,1.9596,0 +3.217,-1.9597,-1.7648,-1.7859,0.40907,1.9597,0 +3.218,-1.9599,-1.7648,-1.7855,0.40866,1.9599,0 +3.219,-1.9601,-1.7647,-1.7851,0.40825,1.9601,0 +3.22,-1.9603,-1.7647,-1.7847,0.40784,1.9603,0 +3.221,-1.9604,-1.7647,-1.7843,0.40744,1.9604,0 +3.222,-1.9606,-1.7647,-1.784,0.40703,1.9606,0 +3.223,-1.9608,-1.7646,-1.7836,0.40662,1.9608,0 +3.224,-1.961,-1.7646,-1.7832,0.40622,1.961,0 +3.225,-1.9611,-1.7646,-1.7828,0.40581,1.9611,0 +3.226,-1.9613,-1.7645,-1.7824,0.4054,1.9613,0 +3.227,-1.9615,-1.7645,-1.7821,0.405,1.9615,0 +3.228,-1.9617,-1.7645,-1.7817,0.40459,1.9617,0 +3.229,-1.9618,-1.7645,-1.7813,0.40418,1.9618,0 +3.23,-1.962,-1.7644,-1.7809,0.40378,1.962,0 +3.231,-1.9622,-1.7644,-1.7805,0.40337,1.9622,0 +3.232,-1.9623,-1.7644,-1.7802,0.40296,1.9623,0 +3.233,-1.9625,-1.7644,-1.7798,0.40255,1.9625,0 +3.234,-1.9627,-1.7643,-1.7794,0.40215,1.9627,0 +3.235,-1.9629,-1.7643,-1.779,0.40174,1.9629,0 +3.236,-1.963,-1.7643,-1.7786,0.40133,1.963,0 +3.237,-1.9632,-1.7643,-1.7783,0.40093,1.9632,0 +3.238,-1.9634,-1.7642,-1.7779,0.40052,1.9634,0 +3.239,-1.9636,-1.7642,-1.7775,0.40011,1.9636,0 +3.24,-1.9637,-1.7642,-1.7771,0.39971,1.9637,0 +3.241,-1.9639,-1.7642,-1.7767,0.3993,1.9639,0 +3.242,-1.9641,-1.7641,-1.7764,0.39889,1.9641,0 +3.243,-1.9642,-1.7641,-1.776,0.39849,1.9642,0 +3.244,-1.9644,-1.7641,-1.7756,0.39808,1.9644,0 +3.245,-1.9646,-1.764,-1.7752,0.39767,1.9646,0 +3.246,-1.9648,-1.764,-1.7748,0.39726,1.9648,0 +3.247,-1.9649,-1.764,-1.7745,0.39686,1.9649,0 +3.248,-1.9651,-1.764,-1.7741,0.39645,1.9651,0 +3.249,-1.9653,-1.7639,-1.7737,0.39604,1.9653,0 +3.25,-1.9655,-1.7639,-1.7733,0.39564,1.9655,0 +3.251,-1.9656,-1.7639,-1.7729,0.39523,1.9656,0 +3.252,-1.9658,-1.7639,-1.7726,0.39482,1.9658,0 +3.253,-1.966,-1.7638,-1.7722,0.39442,1.966,0 +3.254,-1.9661,-1.7638,-1.7718,0.39401,1.9661,0 +3.255,-1.9663,-1.7638,-1.7714,0.3936,1.9663,0 +3.256,-1.9665,-1.7638,-1.771,0.3932,1.9665,0 +3.257,-1.9667,-1.7637,-1.7706,0.39279,1.9667,0 +3.258,-1.9668,-1.7637,-1.7703,0.39238,1.9668,0 +3.259,-1.967,-1.7637,-1.7699,0.39197,1.967,0 +3.26,-1.9672,-1.7637,-1.7695,0.39157,1.9672,0 +3.261,-1.9674,-1.7636,-1.7691,0.39116,1.9674,0 +3.262,-1.9675,-1.7636,-1.7687,0.39075,1.9675,0 +3.263,-1.9677,-1.7636,-1.7684,0.39035,1.9677,0 +3.264,-1.9679,-1.7635,-1.768,0.38994,1.9679,0 +3.265,-1.9681,-1.7635,-1.7676,0.38953,1.9681,0 +3.266,-1.9682,-1.7635,-1.7672,0.38913,1.9682,0 +3.267,-1.9684,-1.7635,-1.7668,0.38872,1.9684,0 +3.268,-1.9686,-1.7634,-1.7665,0.38831,1.9686,0 +3.269,-1.9687,-1.7634,-1.7661,0.38791,1.9687,0 +3.27,-1.9689,-1.7634,-1.7657,0.3875,1.9689,0 +3.271,-1.9691,-1.7634,-1.7653,0.38709,1.9691,0 +3.272,-1.9693,-1.7633,-1.7649,0.38669,1.9693,0 +3.273,-1.9694,-1.7633,-1.7646,0.38628,1.9694,0 +3.274,-1.9696,-1.7633,-1.7642,0.38587,1.9696,0 +3.275,-1.9698,-1.7633,-1.7638,0.38546,1.9698,0 +3.276,-1.97,-1.7632,-1.7634,0.38506,1.97,0 +3.277,-1.9701,-1.7632,-1.763,0.38465,1.9701,0 +3.278,-1.9703,-1.7632,-1.7627,0.38424,1.9703,0 +3.279,-1.9705,-1.7632,-1.7623,0.38384,1.9705,0 +3.28,-1.9706,-1.7631,-1.7619,0.38344,1.9706,0 +3.281,-1.9708,-1.7631,-1.7615,0.38305,1.9708,0 +3.282,-1.971,-1.7631,-1.7612,0.38266,1.971,0 +3.283,-1.9711,-1.763,-1.7608,0.38228,1.9711,0 +3.284,-1.9713,-1.763,-1.7605,0.3819,1.9713,0 +3.285,-1.9714,-1.763,-1.7601,0.38153,1.9714,0 +3.286,-1.9715,-1.763,-1.7598,0.38117,1.9715,0 +3.287,-1.9717,-1.7629,-1.7595,0.38081,1.9717,0 +3.288,-1.9718,-1.7629,-1.7592,0.38045,1.9718,0 +3.289,-1.9719,-1.7629,-1.7588,0.38011,1.9719,0 +3.29,-1.972,-1.7628,-1.7585,0.37976,1.972,0 +3.291,-1.9721,-1.7628,-1.7582,0.37941,1.9721,0 +3.292,-1.9723,-1.7628,-1.7579,0.37906,1.9723,0 +3.293,-1.9724,-1.7627,-1.7576,0.37871,1.9724,0 +3.294,-1.9725,-1.7627,-1.7572,0.37836,1.9725,0 +3.295,-1.9726,-1.7627,-1.7569,0.37802,1.9726,0 +3.296,-1.9727,-1.7627,-1.7566,0.37767,1.9727,0 +3.297,-1.9729,-1.7626,-1.7563,0.37732,1.9729,0 +3.298,-1.973,-1.7626,-1.756,0.37697,1.973,0 +3.299,-1.9731,-1.7626,-1.7557,0.37662,1.9731,0 +3.3,-1.9732,-1.7625,-1.7553,0.37627,1.9732,0 +3.301,-1.9733,-1.7625,-1.755,0.37593,1.9733,0 +3.302,-1.9735,-1.7625,-1.7547,0.37558,1.9735,0 +3.303,-1.9736,-1.7624,-1.7544,0.37523,1.9736,0 +3.304,-1.9737,-1.7624,-1.7541,0.37488,1.9737,0 +3.305,-1.9738,-1.7624,-1.7538,0.37453,1.9738,0 +3.306,-1.9739,-1.7623,-1.7534,0.37418,1.9739,0 +3.307,-1.9741,-1.7623,-1.7531,0.37384,1.9741,0 +3.308,-1.9742,-1.7623,-1.7528,0.37349,1.9742,0 +3.309,-1.9743,-1.7623,-1.7525,0.37314,1.9743,0 +3.31,-1.9744,-1.7622,-1.7522,0.37279,1.9744,0 +3.311,-1.9745,-1.7622,-1.7518,0.37244,1.9745,0 +3.312,-1.9747,-1.7622,-1.7515,0.37209,1.9747,0 +3.313,-1.9748,-1.7621,-1.7512,0.37175,1.9748,0 +3.314,-1.9749,-1.7621,-1.7509,0.3714,1.9749,0 +3.315,-1.975,-1.7621,-1.7506,0.37105,1.975,0 +3.316,-1.9751,-1.762,-1.7503,0.3707,1.9751,0 +3.317,-1.9753,-1.762,-1.7499,0.37035,1.9753,0 +3.318,-1.9754,-1.762,-1.7496,0.37,1.9754,0 +3.319,-1.9755,-1.7619,-1.7493,0.36966,1.9755,0 +3.32,-1.9756,-1.7619,-1.749,0.36931,1.9756,0 +3.321,-1.9757,-1.7619,-1.7487,0.36896,1.9757,0 +3.322,-1.9759,-1.7619,-1.7484,0.36861,1.9759,0 +3.323,-1.976,-1.7618,-1.748,0.36826,1.976,0 +3.324,-1.9761,-1.7618,-1.7477,0.36791,1.9761,0 +3.325,-1.9762,-1.7618,-1.7474,0.36757,1.9762,0 +3.326,-1.9763,-1.7617,-1.7471,0.36722,1.9763,0 +3.327,-1.9765,-1.7617,-1.7468,0.36687,1.9765,0 +3.328,-1.9766,-1.7617,-1.7464,0.36652,1.9766,0 +3.329,-1.9767,-1.7616,-1.7461,0.36617,1.9767,0 +3.33,-1.9768,-1.7616,-1.7458,0.36582,1.9768,0 +3.331,-1.9769,-1.7616,-1.7455,0.36548,1.9769,0 +3.332,-1.9771,-1.7615,-1.7452,0.36513,1.9771,0 +3.333,-1.9772,-1.7615,-1.7449,0.36478,1.9772,0 +3.334,-1.9773,-1.7615,-1.7445,0.36443,1.9773,0 +3.335,-1.9774,-1.7615,-1.7442,0.36408,1.9774,0 +3.336,-1.9775,-1.7614,-1.7439,0.36373,1.9775,0 +3.337,-1.9777,-1.7614,-1.7436,0.36339,1.9777,0 +3.338,-1.9778,-1.7614,-1.7433,0.36304,1.9778,0 +3.339,-1.9779,-1.7613,-1.743,0.36269,1.9779,0 +3.34,-1.978,-1.7613,-1.7426,0.36234,1.978,0 +3.341,-1.9781,-1.7613,-1.7423,0.36199,1.9781,0 +3.342,-1.9783,-1.7612,-1.742,0.36164,1.9783,0 +3.343,-1.9784,-1.7612,-1.7417,0.3613,1.9784,0 +3.344,-1.9785,-1.7612,-1.7414,0.36095,1.9785,0 +3.345,-1.9786,-1.7611,-1.741,0.3606,1.9786,0 +3.346,-1.9787,-1.7611,-1.7407,0.36025,1.9787,0 +3.347,-1.9789,-1.7611,-1.7404,0.3599,1.9789,0 +3.348,-1.979,-1.7611,-1.7401,0.35955,1.979,0 +3.349,-1.9791,-1.761,-1.7398,0.35921,1.9791,0 +3.35,-1.9792,-1.761,-1.7395,0.35886,1.9792,0 +3.351,-1.9793,-1.761,-1.7391,0.35851,1.9793,0 +3.352,-1.9795,-1.7609,-1.7388,0.35816,1.9795,0 +3.353,-1.9796,-1.7609,-1.7385,0.35781,1.9796,0 +3.354,-1.9797,-1.7609,-1.7382,0.35746,1.9797,0 +3.355,-1.9798,-1.7608,-1.7379,0.35712,1.9798,0 +3.356,-1.9799,-1.7608,-1.7376,0.35677,1.9799,0 +3.357,-1.9801,-1.7608,-1.7372,0.35642,1.9801,0 +3.358,-1.9802,-1.7607,-1.7369,0.35607,1.9802,0 +3.359,-1.9803,-1.7607,-1.7366,0.35572,1.9803,0 +3.36,-1.9804,-1.7607,-1.7363,0.35537,1.9804,0 +3.361,-1.9805,-1.7607,-1.736,0.35503,1.9805,0 +3.362,-1.9807,-1.7606,-1.7356,0.35468,1.9807,0 +3.363,-1.9808,-1.7606,-1.7353,0.35433,1.9808,0 +3.364,-1.9809,-1.7606,-1.735,0.35398,1.9809,0 +3.365,-1.981,-1.7605,-1.7347,0.35364,1.981,0 +3.366,-1.9811,-1.7605,-1.7344,0.35329,1.9811,0 +3.367,-1.9812,-1.7605,-1.7341,0.35294,1.9812,0 +3.368,-1.9814,-1.7604,-1.7337,0.3526,1.9814,0 +3.369,-1.9815,-1.7604,-1.7334,0.35225,1.9815,0 +3.37,-1.9816,-1.7604,-1.7331,0.3519,1.9816,0 +3.371,-1.9817,-1.7604,-1.7328,0.35156,1.9817,0 +3.372,-1.9818,-1.7603,-1.7325,0.35121,1.9818,0 +3.373,-1.9819,-1.7603,-1.7322,0.35087,1.9819,0 +3.374,-1.982,-1.7603,-1.7318,0.35052,1.982,0 +3.375,-1.9821,-1.7602,-1.7315,0.35018,1.9821,0 +3.376,-1.9822,-1.7602,-1.7312,0.34983,1.9822,0 +3.377,-1.9823,-1.7602,-1.7309,0.34949,1.9823,0 +3.378,-1.9824,-1.7602,-1.7306,0.34914,1.9824,0 +3.379,-1.9825,-1.7601,-1.7303,0.3488,1.9825,0 +3.38,-1.9826,-1.7601,-1.73,0.34845,1.9826,0 +3.381,-1.9827,-1.7601,-1.7296,0.34811,1.9827,0 +3.382,-1.9829,-1.76,-1.7293,0.34776,1.9829,0 +3.383,-1.983,-1.76,-1.729,0.34742,1.983,0 +3.384,-1.9831,-1.76,-1.7287,0.34707,1.9831,0 +3.385,-1.9832,-1.7599,-1.7284,0.34673,1.9832,0 +3.386,-1.9833,-1.7599,-1.7281,0.34638,1.9833,0 +3.387,-1.9834,-1.7599,-1.7277,0.34604,1.9834,0 +3.388,-1.9835,-1.7599,-1.7274,0.34569,1.9835,0 +3.389,-1.9836,-1.7598,-1.7271,0.34535,1.9836,0 +3.39,-1.9837,-1.7598,-1.7268,0.345,1.9837,0 +3.391,-1.9838,-1.7598,-1.7265,0.34466,1.9838,0 +3.392,-1.9839,-1.7597,-1.7262,0.34431,1.9839,0 +3.393,-1.984,-1.7597,-1.7258,0.34397,1.984,0 +3.394,-1.9841,-1.7597,-1.7255,0.34362,1.9841,0 +3.395,-1.9842,-1.7597,-1.7252,0.34328,1.9842,0 +3.396,-1.9843,-1.7596,-1.7249,0.34293,1.9843,0 +3.397,-1.9845,-1.7596,-1.7246,0.34259,1.9845,0 +3.398,-1.9846,-1.7596,-1.7243,0.34224,1.9846,0 +3.399,-1.9847,-1.7595,-1.724,0.3419,1.9847,0 +3.4,-1.9848,-1.7595,-1.7236,0.34155,1.9848,0 +3.401,-1.9849,-1.7595,-1.7233,0.34121,1.9849,0 +3.402,-1.985,-1.7595,-1.723,0.34086,1.985,0 +3.403,-1.9851,-1.7594,-1.7227,0.34052,1.9851,0 +3.404,-1.9852,-1.7594,-1.7224,0.34017,1.9852,0 +3.405,-1.9853,-1.7594,-1.7221,0.33983,1.9853,0 +3.406,-1.9854,-1.7593,-1.7217,0.33948,1.9854,0 +3.407,-1.9855,-1.7593,-1.7214,0.33914,1.9855,0 +3.408,-1.9856,-1.7593,-1.7211,0.33879,1.9856,0 +3.409,-1.9857,-1.7592,-1.7208,0.33845,1.9857,0 +3.41,-1.9858,-1.7592,-1.7205,0.3381,1.9858,0 +3.411,-1.9859,-1.7592,-1.7202,0.33776,1.9859,0 +3.412,-1.986,-1.7592,-1.7198,0.33741,1.986,0 +3.413,-1.9862,-1.7591,-1.7195,0.33707,1.9862,0 +3.414,-1.9863,-1.7591,-1.7192,0.33672,1.9863,0 +3.415,-1.9864,-1.7591,-1.7189,0.33638,1.9864,0 +3.416,-1.9865,-1.759,-1.7186,0.33603,1.9865,0 +3.417,-1.9866,-1.759,-1.7183,0.33569,1.9866,0 +3.418,-1.9867,-1.759,-1.718,0.33534,1.9867,0 +3.419,-1.9868,-1.759,-1.7176,0.335,1.9868,0 +3.42,-1.9869,-1.7589,-1.7173,0.33465,1.9869,0 +3.421,-1.987,-1.7589,-1.717,0.33431,1.987,0 +3.422,-1.9871,-1.7589,-1.7167,0.33396,1.9871,0 +3.423,-1.9872,-1.7588,-1.7164,0.33362,1.9872,0 +3.424,-1.9873,-1.7588,-1.7161,0.33327,1.9873,0 +3.425,-1.9874,-1.7588,-1.7157,0.33293,1.9874,0 +3.426,-1.9875,-1.7588,-1.7154,0.33258,1.9875,0 +3.427,-1.9876,-1.7587,-1.7151,0.33224,1.9876,0 +3.428,-1.9877,-1.7587,-1.7148,0.33189,1.9877,0 +3.429,-1.9879,-1.7587,-1.7145,0.33155,1.9879,0 +3.43,-1.988,-1.7586,-1.7142,0.3312,1.988,0 +3.431,-1.9881,-1.7586,-1.7138,0.33086,1.9881,0 +3.432,-1.9882,-1.7586,-1.7135,0.33051,1.9882,0 +3.433,-1.9883,-1.7585,-1.7132,0.33017,1.9883,0 +3.434,-1.9884,-1.7585,-1.7129,0.32982,1.9884,0 +3.435,-1.9885,-1.7585,-1.7126,0.32948,1.9885,0 +3.436,-1.9886,-1.7585,-1.7123,0.32913,1.9886,0 +3.437,-1.9887,-1.7584,-1.7119,0.32879,1.9887,0 +3.438,-1.9888,-1.7584,-1.7116,0.32844,1.9888,0 +3.439,-1.9889,-1.7584,-1.7113,0.3281,1.9889,0 +3.44,-1.989,-1.7583,-1.711,0.32775,1.989,0 +3.441,-1.9891,-1.7583,-1.7107,0.32741,1.9891,0 +3.442,-1.9892,-1.7583,-1.7104,0.32706,1.9892,0 +3.443,-1.9893,-1.7583,-1.7101,0.32672,1.9893,0 +3.444,-1.9894,-1.7582,-1.7097,0.32637,1.9894,0 +3.445,-1.9896,-1.7582,-1.7094,0.32603,1.9896,0 +3.446,-1.9897,-1.7582,-1.7091,0.32568,1.9897,0 +3.447,-1.9898,-1.7581,-1.7088,0.32534,1.9898,0 +3.448,-1.9899,-1.7581,-1.7085,0.32499,1.9899,0 +3.449,-1.99,-1.7581,-1.7082,0.32465,1.99,0 +3.45,-1.9901,-1.7581,-1.7078,0.32431,1.9901,0 +3.451,-1.9902,-1.758,-1.7075,0.32396,1.9902,0 +3.452,-1.9903,-1.758,-1.7072,0.32362,1.9903,0 +3.453,-1.9904,-1.758,-1.7069,0.32328,1.9904,0 +3.454,-1.9904,-1.7579,-1.7066,0.32293,1.9904,0 +3.455,-1.9905,-1.7579,-1.7063,0.32259,1.9905,0 +3.456,-1.9906,-1.7579,-1.706,0.32225,1.9906,0 +3.457,-1.9907,-1.7579,-1.7056,0.32191,1.9907,0 +3.458,-1.9908,-1.7578,-1.7053,0.32157,1.9908,0 +3.459,-1.9909,-1.7578,-1.705,0.32122,1.9909,0 +3.46,-1.991,-1.7578,-1.7047,0.32088,1.991,0 +3.461,-1.9911,-1.7577,-1.7044,0.32054,1.9911,0 +3.462,-1.9912,-1.7577,-1.7041,0.3202,1.9912,0 +3.463,-1.9913,-1.7577,-1.7038,0.31986,1.9913,0 +3.464,-1.9914,-1.7577,-1.7035,0.31951,1.9914,0 +3.465,-1.9915,-1.7576,-1.7031,0.31917,1.9915,0 +3.466,-1.9916,-1.7576,-1.7028,0.31883,1.9916,0 +3.467,-1.9917,-1.7576,-1.7025,0.31849,1.9917,0 +3.468,-1.9917,-1.7575,-1.7022,0.31815,1.9917,0 +3.469,-1.9918,-1.7575,-1.7019,0.3178,1.9918,0 +3.47,-1.9919,-1.7575,-1.7016,0.31746,1.9919,0 +3.471,-1.992,-1.7575,-1.7013,0.31712,1.992,0 +3.472,-1.9921,-1.7574,-1.7009,0.31678,1.9921,0 +3.473,-1.9922,-1.7574,-1.7006,0.31644,1.9922,0 +3.474,-1.9923,-1.7574,-1.7003,0.31609,1.9923,0 +3.475,-1.9924,-1.7573,-1.7,0.31575,1.9924,0 +3.476,-1.9925,-1.7573,-1.6997,0.31541,1.9925,0 +3.477,-1.9926,-1.7573,-1.6994,0.31507,1.9926,0 +3.478,-1.9927,-1.7573,-1.6991,0.31473,1.9927,0 +3.479,-1.9928,-1.7572,-1.6987,0.31438,1.9928,0 +3.48,-1.9929,-1.7572,-1.6984,0.31404,1.9929,0 +3.481,-1.993,-1.7572,-1.6981,0.3137,1.993,0 +3.482,-1.9931,-1.7571,-1.6978,0.31336,1.9931,0 +3.483,-1.9931,-1.7571,-1.6975,0.31302,1.9931,0 +3.484,-1.9932,-1.7571,-1.6972,0.31267,1.9932,0 +3.485,-1.9933,-1.7571,-1.6969,0.31233,1.9933,0 +3.486,-1.9934,-1.757,-1.6965,0.31199,1.9934,0 +3.487,-1.9935,-1.757,-1.6962,0.31165,1.9935,0 +3.488,-1.9936,-1.757,-1.6959,0.31131,1.9936,0 +3.489,-1.9937,-1.7569,-1.6956,0.31096,1.9937,0 +3.49,-1.9938,-1.7569,-1.6953,0.31062,1.9938,0 +3.491,-1.9939,-1.7569,-1.695,0.31028,1.9939,0 +3.492,-1.994,-1.7569,-1.6947,0.30994,1.994,0 +3.493,-1.9941,-1.7568,-1.6944,0.3096,1.9941,0 +3.494,-1.9942,-1.7568,-1.694,0.30925,1.9942,0 +3.495,-1.9943,-1.7568,-1.6937,0.30891,1.9943,0 +3.496,-1.9944,-1.7568,-1.6934,0.30857,1.9944,0 +3.497,-1.9944,-1.7567,-1.6931,0.30823,1.9944,0 +3.498,-1.9945,-1.7567,-1.6928,0.30789,1.9945,0 +3.499,-1.9946,-1.7567,-1.6925,0.30754,1.9946,0 +3.5,-1.9947,-1.7566,-1.6922,0.3072,1.9947,0 +3.501,-1.9948,-1.7566,-1.6918,0.30686,1.9948,0 +3.502,-1.9949,-1.7566,-1.6915,0.30652,1.9949,0 +3.503,-1.995,-1.7566,-1.6912,0.30618,1.995,0 +3.504,-1.9951,-1.7565,-1.6909,0.30583,1.9951,0 +3.505,-1.9952,-1.7565,-1.6906,0.30549,1.9952,0 +3.506,-1.9953,-1.7565,-1.6903,0.30515,1.9953,0 +3.507,-1.9954,-1.7564,-1.69,0.30481,1.9954,0 +3.508,-1.9955,-1.7564,-1.6896,0.30447,1.9955,0 +3.509,-1.9956,-1.7564,-1.6893,0.30412,1.9956,0 +3.51,-1.9957,-1.7564,-1.689,0.30378,1.9957,0 +3.511,-1.9957,-1.7563,-1.6887,0.30344,1.9957,0 +3.512,-1.9958,-1.7563,-1.6884,0.3031,1.9958,0 +3.513,-1.9959,-1.7563,-1.6881,0.30276,1.9959,0 +3.514,-1.996,-1.7562,-1.6878,0.30241,1.996,0 +3.515,-1.9961,-1.7562,-1.6875,0.30207,1.9961,0 +3.516,-1.9962,-1.7562,-1.6871,0.30173,1.9962,0 +3.517,-1.9963,-1.7562,-1.6868,0.30139,1.9963,0 +3.518,-1.9964,-1.7561,-1.6865,0.30105,1.9964,0 +3.519,-1.9965,-1.7561,-1.6862,0.3007,1.9965,0 +3.52,-1.9966,-1.7561,-1.6859,0.30036,1.9966,0 +3.521,-1.9967,-1.756,-1.6856,0.30002,1.9967,0 +3.522,-1.9968,-1.756,-1.6853,0.29968,1.9968,0 +3.523,-1.9969,-1.756,-1.6849,0.29934,1.9969,0 +3.524,-1.997,-1.756,-1.6846,0.29899,1.997,0 +3.525,-1.997,-1.7559,-1.6843,0.29865,1.997,0 +3.526,-1.9971,-1.7559,-1.684,0.29831,1.9971,0 +3.527,-1.9972,-1.7559,-1.6837,0.29797,1.9972,0 +3.528,-1.9973,-1.7558,-1.6834,0.29763,1.9973,0 +3.529,-1.9974,-1.7558,-1.6831,0.29729,1.9974,0 +3.53,-1.9975,-1.7558,-1.6828,0.29695,1.9975,0 +3.531,-1.9976,-1.7558,-1.6824,0.29661,1.9976,0 +3.532,-1.9977,-1.7557,-1.6821,0.29628,1.9977,0 +3.533,-1.9978,-1.7557,-1.6818,0.29594,1.9978,0 +3.534,-1.9978,-1.7557,-1.6815,0.29561,1.9978,0 +3.535,-1.9979,-1.7556,-1.6812,0.29528,1.9979,0 +3.536,-1.998,-1.7556,-1.6809,0.29495,1.998,0 +3.537,-1.9981,-1.7556,-1.6806,0.29462,1.9981,0 +3.538,-1.9981,-1.7556,-1.6803,0.2943,1.9981,0 +3.539,-1.9982,-1.7555,-1.68,0.29397,1.9982,0 +3.54,-1.9983,-1.7555,-1.6797,0.29365,1.9983,0 +3.541,-1.9984,-1.7555,-1.6794,0.29332,1.9984,0 +3.542,-1.9984,-1.7554,-1.6791,0.29299,1.9984,0 +3.543,-1.9985,-1.7554,-1.6788,0.29267,1.9985,0 +3.544,-1.9986,-1.7554,-1.6786,0.29234,1.9986,0 +3.545,-1.9987,-1.7554,-1.6783,0.29201,1.9987,0 +3.546,-1.9987,-1.7553,-1.678,0.29169,1.9987,0 +3.547,-1.9988,-1.7553,-1.6777,0.29136,1.9988,0 +3.548,-1.9989,-1.7553,-1.6774,0.29104,1.9989,0 +3.549,-1.999,-1.7552,-1.6771,0.29071,1.999,0 +3.55,-1.999,-1.7552,-1.6768,0.29038,1.999,0 +3.551,-1.9991,-1.7552,-1.6765,0.29006,1.9991,0 +3.552,-1.9992,-1.7551,-1.6762,0.28973,1.9992,0 +3.553,-1.9993,-1.7551,-1.6759,0.28941,1.9993,0 +3.554,-1.9993,-1.7551,-1.6756,0.28908,1.9993,0 +3.555,-1.9994,-1.7551,-1.6753,0.28875,1.9994,0 +3.556,-1.9995,-1.755,-1.675,0.28843,1.9995,0 +3.557,-1.9995,-1.755,-1.6747,0.2881,1.9995,0 +3.558,-1.9996,-1.755,-1.6744,0.28777,1.9996,0 +3.559,-1.9997,-1.7549,-1.6741,0.28745,1.9997,0 +3.56,-1.9998,-1.7549,-1.6738,0.28712,1.9998,0 +3.561,-1.9998,-1.7549,-1.6735,0.2868,1.9998,0 +3.562,-1.9999,-1.7549,-1.6732,0.28647,1.9999,0 +3.563,-2,-1.7548,-1.6729,0.28614,2,0 +3.564,-2.0001,-1.7548,-1.6726,0.28582,2.0001,0 +3.565,-2.0001,-1.7548,-1.6723,0.28549,2.0001,0 +3.566,-2.0002,-1.7547,-1.672,0.28516,2.0002,0 +3.567,-2.0003,-1.7547,-1.6717,0.28484,2.0003,0 +3.568,-2.0004,-1.7547,-1.6714,0.28451,2.0004,0 +3.569,-2.0004,-1.7547,-1.6711,0.28419,2.0004,0 +3.57,-2.0005,-1.7546,-1.6708,0.28386,2.0005,0 +3.571,-2.0006,-1.7546,-1.6705,0.28353,2.0006,0 +3.572,-2.0007,-1.7546,-1.6702,0.28321,2.0007,0 +3.573,-2.0007,-1.7545,-1.6699,0.28288,2.0007,0 +3.574,-2.0008,-1.7545,-1.6696,0.28255,2.0008,0 +3.575,-2.0009,-1.7545,-1.6693,0.28223,2.0009,0 +3.576,-2.0009,-1.7544,-1.669,0.2819,2.0009,0 +3.577,-2.001,-1.7544,-1.6688,0.28158,2.001,0 +3.578,-2.0011,-1.7544,-1.6685,0.28125,2.0011,0 +3.579,-2.0012,-1.7544,-1.6682,0.28092,2.0012,0 +3.58,-2.0012,-1.7543,-1.6679,0.2806,2.0012,0 +3.581,-2.0013,-1.7543,-1.6676,0.28027,2.0013,0 +3.582,-2.0014,-1.7543,-1.6673,0.27994,2.0014,0 +3.583,-2.0015,-1.7542,-1.667,0.27962,2.0015,0 +3.584,-2.0015,-1.7542,-1.6667,0.27929,2.0015,0 +3.585,-2.0016,-1.7542,-1.6664,0.27897,2.0016,0 +3.586,-2.0017,-1.7542,-1.6661,0.27864,2.0017,0 +3.587,-2.0018,-1.7541,-1.6658,0.27831,2.0018,0 +3.588,-2.0018,-1.7541,-1.6655,0.27799,2.0018,0 +3.589,-2.0019,-1.7541,-1.6652,0.27766,2.0019,0 +3.59,-2.002,-1.754,-1.6649,0.27733,2.002,0 +3.591,-2.0021,-1.754,-1.6646,0.27701,2.0021,0 +3.592,-2.0021,-1.754,-1.6643,0.27668,2.0021,0 +3.593,-2.0022,-1.7539,-1.664,0.27636,2.0022,0 +3.594,-2.0023,-1.7539,-1.6637,0.27603,2.0023,0 +3.595,-2.0023,-1.7539,-1.6634,0.2757,2.0023,0 +3.596,-2.0024,-1.7539,-1.6631,0.27538,2.0024,0 +3.597,-2.0025,-1.7538,-1.6628,0.27505,2.0025,0 +3.598,-2.0026,-1.7538,-1.6625,0.27472,2.0026,0 +3.599,-2.0026,-1.7538,-1.6622,0.2744,2.0026,0 +3.6,-2.0027,-1.7537,-1.6619,0.27407,2.0027,0 +3.601,-2.0028,-1.7537,-1.6616,0.27375,2.0028,0 +3.602,-2.0029,-1.7537,-1.6613,0.27342,2.0029,0 +3.603,-2.0029,-1.7537,-1.661,0.27309,2.0029,0 +3.604,-2.003,-1.7536,-1.6607,0.27277,2.003,0 +3.605,-2.0031,-1.7536,-1.6604,0.27244,2.0031,0 +3.606,-2.0032,-1.7536,-1.6601,0.27211,2.0032,0 +3.607,-2.0032,-1.7535,-1.6598,0.27179,2.0032,0 +3.608,-2.0033,-1.7535,-1.6595,0.27146,2.0033,0 +3.609,-2.0034,-1.7535,-1.6592,0.27114,2.0034,0 +3.61,-2.0035,-1.7535,-1.659,0.27081,2.0035,0 +3.611,-2.0035,-1.7534,-1.6587,0.27048,2.0035,0 +3.612,-2.0036,-1.7534,-1.6584,0.27015,2.0036,0 +3.613,-2.0037,-1.7534,-1.6581,0.26982,2.0037,0 +3.614,-2.0037,-1.7533,-1.6578,0.26949,2.0037,0 +3.615,-2.0038,-1.7533,-1.6574,0.26915,2.0038,0 +3.616,-2.0039,-1.7533,-1.6571,0.26881,2.0039,0 +3.617,-2.0039,-1.7532,-1.6568,0.26847,2.0039,0 +3.618,-2.004,-1.7532,-1.6565,0.26813,2.004,0 +3.619,-2.0041,-1.7532,-1.6562,0.26779,2.0041,0 +3.62,-2.0041,-1.7531,-1.6559,0.26744,2.0041,0 +3.621,-2.0042,-1.7531,-1.6556,0.26709,2.0042,0 +3.622,-2.0043,-1.7531,-1.6553,0.26674,2.0043,0 +3.623,-2.0043,-1.753,-1.655,0.26639,2.0043,0 +3.624,-2.0044,-1.753,-1.6547,0.26605,2.0044,0 +3.625,-2.0044,-1.753,-1.6543,0.2657,2.0044,0 +3.626,-2.0045,-1.7529,-1.654,0.26535,2.0045,0 +3.627,-2.0046,-1.7529,-1.6537,0.265,2.0046,0 +3.628,-2.0046,-1.7528,-1.6534,0.26465,2.0046,0 +3.629,-2.0047,-1.7528,-1.6531,0.26431,2.0047,0 +3.63,-2.0047,-1.7528,-1.6528,0.26396,2.0047,0 +3.631,-2.0048,-1.7527,-1.6525,0.26361,2.0048,0 +3.632,-2.0049,-1.7527,-1.6522,0.26326,2.0049,0 +3.633,-2.0049,-1.7527,-1.6518,0.26291,2.0049,0 +3.634,-2.005,-1.7526,-1.6515,0.26257,2.005,0 +3.635,-2.005,-1.7526,-1.6512,0.26222,2.005,0 +3.636,-2.0051,-1.7526,-1.6509,0.26187,2.0051,0 +3.637,-2.0052,-1.7525,-1.6506,0.26152,2.0052,0 +3.638,-2.0052,-1.7525,-1.6503,0.26118,2.0052,0 +3.639,-2.0053,-1.7525,-1.65,0.26083,2.0053,0 +3.64,-2.0054,-1.7524,-1.6497,0.26048,2.0054,0 +3.641,-2.0054,-1.7524,-1.6493,0.26013,2.0054,0 +3.642,-2.0055,-1.7523,-1.649,0.25978,2.0055,0 +3.643,-2.0055,-1.7523,-1.6487,0.25944,2.0055,0 +3.644,-2.0056,-1.7523,-1.6484,0.25909,2.0056,0 +3.645,-2.0057,-1.7522,-1.6481,0.25874,2.0057,0 +3.646,-2.0057,-1.7522,-1.6478,0.25839,2.0057,0 +3.647,-2.0058,-1.7522,-1.6475,0.25804,2.0058,0 +3.648,-2.0058,-1.7521,-1.6472,0.2577,2.0058,0 +3.649,-2.0059,-1.7521,-1.6468,0.25735,2.0059,0 +3.65,-2.006,-1.7521,-1.6465,0.257,2.006,0 +3.651,-2.006,-1.752,-1.6462,0.25665,2.006,0 +3.652,-2.0061,-1.752,-1.6459,0.2563,2.0061,0 +3.653,-2.0061,-1.752,-1.6456,0.25596,2.0061,0 +3.654,-2.0062,-1.7519,-1.6453,0.25561,2.0062,0 +3.655,-2.0063,-1.7519,-1.645,0.25526,2.0063,0 +3.656,-2.0063,-1.7519,-1.6447,0.25491,2.0063,0 +3.657,-2.0064,-1.7518,-1.6443,0.25456,2.0064,0 +3.658,-2.0065,-1.7518,-1.644,0.25422,2.0065,0 +3.659,-2.0065,-1.7517,-1.6437,0.25387,2.0065,0 +3.66,-2.0066,-1.7517,-1.6434,0.25352,2.0066,0 +3.661,-2.0066,-1.7517,-1.6431,0.25317,2.0066,0 +3.662,-2.0067,-1.7516,-1.6428,0.25282,2.0067,0 +3.663,-2.0068,-1.7516,-1.6425,0.25248,2.0068,0 +3.664,-2.0068,-1.7516,-1.6421,0.25213,2.0068,0 +3.665,-2.0069,-1.7515,-1.6418,0.25178,2.0069,0 +3.666,-2.0069,-1.7515,-1.6415,0.25143,2.0069,0 +3.667,-2.007,-1.7515,-1.6412,0.25108,2.007,0 +3.668,-2.0071,-1.7514,-1.6409,0.25074,2.0071,0 +3.669,-2.0071,-1.7514,-1.6406,0.25039,2.0071,0 +3.67,-2.0072,-1.7514,-1.6403,0.25004,2.0072,0 +3.671,-2.0072,-1.7513,-1.64,0.24969,2.0072,0 +3.672,-2.0073,-1.7513,-1.6396,0.24934,2.0073,0 +3.673,-2.0074,-1.7513,-1.6393,0.249,2.0074,0 +3.674,-2.0074,-1.7512,-1.639,0.24865,2.0074,0 +3.675,-2.0075,-1.7512,-1.6387,0.2483,2.0075,0 +3.676,-2.0076,-1.7511,-1.6384,0.24795,2.0076,0 +3.677,-2.0076,-1.7511,-1.6381,0.2476,2.0076,0 +3.678,-2.0077,-1.7511,-1.6378,0.24726,2.0077,0 +3.679,-2.0077,-1.751,-1.6375,0.24691,2.0077,0 +3.68,-2.0078,-1.751,-1.6371,0.24656,2.0078,0 +3.681,-2.0079,-1.751,-1.6368,0.24621,2.0079,0 +3.682,-2.0079,-1.7509,-1.6365,0.24586,2.0079,0 +3.683,-2.008,-1.7509,-1.6362,0.24552,2.008,0 +3.684,-2.008,-1.7509,-1.6359,0.24517,2.008,0 +3.685,-2.0081,-1.7508,-1.6356,0.24482,2.0081,0 +3.686,-2.0082,-1.7508,-1.6353,0.24447,2.0082,0 +3.687,-2.0082,-1.7508,-1.635,0.24412,2.0082,0 +3.688,-2.0083,-1.7507,-1.6346,0.24378,2.0083,0 +3.689,-2.0083,-1.7507,-1.6343,0.24343,2.0083,0 +3.69,-2.0084,-1.7507,-1.634,0.24308,2.0084,0 +3.691,-2.0085,-1.7506,-1.6337,0.24273,2.0085,0 +3.692,-2.0085,-1.7506,-1.6334,0.24239,2.0085,0 +3.693,-2.0086,-1.7505,-1.6331,0.24204,2.0086,0 +3.694,-2.0086,-1.7505,-1.6328,0.24169,2.0086,0 +3.695,-2.0087,-1.7505,-1.6325,0.24135,2.0087,0 +3.696,-2.0088,-1.7504,-1.6322,0.24101,2.0088,0 +3.697,-2.0088,-1.7504,-1.6319,0.24068,2.0088,0 +3.698,-2.0089,-1.7504,-1.6316,0.24035,2.0089,0 +3.699,-2.0089,-1.7503,-1.6313,0.24002,2.0089,0 +3.7,-2.009,-1.7503,-1.631,0.2397,2.009,0 +3.701,-2.009,-1.7503,-1.6307,0.23938,2.009,0 +3.702,-2.009,-1.7502,-1.6304,0.23907,2.009,0 +3.703,-2.0091,-1.7502,-1.6302,0.23876,2.0091,0 +3.704,-2.0091,-1.7501,-1.6299,0.23845,2.0091,0 +3.705,-2.0091,-1.7501,-1.6296,0.23815,2.0091,0 +3.706,-2.0092,-1.7501,-1.6294,0.23784,2.0092,0 +3.707,-2.0092,-1.75,-1.6291,0.23753,2.0092,0 +3.708,-2.0093,-1.75,-1.6288,0.23722,2.0093,0 +3.709,-2.0093,-1.75,-1.6285,0.23692,2.0093,0 +3.71,-2.0093,-1.7499,-1.6283,0.23661,2.0093,0 +3.711,-2.0094,-1.7499,-1.628,0.2363,2.0094,0 +3.712,-2.0094,-1.7498,-1.6277,0.23599,2.0094,0 +3.713,-2.0094,-1.7498,-1.6275,0.23569,2.0094,0 +3.714,-2.0095,-1.7498,-1.6272,0.23538,2.0095,0 +3.715,-2.0095,-1.7497,-1.6269,0.23507,2.0095,0 +3.716,-2.0096,-1.7497,-1.6267,0.23476,2.0096,0 +3.717,-2.0096,-1.7497,-1.6264,0.23445,2.0096,0 +3.718,-2.0096,-1.7496,-1.6261,0.23415,2.0096,0 +3.719,-2.0097,-1.7496,-1.6258,0.23384,2.0097,0 +3.72,-2.0097,-1.7496,-1.6256,0.23353,2.0097,0 +3.721,-2.0097,-1.7495,-1.6253,0.23322,2.0097,0 +3.722,-2.0098,-1.7495,-1.625,0.23292,2.0098,0 +3.723,-2.0098,-1.7494,-1.6248,0.23261,2.0098,0 +3.724,-2.0098,-1.7494,-1.6245,0.2323,2.0098,0 +3.725,-2.0099,-1.7494,-1.6242,0.23199,2.0099,0 +3.726,-2.0099,-1.7493,-1.6239,0.23169,2.0099,0 +3.727,-2.01,-1.7493,-1.6237,0.23138,2.01,0 +3.728,-2.01,-1.7493,-1.6234,0.23107,2.01,0 +3.729,-2.01,-1.7492,-1.6231,0.23076,2.01,0 +3.73,-2.0101,-1.7492,-1.6229,0.23046,2.0101,0 +3.731,-2.0101,-1.7491,-1.6226,0.23015,2.0101,0 +3.732,-2.0101,-1.7491,-1.6223,0.22984,2.0101,0 +3.733,-2.0102,-1.7491,-1.6221,0.22953,2.0102,0 +3.734,-2.0102,-1.749,-1.6218,0.22922,2.0102,0 +3.735,-2.0102,-1.749,-1.6215,0.22892,2.0102,0 +3.736,-2.0103,-1.749,-1.6212,0.22861,2.0103,0 +3.737,-2.0103,-1.7489,-1.621,0.2283,2.0103,0 +3.738,-2.0104,-1.7489,-1.6207,0.22799,2.0104,0 +3.739,-2.0104,-1.7488,-1.6204,0.22769,2.0104,0 +3.74,-2.0104,-1.7488,-1.6202,0.22738,2.0104,0 +3.741,-2.0105,-1.7488,-1.6199,0.22707,2.0105,0 +3.742,-2.0105,-1.7487,-1.6196,0.22676,2.0105,0 +3.743,-2.0105,-1.7487,-1.6193,0.22646,2.0105,0 +3.744,-2.0106,-1.7487,-1.6191,0.22615,2.0106,0 +3.745,-2.0106,-1.7486,-1.6188,0.22584,2.0106,0 +3.746,-2.0106,-1.7486,-1.6185,0.22553,2.0106,0 +3.747,-2.0107,-1.7486,-1.6183,0.22523,2.0107,0 +3.748,-2.0107,-1.7485,-1.618,0.22492,2.0107,0 +3.749,-2.0108,-1.7485,-1.6177,0.22461,2.0108,0 +3.75,-2.0108,-1.7484,-1.6175,0.2243,2.0108,0 +3.751,-2.0108,-1.7484,-1.6172,0.22399,2.0108,0 +3.752,-2.0109,-1.7484,-1.6169,0.22369,2.0109,0 +3.753,-2.0109,-1.7483,-1.6166,0.22338,2.0109,0 +3.754,-2.0109,-1.7483,-1.6164,0.22307,2.0109,0 +3.755,-2.011,-1.7483,-1.6161,0.22276,2.011,0 +3.756,-2.011,-1.7482,-1.6158,0.22246,2.011,0 +3.757,-2.011,-1.7482,-1.6156,0.22215,2.011,0 +3.758,-2.0111,-1.7481,-1.6153,0.22184,2.0111,0 +3.759,-2.0111,-1.7481,-1.615,0.22153,2.0111,0 +3.76,-2.0112,-1.7481,-1.6147,0.22123,2.0112,0 +3.761,-2.0112,-1.748,-1.6145,0.22092,2.0112,0 +3.762,-2.0112,-1.748,-1.6142,0.22061,2.0112,0 +3.763,-2.0113,-1.748,-1.6139,0.2203,2.0113,0 +3.764,-2.0113,-1.7479,-1.6137,0.22,2.0113,0 +3.765,-2.0113,-1.7479,-1.6134,0.21969,2.0113,0 +3.766,-2.0114,-1.7478,-1.6131,0.21938,2.0114,0 +3.767,-2.0114,-1.7478,-1.6129,0.21907,2.0114,0 +3.768,-2.0114,-1.7478,-1.6126,0.21876,2.0114,0 +3.769,-2.0115,-1.7477,-1.6123,0.21846,2.0115,0 +3.77,-2.0115,-1.7477,-1.612,0.21815,2.0115,0 +3.771,-2.0116,-1.7477,-1.6118,0.21784,2.0116,0 +3.772,-2.0116,-1.7476,-1.6115,0.21753,2.0116,0 +3.773,-2.0116,-1.7476,-1.6112,0.21723,2.0116,0 +3.774,-2.0117,-1.7476,-1.611,0.21692,2.0117,0 +3.775,-2.0117,-1.7475,-1.6107,0.21661,2.0117,0 +3.776,-2.0117,-1.7475,-1.6104,0.2163,2.0117,0 +3.777,-2.0118,-1.7474,-1.6101,0.21599,2.0118,0 +3.778,-2.0118,-1.7474,-1.6099,0.21568,2.0118,0 +3.779,-2.0118,-1.7474,-1.6096,0.21537,2.0118,0 +3.78,-2.0119,-1.7473,-1.6093,0.21505,2.0119,0 +3.781,-2.0119,-1.7473,-1.6091,0.21474,2.0119,0 +3.782,-2.0119,-1.7472,-1.6088,0.21442,2.0119,0 +3.783,-2.0119,-1.7472,-1.6085,0.2141,2.0119,0 +3.784,-2.012,-1.7471,-1.6082,0.21377,2.012,0 +3.785,-2.012,-1.7471,-1.6079,0.21345,2.012,0 +3.786,-2.012,-1.7471,-1.6077,0.21312,2.012,0 +3.787,-2.012,-1.747,-1.6074,0.21279,2.012,0 +3.788,-2.012,-1.747,-1.6071,0.21246,2.012,0 +3.789,-2.0121,-1.7469,-1.6068,0.21213,2.0121,0 +3.79,-2.0121,-1.7469,-1.6065,0.2118,2.0121,0 +3.791,-2.0121,-1.7468,-1.6063,0.21147,2.0121,0 +3.792,-2.0121,-1.7468,-1.606,0.21114,2.0121,0 +3.793,-2.0121,-1.7467,-1.6057,0.21081,2.0121,0 +3.794,-2.0122,-1.7467,-1.6054,0.21049,2.0122,0 +3.795,-2.0122,-1.7466,-1.6051,0.21016,2.0122,0 +3.796,-2.0122,-1.7466,-1.6048,0.20983,2.0122,0 +3.797,-2.0122,-1.7465,-1.6046,0.2095,2.0122,0 +3.798,-2.0122,-1.7465,-1.6043,0.20917,2.0122,0 +3.799,-2.0122,-1.7464,-1.604,0.20884,2.0122,0 +3.8,-2.0123,-1.7464,-1.6037,0.20851,2.0123,0 +3.801,-2.0123,-1.7463,-1.6034,0.20818,2.0123,0 +3.802,-2.0123,-1.7463,-1.6032,0.20785,2.0123,0 +3.803,-2.0123,-1.7462,-1.6029,0.20752,2.0123,0 +3.804,-2.0123,-1.7462,-1.6026,0.2072,2.0123,0 +3.805,-2.0124,-1.7461,-1.6023,0.20687,2.0124,0 +3.806,-2.0124,-1.7461,-1.602,0.20654,2.0124,0 +3.807,-2.0124,-1.746,-1.6018,0.20621,2.0124,0 +3.808,-2.0124,-1.746,-1.6015,0.20588,2.0124,0 +3.809,-2.0124,-1.7459,-1.6012,0.20555,2.0124,0 +3.81,-2.0124,-1.7459,-1.6009,0.20522,2.0124,0 +3.811,-2.0125,-1.7459,-1.6006,0.20489,2.0125,0 +3.812,-2.0125,-1.7458,-1.6004,0.20456,2.0125,0 +3.813,-2.0125,-1.7458,-1.6001,0.20423,2.0125,0 +3.814,-2.0125,-1.7457,-1.5998,0.20391,2.0125,0 +3.815,-2.0125,-1.7457,-1.5995,0.20358,2.0125,0 +3.816,-2.0126,-1.7456,-1.5992,0.20325,2.0126,0 +3.817,-2.0126,-1.7456,-1.5989,0.20292,2.0126,0 +3.818,-2.0126,-1.7455,-1.5987,0.20259,2.0126,0 +3.819,-2.0126,-1.7455,-1.5984,0.20226,2.0126,0 +3.82,-2.0126,-1.7454,-1.5981,0.20193,2.0126,0 +3.821,-2.0126,-1.7454,-1.5978,0.2016,2.0126,0 +3.822,-2.0127,-1.7453,-1.5975,0.20127,2.0127,0 +3.823,-2.0127,-1.7453,-1.5973,0.20094,2.0127,0 +3.824,-2.0127,-1.7452,-1.597,0.20062,2.0127,0 +3.825,-2.0127,-1.7452,-1.5967,0.20029,2.0127,0 +3.826,-2.0127,-1.7451,-1.5964,0.19996,2.0127,0 +3.827,-2.0128,-1.7451,-1.5961,0.19963,2.0128,0 +3.828,-2.0128,-1.745,-1.5959,0.1993,2.0128,0 +3.829,-2.0128,-1.745,-1.5956,0.19897,2.0128,0 +3.83,-2.0128,-1.7449,-1.5953,0.19864,2.0128,0 +3.831,-2.0128,-1.7449,-1.595,0.19831,2.0128,0 +3.832,-2.0128,-1.7448,-1.5947,0.19798,2.0128,0 +3.833,-2.0129,-1.7448,-1.5944,0.19765,2.0129,0 +3.834,-2.0129,-1.7448,-1.5942,0.19733,2.0129,0 +3.835,-2.0129,-1.7447,-1.5939,0.197,2.0129,0 +3.836,-2.0129,-1.7447,-1.5936,0.19667,2.0129,0 +3.837,-2.0129,-1.7446,-1.5933,0.19634,2.0129,0 +3.838,-2.013,-1.7446,-1.593,0.19601,2.013,0 +3.839,-2.013,-1.7445,-1.5928,0.19568,2.013,0 +3.84,-2.013,-1.7445,-1.5925,0.19535,2.013,0 +3.841,-2.013,-1.7444,-1.5922,0.19502,2.013,0 +3.842,-2.013,-1.7444,-1.5919,0.19469,2.013,0 +3.843,-2.013,-1.7443,-1.5916,0.19436,2.013,0 +3.844,-2.0131,-1.7443,-1.5914,0.19404,2.0131,0 +3.845,-2.0131,-1.7442,-1.5911,0.19371,2.0131,0 +3.846,-2.0131,-1.7442,-1.5908,0.19338,2.0131,0 +3.847,-2.0131,-1.7441,-1.5905,0.19305,2.0131,0 +3.848,-2.0131,-1.7441,-1.5902,0.19272,2.0131,0 +3.849,-2.0132,-1.744,-1.59,0.19239,2.0132,0 +3.85,-2.0132,-1.744,-1.5897,0.19206,2.0132,0 +3.851,-2.0132,-1.7439,-1.5894,0.19173,2.0132,0 +3.852,-2.0132,-1.7439,-1.5891,0.1914,2.0132,0 +3.853,-2.0132,-1.7438,-1.5888,0.19107,2.0132,0 +3.854,-2.0132,-1.7438,-1.5885,0.19075,2.0132,0 +3.855,-2.0133,-1.7437,-1.5883,0.19042,2.0133,0 +3.856,-2.0133,-1.7437,-1.588,0.19009,2.0133,0 +3.857,-2.0133,-1.7436,-1.5877,0.18976,2.0133,0 +3.858,-2.0133,-1.7436,-1.5874,0.18943,2.0133,0 +3.859,-2.0133,-1.7436,-1.5871,0.1891,2.0133,0 +3.86,-2.0134,-1.7435,-1.5869,0.18877,2.0134,0 +3.861,-2.0134,-1.7435,-1.5866,0.18844,2.0134,0 +3.862,-2.0134,-1.7434,-1.5863,0.18811,2.0134,0 +3.863,-2.0134,-1.7433,-1.586,0.18778,2.0134,0 +3.864,-2.0134,-1.7433,-1.5858,0.18745,2.0134,0 +3.865,-2.0134,-1.7432,-1.5855,0.18711,2.0134,0 +3.866,-2.0134,-1.7432,-1.5852,0.18678,2.0134,0 +3.867,-2.0134,-1.7431,-1.5849,0.18644,2.0134,0 +3.868,-2.0133,-1.743,-1.5847,0.18611,2.0133,0 +3.869,-2.0133,-1.743,-1.5844,0.18577,2.0133,0 +3.87,-2.0133,-1.7429,-1.5841,0.18544,2.0133,0 +3.871,-2.0133,-1.7428,-1.5839,0.1851,2.0133,0 +3.872,-2.0133,-1.7428,-1.5836,0.18477,2.0133,0 +3.873,-2.0133,-1.7427,-1.5833,0.18443,2.0133,0 +3.874,-2.0132,-1.7426,-1.5831,0.18409,2.0132,0 +3.875,-2.0132,-1.7425,-1.5828,0.18376,2.0132,0 +3.876,-2.0132,-1.7425,-1.5825,0.18342,2.0132,0 +3.877,-2.0132,-1.7424,-1.5823,0.18309,2.0132,0 +3.878,-2.0132,-1.7423,-1.582,0.18275,2.0132,0 +3.879,-2.0131,-1.7423,-1.5817,0.18241,2.0131,0 +3.88,-2.0131,-1.7422,-1.5815,0.18208,2.0131,0 +3.881,-2.0131,-1.7421,-1.5812,0.18174,2.0131,0 +3.882,-2.0131,-1.7421,-1.5809,0.18141,2.0131,0 +3.883,-2.0131,-1.742,-1.5807,0.18107,2.0131,0 +3.884,-2.0131,-1.7419,-1.5804,0.18073,2.0131,0 +3.885,-2.013,-1.7418,-1.5801,0.1804,2.013,0 +3.886,-2.013,-1.7418,-1.5799,0.18006,2.013,0 +3.887,-2.013,-1.7417,-1.5796,0.17973,2.013,0 +3.888,-2.013,-1.7416,-1.5793,0.17939,2.013,0 +3.889,-2.013,-1.7416,-1.5791,0.17905,2.013,0 +3.89,-2.0129,-1.7415,-1.5788,0.17872,2.0129,0 +3.891,-2.0129,-1.7414,-1.5785,0.17838,2.0129,0 +3.892,-2.0129,-1.7414,-1.5783,0.17804,2.0129,0 +3.893,-2.0129,-1.7413,-1.578,0.17771,2.0129,0 +3.894,-2.0129,-1.7412,-1.5777,0.17737,2.0129,0 +3.895,-2.0129,-1.7412,-1.5775,0.17704,2.0129,0 +3.896,-2.0128,-1.7411,-1.5772,0.1767,2.0128,0 +3.897,-2.0128,-1.741,-1.5769,0.17636,2.0128,0 +3.898,-2.0128,-1.7409,-1.5767,0.17603,2.0128,0 +3.899,-2.0128,-1.7409,-1.5764,0.17569,2.0128,0 +3.9,-2.0128,-1.7408,-1.5761,0.17536,2.0128,0 +3.901,-2.0127,-1.7407,-1.5759,0.17502,2.0127,0 +3.902,-2.0127,-1.7407,-1.5756,0.17468,2.0127,0 +3.903,-2.0127,-1.7406,-1.5753,0.17435,2.0127,0 +3.904,-2.0127,-1.7405,-1.5751,0.17401,2.0127,0 +3.905,-2.0127,-1.7405,-1.5748,0.17368,2.0127,0 +3.906,-2.0127,-1.7404,-1.5745,0.17334,2.0127,0 +3.907,-2.0126,-1.7403,-1.5743,0.173,2.0126,0 +3.908,-2.0126,-1.7402,-1.574,0.17267,2.0126,0 +3.909,-2.0126,-1.7402,-1.5737,0.17233,2.0126,0 +3.91,-2.0126,-1.7401,-1.5735,0.172,2.0126,0 +3.911,-2.0126,-1.74,-1.5732,0.17166,2.0126,0 +3.912,-2.0125,-1.74,-1.5729,0.17132,2.0125,0 +3.913,-2.0125,-1.7399,-1.5727,0.17099,2.0125,0 +3.914,-2.0125,-1.7398,-1.5724,0.17065,2.0125,0 +3.915,-2.0125,-1.7398,-1.5721,0.17032,2.0125,0 +3.916,-2.0125,-1.7397,-1.5719,0.16998,2.0125,0 +3.917,-2.0125,-1.7396,-1.5716,0.16964,2.0125,0 +3.918,-2.0124,-1.7396,-1.5713,0.16931,2.0124,0 +3.919,-2.0124,-1.7395,-1.5711,0.16897,2.0124,0 +3.92,-2.0124,-1.7394,-1.5708,0.16864,2.0124,0 +3.921,-2.0124,-1.7393,-1.5705,0.1683,2.0124,0 +3.922,-2.0124,-1.7393,-1.5703,0.16796,2.0124,0 +3.923,-2.0123,-1.7392,-1.57,0.16763,2.0123,0 +3.924,-2.0123,-1.7391,-1.5697,0.16729,2.0123,0 +3.925,-2.0123,-1.7391,-1.5695,0.16696,2.0123,0 +3.926,-2.0123,-1.739,-1.5692,0.16662,2.0123,0 +3.927,-2.0123,-1.7389,-1.5689,0.16628,2.0123,0 +3.928,-2.0123,-1.7389,-1.5687,0.16595,2.0123,0 +3.929,-2.0122,-1.7388,-1.5684,0.16561,2.0122,0 +3.93,-2.0122,-1.7387,-1.5681,0.16528,2.0122,0 +3.931,-2.0122,-1.7387,-1.5679,0.16494,2.0122,0 +3.932,-2.0122,-1.7386,-1.5676,0.1646,2.0122,0 +3.933,-2.0122,-1.7385,-1.5673,0.16427,2.0122,0 +3.934,-2.0121,-1.7384,-1.5671,0.16393,2.0121,0 +3.935,-2.0121,-1.7384,-1.5668,0.1636,2.0121,0 +3.936,-2.0121,-1.7383,-1.5665,0.16326,2.0121,0 +3.937,-2.0121,-1.7382,-1.5663,0.16292,2.0121,0 +3.938,-2.0121,-1.7382,-1.566,0.16259,2.0121,0 +3.939,-2.0121,-1.7381,-1.5657,0.16225,2.0121,0 +3.94,-2.012,-1.738,-1.5655,0.16191,2.012,0 +3.941,-2.012,-1.738,-1.5652,0.16158,2.012,0 +3.942,-2.012,-1.7379,-1.5649,0.16124,2.012,0 +3.943,-2.012,-1.7378,-1.5647,0.1609,2.012,0 +3.944,-2.0119,-1.7377,-1.5644,0.16054,2.0119,0 +3.945,-2.0119,-1.7376,-1.5641,0.16018,2.0119,0 +3.946,-2.0119,-1.7375,-1.5638,0.1598,2.0119,0 +3.947,-2.0118,-1.7374,-1.5636,0.15941,2.0118,0 +3.948,-2.0117,-1.7373,-1.5633,0.15901,2.0117,0 +3.949,-2.0117,-1.7372,-1.563,0.1586,2.0117,0 +3.95,-2.0116,-1.7371,-1.5627,0.15818,2.0116,0 +3.951,-2.0115,-1.737,-1.5624,0.15774,2.0115,0 +3.952,-2.0114,-1.7368,-1.5621,0.1573,2.0114,0 +3.953,-2.0113,-1.7367,-1.5617,0.15685,2.0113,0 +3.954,-2.0112,-1.7366,-1.5614,0.1564,2.0112,0 +3.955,-2.0111,-1.7364,-1.5611,0.15596,2.0111,0 +3.956,-2.011,-1.7363,-1.5608,0.15551,2.011,0 +3.957,-2.0109,-1.7362,-1.5605,0.15506,2.0109,0 +3.958,-2.0108,-1.736,-1.5602,0.15462,2.0108,0 +3.959,-2.0107,-1.7359,-1.5599,0.15417,2.0107,0 +3.96,-2.0106,-1.7358,-1.5596,0.15372,2.0106,0 +3.961,-2.0105,-1.7356,-1.5593,0.15327,2.0105,0 +3.962,-2.0104,-1.7355,-1.5589,0.15283,2.0104,0 +3.963,-2.0103,-1.7353,-1.5586,0.15238,2.0103,0 +3.964,-2.0102,-1.7352,-1.5583,0.15193,2.0102,0 +3.965,-2.0101,-1.7351,-1.558,0.15148,2.0101,0 +3.966,-2.01,-1.7349,-1.5577,0.15104,2.01,0 +3.967,-2.0099,-1.7348,-1.5574,0.15059,2.0099,0 +3.968,-2.0098,-1.7347,-1.5571,0.15014,2.0098,0 +3.969,-2.0097,-1.7345,-1.5568,0.14969,2.0097,0 +3.97,-2.0096,-1.7344,-1.5565,0.14925,2.0096,0 +3.971,-2.0096,-1.7343,-1.5561,0.1488,2.0096,0 +3.972,-2.0095,-1.7341,-1.5558,0.14835,2.0095,0 +3.973,-2.0094,-1.734,-1.5555,0.14791,2.0094,0 +3.974,-2.0093,-1.7338,-1.5552,0.14746,2.0093,0 +3.975,-2.0092,-1.7337,-1.5549,0.14701,2.0092,0 +3.976,-2.0091,-1.7336,-1.5546,0.14656,2.0091,0 +3.977,-2.009,-1.7334,-1.5543,0.14612,2.009,0 +3.978,-2.0089,-1.7333,-1.554,0.14567,2.0089,0 +3.979,-2.0088,-1.7332,-1.5537,0.14522,2.0088,0 +3.98,-2.0087,-1.733,-1.5533,0.14477,2.0087,0 +3.981,-2.0086,-1.7329,-1.553,0.14433,2.0086,0 +3.982,-2.0085,-1.7328,-1.5527,0.14388,2.0085,0 +3.983,-2.0084,-1.7326,-1.5524,0.14343,2.0084,0 +3.984,-2.0083,-1.7325,-1.5521,0.14298,2.0083,0 +3.985,-2.0082,-1.7323,-1.5518,0.14254,2.0082,0 +3.986,-2.0081,-1.7322,-1.5515,0.14209,2.0081,0 +3.987,-2.008,-1.7321,-1.5512,0.14164,2.008,0 +3.988,-2.0079,-1.7319,-1.5509,0.1412,2.0079,0 +3.989,-2.0078,-1.7318,-1.5505,0.14075,2.0078,0 +3.99,-2.0077,-1.7317,-1.5502,0.1403,2.0077,0 +3.991,-2.0076,-1.7315,-1.5499,0.13985,2.0076,0 +3.992,-2.0075,-1.7314,-1.5496,0.13941,2.0075,0 +3.993,-2.0074,-1.7313,-1.5493,0.13896,2.0074,0 +3.994,-2.0073,-1.7311,-1.549,0.13851,2.0073,0 +3.995,-2.0072,-1.731,-1.5487,0.13806,2.0072,0 +3.996,-2.0071,-1.7308,-1.5484,0.13762,2.0071,0 +3.997,-2.007,-1.7307,-1.5481,0.13717,2.007,0 +3.998,-2.0069,-1.7306,-1.5477,0.13672,2.0069,0 +3.999,-2.0068,-1.7304,-1.5474,0.13627,2.0068,0 +4,-2.0067,-1.7303,-1.5471,0.13583,2.0067,0 +4.001,-2.0066,-1.7302,-1.5468,0.13538,2.0066,0 +4.002,-2.0065,-1.73,-1.5465,0.13493,2.0065,0 +4.003,-2.0064,-1.7299,-1.5462,0.13449,2.0064,0 +4.004,-2.0063,-1.7298,-1.5459,0.13404,2.0063,0 +4.005,-2.0062,-1.7296,-1.5456,0.13359,2.0062,0 +4.006,-2.0061,-1.7295,-1.5453,0.13314,2.0061,0 +4.007,-2.006,-1.7293,-1.5449,0.1327,2.006,0 +4.008,-2.0059,-1.7292,-1.5446,0.13225,2.0059,0 +4.009,-2.0058,-1.7291,-1.5443,0.1318,2.0058,0 +4.01,-2.0057,-1.7289,-1.544,0.13135,2.0057,0 +4.011,-2.0056,-1.7288,-1.5437,0.13091,2.0056,0 +4.012,-2.0056,-1.7287,-1.5434,0.13046,2.0056,0 +4.013,-2.0055,-1.7285,-1.5431,0.13001,2.0055,0 +4.014,-2.0054,-1.7284,-1.5428,0.12957,2.0054,0 +4.015,-2.0053,-1.7283,-1.5425,0.12912,2.0053,0 +4.016,-2.0052,-1.7281,-1.5421,0.12867,2.0052,0 +4.017,-2.0051,-1.728,-1.5418,0.12822,2.0051,0 +4.018,-2.005,-1.7278,-1.5415,0.12778,2.005,0 +4.019,-2.0049,-1.7277,-1.5412,0.12733,2.0049,0 +4.02,-2.0048,-1.7276,-1.5409,0.12688,2.0048,0 +4.021,-2.0047,-1.7274,-1.5406,0.12643,2.0047,0 +4.022,-2.0046,-1.7273,-1.5403,0.12599,2.0046,0 +4.023,-2.0045,-1.7272,-1.54,0.12554,2.0045,0 +4.024,-2.0044,-1.727,-1.5397,0.12509,2.0044,0 +4.025,-2.0043,-1.7269,-1.5393,0.12464,2.0043,0 +4.026,-2.0042,-1.7268,-1.539,0.1242,2.0042,0 +4.027,-2.0041,-1.7266,-1.5387,0.12375,2.0041,0 +4.028,-2.004,-1.7265,-1.5384,0.1233,2.004,0 +4.029,-2.0039,-1.7263,-1.5381,0.12285,2.0039,0 +4.03,-2.0037,-1.7262,-1.5378,0.1224,2.0037,0 +4.031,-2.0036,-1.726,-1.5375,0.12194,2.0036,0 +4.032,-2.0035,-1.7259,-1.5372,0.12149,2.0035,0 +4.033,-2.0033,-1.7257,-1.5369,0.12103,2.0033,0 +4.034,-2.0032,-1.7256,-1.5366,0.12058,2.0032,0 +4.035,-2.0031,-1.7254,-1.5363,0.12012,2.0031,0 +4.036,-2.0029,-1.7253,-1.536,0.11967,2.0029,0 +4.037,-2.0028,-1.7251,-1.5357,0.11921,2.0028,0 +4.038,-2.0026,-1.725,-1.5354,0.11875,2.0026,0 +4.039,-2.0025,-1.7248,-1.5351,0.1183,2.0025,0 +4.04,-2.0024,-1.7247,-1.5348,0.11784,2.0024,0 +4.041,-2.0022,-1.7245,-1.5345,0.11738,2.0022,0 +4.042,-2.0021,-1.7244,-1.5342,0.11693,2.0021,0 +4.043,-2.0019,-1.7242,-1.5338,0.11647,2.0019,0 +4.044,-2.0018,-1.7241,-1.5335,0.11601,2.0018,0 +4.045,-2.0017,-1.7239,-1.5332,0.11556,2.0017,0 +4.046,-2.0015,-1.7238,-1.5329,0.1151,2.0015,0 +4.047,-2.0014,-1.7236,-1.5326,0.11464,2.0014,0 +4.048,-2.0012,-1.7234,-1.5323,0.11419,2.0012,0 +4.049,-2.0011,-1.7233,-1.532,0.11373,2.0011,0 +4.05,-2.0009,-1.7231,-1.5317,0.11327,2.0009,0 +4.051,-2.0008,-1.723,-1.5314,0.11282,2.0008,0 +4.052,-2.0007,-1.7228,-1.5311,0.11236,2.0007,0 +4.053,-2.0005,-1.7227,-1.5308,0.1119,2.0005,0 +4.054,-2.0004,-1.7225,-1.5305,0.11145,2.0004,0 +4.055,-2.0002,-1.7224,-1.5302,0.11099,2.0002,0 +4.056,-2.0001,-1.7222,-1.5299,0.11053,2.0001,0 +4.057,-2,-1.7221,-1.5296,0.11008,2,0 +4.058,-1.9998,-1.7219,-1.5293,0.10962,1.9998,0 +4.059,-1.9997,-1.7218,-1.529,0.10916,1.9997,0 +4.06,-1.9995,-1.7216,-1.5287,0.10871,1.9995,0 +4.061,-1.9994,-1.7215,-1.5284,0.10825,1.9994,0 +4.062,-1.9992,-1.7213,-1.5281,0.10779,1.9992,0 +4.063,-1.9991,-1.7211,-1.5278,0.10734,1.9991,0 +4.064,-1.999,-1.721,-1.5275,0.10688,1.999,0 +4.065,-1.9988,-1.7208,-1.5272,0.10642,1.9988,0 +4.066,-1.9987,-1.7207,-1.5269,0.10597,1.9987,0 +4.067,-1.9985,-1.7205,-1.5266,0.10551,1.9985,0 +4.068,-1.9984,-1.7204,-1.5263,0.10506,1.9984,0 +4.069,-1.9982,-1.7202,-1.526,0.1046,1.9982,0 +4.07,-1.9981,-1.7201,-1.5257,0.10414,1.9981,0 +4.071,-1.998,-1.7199,-1.5254,0.10369,1.998,0 +4.072,-1.9978,-1.7198,-1.5251,0.10323,1.9978,0 +4.073,-1.9977,-1.7196,-1.5248,0.10277,1.9977,0 +4.074,-1.9975,-1.7195,-1.5245,0.10232,1.9975,0 +4.075,-1.9974,-1.7193,-1.5242,0.10186,1.9974,0 +4.076,-1.9973,-1.7191,-1.5238,0.1014,1.9973,0 +4.077,-1.9971,-1.719,-1.5235,0.10095,1.9971,0 +4.078,-1.997,-1.7188,-1.5232,0.10049,1.997,0 +4.079,-1.9968,-1.7187,-1.5229,0.10003,1.9968,0 +4.08,-1.9967,-1.7185,-1.5226,0.099576,1.9967,0 +4.081,-1.9965,-1.7184,-1.5223,0.09912,1.9965,0 +4.082,-1.9964,-1.7182,-1.522,0.098663,1.9964,0 +4.083,-1.9963,-1.7181,-1.5217,0.098207,1.9963,0 +4.084,-1.9961,-1.7179,-1.5214,0.09775,1.9961,0 +4.085,-1.996,-1.7178,-1.5211,0.097293,1.996,0 +4.086,-1.9958,-1.7176,-1.5208,0.096837,1.9958,0 +4.087,-1.9957,-1.7175,-1.5205,0.09638,1.9957,0 +4.088,-1.9956,-1.7173,-1.5202,0.095924,1.9956,0 +4.089,-1.9954,-1.7172,-1.5199,0.095467,1.9954,0 +4.09,-1.9953,-1.717,-1.5196,0.09501,1.9953,0 +4.091,-1.9951,-1.7168,-1.5193,0.094554,1.9951,0 +4.092,-1.995,-1.7167,-1.519,0.094097,1.995,0 +4.093,-1.9948,-1.7165,-1.5187,0.093641,1.9948,0 +4.094,-1.9947,-1.7164,-1.5184,0.093184,1.9947,0 +4.095,-1.9946,-1.7162,-1.5181,0.092728,1.9946,0 +4.096,-1.9944,-1.7161,-1.5178,0.092271,1.9944,0 +4.097,-1.9943,-1.7159,-1.5175,0.091814,1.9943,0 +4.098,-1.9941,-1.7158,-1.5172,0.091358,1.9941,0 +4.099,-1.994,-1.7156,-1.5169,0.090901,1.994,0 +4.1,-1.9938,-1.7155,-1.5166,0.090445,1.9938,0 +4.101,-1.9937,-1.7153,-1.5163,0.089988,1.9937,0 +4.102,-1.9936,-1.7152,-1.516,0.089532,1.9936,0 +4.103,-1.9934,-1.715,-1.5157,0.089075,1.9934,0 +4.104,-1.9933,-1.7148,-1.5154,0.088618,1.9933,0 +4.105,-1.9931,-1.7147,-1.5151,0.088162,1.9931,0 +4.106,-1.993,-1.7145,-1.5148,0.087705,1.993,0 +4.107,-1.9929,-1.7144,-1.5145,0.087249,1.9929,0 +4.108,-1.9927,-1.7142,-1.5141,0.086792,1.9927,0 +4.109,-1.9926,-1.7141,-1.5138,0.086333,1.9926,0 +4.11,-1.9924,-1.7139,-1.5135,0.085872,1.9924,0 +4.111,-1.9923,-1.7138,-1.5132,0.085409,1.9923,0 +4.112,-1.9921,-1.7136,-1.5129,0.084943,1.9921,0 +4.113,-1.992,-1.7135,-1.5126,0.084474,1.992,0 +4.114,-1.9918,-1.7133,-1.5123,0.084004,1.9918,0 +4.115,-1.9916,-1.7131,-1.512,0.08353,1.9916,0 +4.116,-1.9915,-1.713,-1.5117,0.083055,1.9915,0 +4.117,-1.9913,-1.7128,-1.5113,0.082577,1.9913,0 +4.118,-1.9911,-1.7127,-1.511,0.082096,1.9911,0 +4.119,-1.9909,-1.7125,-1.5107,0.081615,1.9909,0 +4.12,-1.9908,-1.7123,-1.5104,0.081134,1.9908,0 +4.121,-1.9906,-1.7122,-1.5101,0.080653,1.9906,0 +4.122,-1.9904,-1.712,-1.5097,0.080173,1.9904,0 +4.123,-1.9902,-1.7119,-1.5094,0.079692,1.9902,0 +4.124,-1.9901,-1.7117,-1.5091,0.079211,1.9901,0 +4.125,-1.9899,-1.7115,-1.5088,0.07873,1.9899,0 +4.126,-1.9897,-1.7114,-1.5085,0.078249,1.9897,0 +4.127,-1.9895,-1.7112,-1.5081,0.077768,1.9895,0 +4.128,-1.9894,-1.7111,-1.5078,0.077287,1.9894,0 +4.129,-1.9892,-1.7109,-1.5075,0.076807,1.9892,0 +4.13,-1.989,-1.7107,-1.5072,0.076326,1.989,0 +4.131,-1.9888,-1.7106,-1.5068,0.075845,1.9888,0 +4.132,-1.9887,-1.7104,-1.5065,0.075364,1.9887,0 +4.133,-1.9885,-1.7103,-1.5062,0.074883,1.9885,0 +4.134,-1.9883,-1.7101,-1.5059,0.074402,1.9883,0 +4.135,-1.9881,-1.7099,-1.5056,0.073921,1.9881,0 +4.136,-1.988,-1.7098,-1.5052,0.07344,1.988,0 +4.137,-1.9878,-1.7096,-1.5049,0.07296,1.9878,0 +4.138,-1.9876,-1.7095,-1.5046,0.072479,1.9876,0 +4.139,-1.9874,-1.7093,-1.5043,0.071998,1.9874,0 +4.14,-1.9873,-1.7091,-1.504,0.071517,1.9873,0 +4.141,-1.9871,-1.709,-1.5036,0.071036,1.9871,0 +4.142,-1.9869,-1.7088,-1.5033,0.070555,1.9869,0 +4.143,-1.9867,-1.7087,-1.503,0.070074,1.9867,0 +4.144,-1.9866,-1.7085,-1.5027,0.069593,1.9866,0 +4.145,-1.9864,-1.7083,-1.5024,0.069113,1.9864,0 +4.146,-1.9862,-1.7082,-1.502,0.068632,1.9862,0 +4.147,-1.986,-1.708,-1.5017,0.068151,1.986,0 +4.148,-1.9859,-1.7079,-1.5014,0.06767,1.9859,0 +4.149,-1.9857,-1.7077,-1.5011,0.067189,1.9857,0 +4.15,-1.9855,-1.7076,-1.5008,0.066708,1.9855,0 +4.151,-1.9853,-1.7074,-1.5004,0.066227,1.9853,0 +4.152,-1.9852,-1.7072,-1.5001,0.065747,1.9852,0 +4.153,-1.985,-1.7071,-1.4998,0.065266,1.985,0 +4.154,-1.9848,-1.7069,-1.4995,0.064785,1.9848,0 +4.155,-1.9846,-1.7068,-1.4991,0.064304,1.9846,0 +4.156,-1.9845,-1.7066,-1.4988,0.063823,1.9845,0 +4.157,-1.9843,-1.7064,-1.4985,0.063342,1.9843,0 +4.158,-1.9841,-1.7063,-1.4982,0.062861,1.9841,0 +4.159,-1.9839,-1.7061,-1.4979,0.06238,1.9839,0 +4.16,-1.9838,-1.706,-1.4975,0.0619,1.9838,0 +4.161,-1.9836,-1.7058,-1.4972,0.061419,1.9836,0 +4.162,-1.9834,-1.7056,-1.4969,0.060938,1.9834,0 +4.163,-1.9832,-1.7055,-1.4966,0.060457,1.9832,0 +4.164,-1.9831,-1.7053,-1.4963,0.059976,1.9831,0 +4.165,-1.9829,-1.7052,-1.4959,0.059495,1.9829,0 +4.166,-1.9827,-1.705,-1.4956,0.059014,1.9827,0 +4.167,-1.9825,-1.7048,-1.4953,0.058533,1.9825,0 +4.168,-1.9823,-1.7047,-1.495,0.058053,1.9823,0 +4.169,-1.9822,-1.7045,-1.4947,0.057572,1.9822,0 +4.17,-1.982,-1.7044,-1.4943,0.057091,1.982,0 +4.171,-1.9818,-1.7042,-1.494,0.05661,1.9818,0 +4.172,-1.9816,-1.704,-1.4937,0.056129,1.9816,0 +4.173,-1.9815,-1.7039,-1.4934,0.055648,1.9815,0 +4.174,-1.9813,-1.7037,-1.493,0.055167,1.9813,0 +4.175,-1.9811,-1.7036,-1.4927,0.054686,1.9811,0 +4.176,-1.9809,-1.7034,-1.4924,0.054206,1.9809,0 +4.177,-1.9808,-1.7032,-1.4921,0.053725,1.9808,0 +4.178,-1.9806,-1.7031,-1.4918,0.053244,1.9806,0 +4.179,-1.9804,-1.7029,-1.4914,0.052763,1.9804,0 +4.18,-1.9802,-1.7028,-1.4911,0.052282,1.9802,0 +4.181,-1.9801,-1.7026,-1.4908,0.051801,1.9801,0 +4.182,-1.9799,-1.7024,-1.4905,0.05132,1.9799,0 +4.183,-1.9797,-1.7023,-1.4902,0.05084,1.9797,0 +4.184,-1.9795,-1.7021,-1.4898,0.050359,1.9795,0 +4.185,-1.9794,-1.702,-1.4895,0.049878,1.9794,0 +4.186,-1.9792,-1.7018,-1.4892,0.049397,1.9792,0 +4.187,-1.979,-1.7016,-1.4889,0.048916,1.979,0 +4.188,-1.9788,-1.7015,-1.4886,0.048435,1.9788,0 +4.189,-1.9787,-1.7013,-1.4882,0.047954,1.9787,0 +4.19,-1.9785,-1.7012,-1.4879,0.047473,1.9785,0 +4.191,-1.9783,-1.701,-1.4876,0.046993,1.9783,0 +4.192,-1.9781,-1.7008,-1.4873,0.046504,1.9781,0 +4.193,-1.9779,-1.7007,-1.4869,0.046008,1.9779,0 +4.194,-1.9777,-1.7005,-1.4866,0.045503,1.9777,0 +4.195,-1.9775,-1.7003,-1.4863,0.04499,1.9775,0 +4.196,-1.9773,-1.7001,-1.4859,0.044469,1.9773,0 +4.197,-1.9771,-1.6999,-1.4856,0.043939,1.9771,0 +4.198,-1.9768,-1.6998,-1.4852,0.043402,1.9768,0 +4.199,-1.9766,-1.6996,-1.4849,0.042856,1.9766,0 +4.2,-1.9763,-1.6994,-1.4845,0.042302,1.9763,0 +4.201,-1.9761,-1.6992,-1.4842,0.04174,1.9761,0 +4.202,-1.9758,-1.699,-1.4838,0.041177,1.9758,0 +4.203,-1.9755,-1.6988,-1.4834,0.040614,1.9755,0 +4.204,-1.9753,-1.6986,-1.4831,0.040051,1.9753,0 +4.205,-1.975,-1.6984,-1.4827,0.039488,1.975,0 +4.206,-1.9747,-1.6981,-1.4824,0.038925,1.9747,0 +4.207,-1.9744,-1.6979,-1.482,0.038362,1.9744,0 +4.208,-1.9742,-1.6977,-1.4817,0.0378,1.9742,0 +4.209,-1.9739,-1.6975,-1.4813,0.037237,1.9739,0 +4.21,-1.9736,-1.6973,-1.4809,0.036674,1.9736,0 +4.211,-1.9734,-1.6971,-1.4806,0.036111,1.9734,0 +4.212,-1.9731,-1.6969,-1.4802,0.035548,1.9731,0 +4.213,-1.9728,-1.6967,-1.4799,0.034985,1.9728,0 +4.214,-1.9726,-1.6965,-1.4795,0.034422,1.9726,0 +4.215,-1.9723,-1.6963,-1.4791,0.033859,1.9723,0 +4.216,-1.972,-1.6961,-1.4788,0.033296,1.972,0 +4.217,-1.9718,-1.6959,-1.4784,0.032734,1.9718,0 +4.218,-1.9715,-1.6957,-1.4781,0.032171,1.9715,0 +4.219,-1.9712,-1.6955,-1.4777,0.031608,1.9712,0 +4.22,-1.971,-1.6953,-1.4773,0.031045,1.971,0 +4.221,-1.9707,-1.6951,-1.477,0.030482,1.9707,0 +4.222,-1.9704,-1.6949,-1.4766,0.029919,1.9704,0 +4.223,-1.9702,-1.6947,-1.4763,0.029356,1.9702,0 +4.224,-1.9699,-1.6945,-1.4759,0.028793,1.9699,0 +4.225,-1.9696,-1.6943,-1.4755,0.028231,1.9696,0 +4.226,-1.9693,-1.6941,-1.4752,0.027668,1.9693,0 +4.227,-1.9691,-1.6939,-1.4748,0.027105,1.9691,0 +4.228,-1.9688,-1.6937,-1.4745,0.026542,1.9688,0 +4.229,-1.9685,-1.6935,-1.4741,0.025979,1.9685,0 +4.23,-1.9683,-1.6933,-1.4737,0.025416,1.9683,0 +4.231,-1.968,-1.6931,-1.4734,0.024853,1.968,0 +4.232,-1.9677,-1.6929,-1.473,0.02429,1.9677,0 +4.233,-1.9675,-1.6927,-1.4727,0.023728,1.9675,0 +4.234,-1.9672,-1.6925,-1.4723,0.023165,1.9672,0 +4.235,-1.9669,-1.6923,-1.4719,0.022602,1.9669,0 +4.236,-1.9667,-1.6921,-1.4716,0.022039,1.9667,0 +4.237,-1.9664,-1.6919,-1.4712,0.021476,1.9664,0 +4.238,-1.9661,-1.6917,-1.4709,0.020913,1.9661,0 +4.239,-1.9659,-1.6914,-1.4705,0.02035,1.9659,0 +4.24,-1.9656,-1.6912,-1.4701,0.019787,1.9656,0 +4.241,-1.9653,-1.691,-1.4698,0.019225,1.9653,0 +4.242,-1.9651,-1.6908,-1.4694,0.018662,1.9651,0 +4.243,-1.9648,-1.6906,-1.4691,0.018099,1.9648,0 +4.244,-1.9645,-1.6904,-1.4687,0.017536,1.9645,0 +4.245,-1.9642,-1.6902,-1.4683,0.016973,1.9642,0 +4.246,-1.964,-1.69,-1.468,0.01641,1.964,0 +4.247,-1.9637,-1.6898,-1.4676,0.015847,1.9637,0 +4.248,-1.9634,-1.6896,-1.4673,0.015284,1.9634,0 +4.249,-1.9632,-1.6894,-1.4669,0.014722,1.9632,0 +4.25,-1.9629,-1.6892,-1.4665,0.014159,1.9629,0 +4.251,-1.9626,-1.689,-1.4662,0.013596,1.9626,0 +4.252,-1.9624,-1.6888,-1.4658,0.013033,1.9624,0 +4.253,-1.9621,-1.6886,-1.4655,0.01247,1.9621,0 +4.254,-1.9618,-1.6884,-1.4651,0.011907,1.9618,0 +4.255,-1.9616,-1.6882,-1.4647,0.011344,1.9616,0 +4.256,-1.9613,-1.688,-1.4644,0.010781,1.9613,0 +4.257,-1.961,-1.6878,-1.464,0.010219,1.961,0 +4.258,-1.9608,-1.6876,-1.4637,0.0096556,1.9608,0 +4.259,-1.9605,-1.6874,-1.4633,0.0090928,1.9605,0 +4.26,-1.9602,-1.6872,-1.4629,0.0085299,1.9602,0 +4.261,-1.96,-1.687,-1.4626,0.007967,1.96,0 +4.262,-1.9597,-1.6868,-1.4622,0.0074041,1.9597,0 +4.263,-1.9594,-1.6866,-1.4619,0.0068412,1.9594,0 +4.264,-1.9591,-1.6864,-1.4615,0.0062784,1.9591,0 +4.265,-1.9589,-1.6862,-1.4611,0.0057155,1.9589,0 +4.266,-1.9586,-1.686,-1.4608,0.0051526,1.9586,0 +4.267,-1.9583,-1.6858,-1.4604,0.0045897,1.9583,0 +4.268,-1.9581,-1.6856,-1.4601,0.0040269,1.9581,0 +4.269,-1.9578,-1.6854,-1.4597,0.003464,1.9578,0 +4.27,-1.9575,-1.6852,-1.4593,0.0029011,1.9575,0 +4.271,-1.9573,-1.685,-1.459,0.0023382,1.9573,0 +4.272,-1.957,-1.6847,-1.4586,0.0017753,1.957,0 +4.273,-1.9567,-1.6845,-1.4583,0.0012125,1.9567,0 +4.274,-1.9565,-1.6843,-1.4579,0.00064959,1.9565,0 +4.275,-1.9562,-1.6841,-1.4575,8.2833e-05,1.9562,0 +4.276,-1.9559,-1.6839,-1.4572,-0.0004879,1.9559,0 +4.277,-1.9556,-1.6837,-1.4568,-0.0010626,1.9556,0 +4.278,-1.9553,-1.6835,-1.4564,-0.0016413,1.9553,0 +4.279,-1.955,-1.6833,-1.4561,-0.0022239,1.955,0 +4.28,-1.9547,-1.6831,-1.4557,-0.0028106,1.9547,0 +4.281,-1.9544,-1.6829,-1.4553,-0.0034012,1.9544,0 +4.282,-1.9541,-1.6827,-1.4549,-0.0039958,1.9541,0 +4.283,-1.9537,-1.6825,-1.4545,-0.0045943,1.9537,0 +4.284,-1.9534,-1.6823,-1.4541,-0.0051968,1.9534,0 +4.285,-1.9531,-1.6821,-1.4537,-0.0057995,1.9531,0 +4.286,-1.9527,-1.6819,-1.4533,-0.0064021,1.9527,0 +4.287,-1.9524,-1.6816,-1.4529,-0.0070047,1.9524,0 +4.288,-1.9521,-1.6814,-1.4526,-0.0076074,1.9521,0 +4.289,-1.9517,-1.6812,-1.4522,-0.00821,1.9517,0 +4.29,-1.9514,-1.681,-1.4518,-0.0088126,1.9514,0 +4.291,-1.9511,-1.6808,-1.4514,-0.0094153,1.9511,0 +4.292,-1.9507,-1.6806,-1.451,-0.010018,1.9507,0 +4.293,-1.9504,-1.6804,-1.4506,-0.010621,1.9504,0 +4.294,-1.9501,-1.6802,-1.4502,-0.011223,1.9501,0 +4.295,-1.9497,-1.68,-1.4498,-0.011826,1.9497,0 +4.296,-1.9494,-1.6797,-1.4494,-0.012428,1.9494,0 +4.297,-1.9491,-1.6795,-1.449,-0.013031,1.9491,0 +4.298,-1.9487,-1.6793,-1.4486,-0.013634,1.9487,0 +4.299,-1.9484,-1.6791,-1.4482,-0.014236,1.9484,0 +4.3,-1.9481,-1.6789,-1.4479,-0.014839,1.9481,0 +4.301,-1.9477,-1.6787,-1.4475,-0.015442,1.9477,0 +4.302,-1.9474,-1.6785,-1.4471,-0.016044,1.9474,0 +4.303,-1.9471,-1.6783,-1.4467,-0.016647,1.9471,0 +4.304,-1.9467,-1.6781,-1.4463,-0.01725,1.9467,0 +4.305,-1.9464,-1.6778,-1.4459,-0.017852,1.9464,0 +4.306,-1.9461,-1.6776,-1.4455,-0.018455,1.9461,0 +4.307,-1.9457,-1.6774,-1.4451,-0.019057,1.9457,0 +4.308,-1.9454,-1.6772,-1.4447,-0.01966,1.9454,0 +4.309,-1.945,-1.677,-1.4443,-0.020263,1.945,0 +4.31,-1.9447,-1.6768,-1.4439,-0.020865,1.9447,0 +4.311,-1.9444,-1.6766,-1.4435,-0.021468,1.9444,0 +4.312,-1.944,-1.6764,-1.4431,-0.022071,1.944,0 +4.313,-1.9437,-1.6762,-1.4428,-0.022673,1.9437,0 +4.314,-1.9434,-1.676,-1.4424,-0.023276,1.9434,0 +4.315,-1.943,-1.6757,-1.442,-0.023878,1.943,0 +4.316,-1.9427,-1.6755,-1.4416,-0.024481,1.9427,0 +4.317,-1.9424,-1.6753,-1.4412,-0.025084,1.9424,0 +4.318,-1.942,-1.6751,-1.4408,-0.025686,1.942,0 +4.319,-1.9417,-1.6749,-1.4404,-0.026289,1.9417,0 +4.32,-1.9414,-1.6747,-1.44,-0.026892,1.9414,0 +4.321,-1.941,-1.6745,-1.4396,-0.027494,1.941,0 +4.322,-1.9407,-1.6743,-1.4392,-0.028097,1.9407,0 +4.323,-1.9404,-1.6741,-1.4388,-0.0287,1.9404,0 +4.324,-1.94,-1.6738,-1.4384,-0.029302,1.94,0 +4.325,-1.9397,-1.6736,-1.4381,-0.029905,1.9397,0 +4.326,-1.9394,-1.6734,-1.4377,-0.030507,1.9394,0 +4.327,-1.939,-1.6732,-1.4373,-0.03111,1.939,0 +4.328,-1.9387,-1.673,-1.4369,-0.031713,1.9387,0 +4.329,-1.9384,-1.6728,-1.4365,-0.032315,1.9384,0 +4.33,-1.938,-1.6726,-1.4361,-0.032918,1.938,0 +4.331,-1.9377,-1.6724,-1.4357,-0.033521,1.9377,0 +4.332,-1.9373,-1.6722,-1.4353,-0.034123,1.9373,0 +4.333,-1.937,-1.6719,-1.4349,-0.034726,1.937,0 +4.334,-1.9367,-1.6717,-1.4345,-0.035329,1.9367,0 +4.335,-1.9363,-1.6715,-1.4341,-0.035931,1.9363,0 +4.336,-1.936,-1.6713,-1.4337,-0.036534,1.936,0 +4.337,-1.9357,-1.6711,-1.4334,-0.037136,1.9357,0 +4.338,-1.9353,-1.6709,-1.433,-0.037739,1.9353,0 +4.339,-1.935,-1.6707,-1.4326,-0.038342,1.935,0 +4.34,-1.9347,-1.6705,-1.4322,-0.038944,1.9347,0 +4.341,-1.9343,-1.6703,-1.4318,-0.039547,1.9343,0 +4.342,-1.934,-1.6701,-1.4314,-0.04015,1.934,0 +4.343,-1.9337,-1.6698,-1.431,-0.040752,1.9337,0 +4.344,-1.9333,-1.6696,-1.4306,-0.041355,1.9333,0 +4.345,-1.933,-1.6694,-1.4302,-0.041957,1.933,0 +4.346,-1.9327,-1.6692,-1.4298,-0.04256,1.9327,0 +4.347,-1.9323,-1.669,-1.4294,-0.043163,1.9323,0 +4.348,-1.932,-1.6688,-1.429,-0.043765,1.932,0 +4.349,-1.9317,-1.6686,-1.4286,-0.044368,1.9317,0 +4.35,-1.9313,-1.6684,-1.4283,-0.044971,1.9313,0 +4.351,-1.931,-1.6682,-1.4279,-0.045573,1.931,0 +4.352,-1.9307,-1.6679,-1.4275,-0.046176,1.9307,0 +4.353,-1.9303,-1.6677,-1.4271,-0.046779,1.9303,0 +4.354,-1.93,-1.6675,-1.4267,-0.047381,1.93,0 +4.355,-1.9296,-1.6673,-1.4263,-0.047984,1.9296,0 +4.356,-1.9293,-1.6671,-1.4259,-0.048586,1.9293,0 +4.357,-1.929,-1.6669,-1.4255,-0.049189,1.929,0 +4.358,-1.9286,-1.6667,-1.4251,-0.049792,1.9286,0 +4.359,-1.9283,-1.6665,-1.4247,-0.050397,1.9283,0 +4.36,-1.928,-1.6663,-1.4243,-0.051001,1.928,0 +4.361,-1.9276,-1.6661,-1.4239,-0.051607,1.9276,0 +4.362,-1.9272,-1.6659,-1.4235,-0.052213,1.9272,0 +4.363,-1.9269,-1.6657,-1.4231,-0.05282,1.9269,0 +4.364,-1.9265,-1.6655,-1.4227,-0.053428,1.9265,0 +4.365,-1.9262,-1.6653,-1.4223,-0.054036,1.9262,0 +4.366,-1.9258,-1.6651,-1.4219,-0.054645,1.9258,0 +4.367,-1.9254,-1.6649,-1.4214,-0.055255,1.9254,0 +4.368,-1.9251,-1.6647,-1.421,-0.055865,1.9251,0 +4.369,-1.9247,-1.6645,-1.4206,-0.056475,1.9247,0 +4.37,-1.9243,-1.6643,-1.4202,-0.057085,1.9243,0 +4.371,-1.9239,-1.6641,-1.4198,-0.057694,1.9239,0 +4.372,-1.9236,-1.6639,-1.4193,-0.058304,1.9236,0 +4.373,-1.9232,-1.6637,-1.4189,-0.058914,1.9232,0 +4.374,-1.9228,-1.6636,-1.4185,-0.059524,1.9228,0 +4.375,-1.9225,-1.6634,-1.4181,-0.060134,1.9225,0 +4.376,-1.9221,-1.6632,-1.4177,-0.060743,1.9221,0 +4.377,-1.9217,-1.663,-1.4173,-0.061353,1.9217,0 +4.378,-1.9213,-1.6628,-1.4168,-0.061963,1.9213,0 +4.379,-1.921,-1.6626,-1.4164,-0.062573,1.921,0 +4.38,-1.9206,-1.6624,-1.416,-0.063183,1.9206,0 +4.381,-1.9202,-1.6622,-1.4156,-0.063792,1.9202,0 +4.382,-1.9199,-1.662,-1.4152,-0.064402,1.9199,0 +4.383,-1.9195,-1.6618,-1.4147,-0.065012,1.9195,0 +4.384,-1.9191,-1.6616,-1.4143,-0.065622,1.9191,0 +4.385,-1.9187,-1.6615,-1.4139,-0.066232,1.9187,0 +4.386,-1.9184,-1.6613,-1.4135,-0.066841,1.9184,0 +4.387,-1.918,-1.6611,-1.4131,-0.067451,1.918,0 +4.388,-1.9176,-1.6609,-1.4126,-0.068061,1.9176,0 +4.389,-1.9172,-1.6607,-1.4122,-0.068671,1.9172,0 +4.39,-1.9169,-1.6605,-1.4118,-0.069281,1.9169,0 +4.391,-1.9165,-1.6603,-1.4114,-0.06989,1.9165,0 +4.392,-1.9161,-1.6601,-1.411,-0.0705,1.9161,0 +4.393,-1.9158,-1.6599,-1.4106,-0.07111,1.9158,0 +4.394,-1.9154,-1.6597,-1.4101,-0.07172,1.9154,0 +4.395,-1.915,-1.6595,-1.4097,-0.07233,1.915,0 +4.396,-1.9146,-1.6594,-1.4093,-0.07294,1.9146,0 +4.397,-1.9143,-1.6592,-1.4089,-0.073549,1.9143,0 +4.398,-1.9139,-1.659,-1.4085,-0.074159,1.9139,0 +4.399,-1.9135,-1.6588,-1.408,-0.074769,1.9135,0 +4.4,-1.9132,-1.6586,-1.4076,-0.075379,1.9132,0 +4.401,-1.9128,-1.6584,-1.4072,-0.075989,1.9128,0 +4.402,-1.9124,-1.6582,-1.4068,-0.076598,1.9124,0 +4.403,-1.912,-1.658,-1.4064,-0.077208,1.912,0 +4.404,-1.9117,-1.6578,-1.4059,-0.077818,1.9117,0 +4.405,-1.9113,-1.6576,-1.4055,-0.078428,1.9113,0 +4.406,-1.9109,-1.6574,-1.4051,-0.079038,1.9109,0 +4.407,-1.9106,-1.6573,-1.4047,-0.079647,1.9106,0 +4.408,-1.9102,-1.6571,-1.4043,-0.080257,1.9102,0 +4.409,-1.9098,-1.6569,-1.4039,-0.080867,1.9098,0 +4.41,-1.9094,-1.6567,-1.4034,-0.081477,1.9094,0 +4.411,-1.9091,-1.6565,-1.403,-0.082087,1.9091,0 +4.412,-1.9087,-1.6563,-1.4026,-0.082696,1.9087,0 +4.413,-1.9083,-1.6561,-1.4022,-0.083306,1.9083,0 +4.414,-1.908,-1.6559,-1.4018,-0.083916,1.908,0 +4.415,-1.9076,-1.6557,-1.4013,-0.084526,1.9076,0 +4.416,-1.9072,-1.6555,-1.4009,-0.085136,1.9072,0 +4.417,-1.9068,-1.6553,-1.4005,-0.085745,1.9068,0 +4.418,-1.9065,-1.6552,-1.4001,-0.086355,1.9065,0 +4.419,-1.9061,-1.655,-1.3997,-0.086965,1.9061,0 +4.42,-1.9057,-1.6548,-1.3992,-0.087575,1.9057,0 +4.421,-1.9054,-1.6546,-1.3988,-0.088185,1.9054,0 +4.422,-1.905,-1.6544,-1.3984,-0.088795,1.905,0 +4.423,-1.9046,-1.6542,-1.398,-0.089404,1.9046,0 +4.424,-1.9042,-1.654,-1.3976,-0.090014,1.9042,0 +4.425,-1.9039,-1.6538,-1.3971,-0.090624,1.9039,0 +4.426,-1.9035,-1.6536,-1.3967,-0.091234,1.9035,0 +4.427,-1.9031,-1.6534,-1.3963,-0.091844,1.9031,0 +4.428,-1.9028,-1.6532,-1.3959,-0.092453,1.9028,0 +4.429,-1.9024,-1.6531,-1.3955,-0.093063,1.9024,0 +4.43,-1.902,-1.6529,-1.3951,-0.093673,1.902,0 +4.431,-1.9016,-1.6527,-1.3946,-0.094283,1.9016,0 +4.432,-1.9013,-1.6525,-1.3942,-0.094893,1.9013,0 +4.433,-1.9009,-1.6523,-1.3938,-0.095502,1.9009,0 +4.434,-1.9005,-1.6521,-1.3934,-0.096112,1.9005,0 +4.435,-1.9001,-1.6519,-1.393,-0.096722,1.9001,0 +4.436,-1.8998,-1.6517,-1.3925,-0.097332,1.8998,0 +4.437,-1.8994,-1.6515,-1.3921,-0.097942,1.8994,0 +4.438,-1.899,-1.6513,-1.3917,-0.098551,1.899,0 +4.439,-1.8987,-1.6511,-1.3913,-0.099161,1.8987,0 +4.44,-1.8983,-1.651,-1.3909,-0.099771,1.8983,0 +4.441,-1.8979,-1.6508,-1.3904,-0.10038,1.8979,0 +4.442,-1.8975,-1.6506,-1.39,-0.10099,1.8975,0 +4.443,-1.8971,-1.6504,-1.3896,-0.1016,1.8971,0 +4.444,-1.8967,-1.6502,-1.3892,-0.10222,1.8967,0 +4.445,-1.8963,-1.65,-1.3888,-0.10283,1.8963,0 +4.446,-1.8959,-1.6498,-1.3883,-0.10344,1.8959,0 +4.447,-1.8955,-1.6496,-1.3879,-0.10406,1.8955,0 +4.448,-1.895,-1.6494,-1.3875,-0.10467,1.895,0 +4.449,-1.8946,-1.6493,-1.3871,-0.10529,1.8946,0 +4.45,-1.8942,-1.6491,-1.3866,-0.10591,1.8942,0 +4.451,-1.8937,-1.6489,-1.3862,-0.10652,1.8937,0 +4.452,-1.8933,-1.6487,-1.3858,-0.10714,1.8933,0 +4.453,-1.8928,-1.6485,-1.3853,-0.10776,1.8928,0 +4.454,-1.8924,-1.6483,-1.3849,-0.10837,1.8924,0 +4.455,-1.8919,-1.6481,-1.3845,-0.10899,1.8919,0 +4.456,-1.8915,-1.6479,-1.3841,-0.10961,1.8915,0 +4.457,-1.891,-1.6477,-1.3836,-0.11022,1.891,0 +4.458,-1.8906,-1.6476,-1.3832,-0.11084,1.8906,0 +4.459,-1.8901,-1.6474,-1.3828,-0.11145,1.8901,0 +4.46,-1.8897,-1.6472,-1.3823,-0.11207,1.8897,0 +4.461,-1.8892,-1.647,-1.3819,-0.11269,1.8892,0 +4.462,-1.8888,-1.6468,-1.3815,-0.1133,1.8888,0 +4.463,-1.8883,-1.6466,-1.3811,-0.11392,1.8883,0 +4.464,-1.8879,-1.6464,-1.3806,-0.11454,1.8879,0 +4.465,-1.8875,-1.6462,-1.3802,-0.11515,1.8875,0 +4.466,-1.887,-1.6461,-1.3798,-0.11577,1.887,0 +4.467,-1.8866,-1.6459,-1.3793,-0.11639,1.8866,0 +4.468,-1.8861,-1.6457,-1.3789,-0.117,1.8861,0 +4.469,-1.8857,-1.6455,-1.3785,-0.11762,1.8857,0 +4.47,-1.8852,-1.6453,-1.3781,-0.11824,1.8852,0 +4.471,-1.8848,-1.6451,-1.3776,-0.11885,1.8848,0 +4.472,-1.8843,-1.6449,-1.3772,-0.11947,1.8843,0 +4.473,-1.8839,-1.6447,-1.3768,-0.12008,1.8839,0 +4.474,-1.8834,-1.6445,-1.3763,-0.1207,1.8834,0 +4.475,-1.883,-1.6444,-1.3759,-0.12132,1.883,0 +4.476,-1.8825,-1.6442,-1.3755,-0.12193,1.8825,0 +4.477,-1.8821,-1.644,-1.3751,-0.12255,1.8821,0 +4.478,-1.8816,-1.6438,-1.3746,-0.12317,1.8816,0 +4.479,-1.8812,-1.6436,-1.3742,-0.12378,1.8812,0 +4.48,-1.8808,-1.6434,-1.3738,-0.1244,1.8808,0 +4.481,-1.8803,-1.6432,-1.3733,-0.12502,1.8803,0 +4.482,-1.8799,-1.643,-1.3729,-0.12563,1.8799,0 +4.483,-1.8794,-1.6429,-1.3725,-0.12625,1.8794,0 +4.484,-1.879,-1.6427,-1.3721,-0.12687,1.879,0 +4.485,-1.8785,-1.6425,-1.3716,-0.12748,1.8785,0 +4.486,-1.8781,-1.6423,-1.3712,-0.1281,1.8781,0 +4.487,-1.8776,-1.6421,-1.3708,-0.12872,1.8776,0 +4.488,-1.8772,-1.6419,-1.3703,-0.12933,1.8772,0 +4.489,-1.8767,-1.6417,-1.3699,-0.12995,1.8767,0 +4.49,-1.8763,-1.6415,-1.3695,-0.13056,1.8763,0 +4.491,-1.8758,-1.6414,-1.3691,-0.13118,1.8758,0 +4.492,-1.8754,-1.6412,-1.3686,-0.1318,1.8754,0 +4.493,-1.875,-1.641,-1.3682,-0.13241,1.875,0 +4.494,-1.8745,-1.6408,-1.3678,-0.13303,1.8745,0 +4.495,-1.8741,-1.6406,-1.3673,-0.13365,1.8741,0 +4.496,-1.8736,-1.6404,-1.3669,-0.13426,1.8736,0 +4.497,-1.8732,-1.6402,-1.3665,-0.13488,1.8732,0 +4.498,-1.8727,-1.64,-1.3661,-0.1355,1.8727,0 +4.499,-1.8723,-1.6398,-1.3656,-0.13611,1.8723,0 +4.5,-1.8718,-1.6397,-1.3652,-0.13673,1.8718,0 +4.501,-1.8714,-1.6395,-1.3648,-0.13735,1.8714,0 +4.502,-1.8709,-1.6393,-1.3643,-0.13796,1.8709,0 +4.503,-1.8705,-1.6391,-1.3639,-0.13858,1.8705,0 +4.504,-1.87,-1.6389,-1.3635,-0.1392,1.87,0 +4.505,-1.8696,-1.6387,-1.3631,-0.13981,1.8696,0 +4.506,-1.8691,-1.6385,-1.3626,-0.14043,1.8691,0 +4.507,-1.8687,-1.6383,-1.3622,-0.14104,1.8687,0 +4.508,-1.8683,-1.6382,-1.3618,-0.14166,1.8683,0 +4.509,-1.8678,-1.638,-1.3614,-0.14228,1.8678,0 +4.51,-1.8674,-1.6378,-1.3609,-0.14289,1.8674,0 +4.511,-1.8669,-1.6376,-1.3605,-0.14351,1.8669,0 +4.512,-1.8665,-1.6374,-1.3601,-0.14413,1.8665,0 +4.513,-1.866,-1.6372,-1.3596,-0.14474,1.866,0 +4.514,-1.8656,-1.637,-1.3592,-0.14536,1.8656,0 +4.515,-1.8651,-1.6368,-1.3588,-0.14598,1.8651,0 +4.516,-1.8647,-1.6366,-1.3584,-0.14659,1.8647,0 +4.517,-1.8642,-1.6365,-1.3579,-0.14721,1.8642,0 +4.518,-1.8638,-1.6363,-1.3575,-0.14783,1.8638,0 +4.519,-1.8633,-1.6361,-1.3571,-0.14844,1.8633,0 +4.52,-1.8629,-1.6359,-1.3566,-0.14906,1.8629,0 +4.521,-1.8624,-1.6357,-1.3562,-0.14967,1.8624,0 +4.522,-1.862,-1.6355,-1.3558,-0.15029,1.862,0 +4.523,-1.8616,-1.6353,-1.3554,-0.15091,1.8616,0 +4.524,-1.8611,-1.6351,-1.3549,-0.15152,1.8611,0 +4.525,-1.8606,-1.635,-1.3545,-0.15213,1.8606,0 +4.526,-1.8602,-1.6348,-1.3541,-0.15274,1.8602,0 +4.527,-1.8597,-1.6346,-1.3536,-0.15334,1.8597,0 +4.528,-1.8593,-1.6344,-1.3532,-0.15394,1.8593,0 +4.529,-1.8588,-1.6343,-1.3528,-0.15454,1.8588,0 +4.53,-1.8583,-1.6341,-1.3524,-0.15514,1.8583,0 +4.531,-1.8578,-1.6339,-1.3519,-0.15573,1.8578,0 +4.532,-1.8573,-1.6337,-1.3515,-0.15632,1.8573,0 +4.533,-1.8568,-1.6336,-1.3511,-0.15691,1.8568,0 +4.534,-1.8563,-1.6334,-1.3507,-0.1575,1.8563,0 +4.535,-1.8559,-1.6332,-1.3503,-0.15809,1.8559,0 +4.536,-1.8554,-1.6331,-1.3498,-0.15868,1.8554,0 +4.537,-1.8549,-1.6329,-1.3494,-0.15927,1.8549,0 +4.538,-1.8544,-1.6327,-1.349,-0.15985,1.8544,0 +4.539,-1.8539,-1.6326,-1.3486,-0.16044,1.8539,0 +4.54,-1.8534,-1.6324,-1.3482,-0.16103,1.8534,0 +4.541,-1.8529,-1.6322,-1.3477,-0.16162,1.8529,0 +4.542,-1.8524,-1.6321,-1.3473,-0.16221,1.8524,0 +4.543,-1.8519,-1.6319,-1.3469,-0.16279,1.8519,0 +4.544,-1.8514,-1.6317,-1.3465,-0.16338,1.8514,0 +4.545,-1.851,-1.6316,-1.346,-0.16397,1.851,0 +4.546,-1.8505,-1.6314,-1.3456,-0.16456,1.8505,0 +4.547,-1.85,-1.6312,-1.3452,-0.16515,1.85,0 +4.548,-1.8495,-1.6311,-1.3448,-0.16573,1.8495,0 +4.549,-1.849,-1.6309,-1.3444,-0.16632,1.849,0 +4.55,-1.8485,-1.6307,-1.3439,-0.16691,1.8485,0 +4.551,-1.848,-1.6306,-1.3435,-0.1675,1.848,0 +4.552,-1.8475,-1.6304,-1.3431,-0.16809,1.8475,0 +4.553,-1.847,-1.6303,-1.3427,-0.16868,1.847,0 +4.554,-1.8465,-1.6301,-1.3422,-0.16926,1.8465,0 +4.555,-1.846,-1.6299,-1.3418,-0.16985,1.846,0 +4.556,-1.8456,-1.6298,-1.3414,-0.17044,1.8456,0 +4.557,-1.8451,-1.6296,-1.341,-0.17103,1.8451,0 +4.558,-1.8446,-1.6294,-1.3406,-0.17162,1.8446,0 +4.559,-1.8441,-1.6293,-1.3401,-0.1722,1.8441,0 +4.56,-1.8436,-1.6291,-1.3397,-0.17279,1.8436,0 +4.561,-1.8431,-1.6289,-1.3393,-0.17338,1.8431,0 +4.562,-1.8426,-1.6288,-1.3389,-0.17397,1.8426,0 +4.563,-1.8421,-1.6286,-1.3384,-0.17456,1.8421,0 +4.564,-1.8416,-1.6284,-1.338,-0.17515,1.8416,0 +4.565,-1.8411,-1.6283,-1.3376,-0.17573,1.8411,0 +4.566,-1.8406,-1.6281,-1.3372,-0.17632,1.8406,0 +4.567,-1.8402,-1.6279,-1.3368,-0.17691,1.8402,0 +4.568,-1.8397,-1.6278,-1.3363,-0.1775,1.8397,0 +4.569,-1.8392,-1.6276,-1.3359,-0.17809,1.8392,0 +4.57,-1.8387,-1.6274,-1.3355,-0.17867,1.8387,0 +4.571,-1.8382,-1.6273,-1.3351,-0.17926,1.8382,0 +4.572,-1.8377,-1.6271,-1.3347,-0.17985,1.8377,0 +4.573,-1.8372,-1.6269,-1.3342,-0.18044,1.8372,0 +4.574,-1.8367,-1.6268,-1.3338,-0.18103,1.8367,0 +4.575,-1.8362,-1.6266,-1.3334,-0.18162,1.8362,0 +4.576,-1.8357,-1.6264,-1.333,-0.1822,1.8357,0 +4.577,-1.8353,-1.6263,-1.3325,-0.18279,1.8353,0 +4.578,-1.8348,-1.6261,-1.3321,-0.18338,1.8348,0 +4.579,-1.8343,-1.6259,-1.3317,-0.18397,1.8343,0 +4.58,-1.8338,-1.6258,-1.3313,-0.18456,1.8338,0 +4.581,-1.8333,-1.6256,-1.3309,-0.18514,1.8333,0 +4.582,-1.8328,-1.6254,-1.3304,-0.18573,1.8328,0 +4.583,-1.8323,-1.6253,-1.33,-0.18632,1.8323,0 +4.584,-1.8318,-1.6251,-1.3296,-0.18691,1.8318,0 +4.585,-1.8313,-1.6249,-1.3292,-0.1875,1.8313,0 +4.586,-1.8308,-1.6248,-1.3287,-0.18809,1.8308,0 +4.587,-1.8303,-1.6246,-1.3283,-0.18867,1.8303,0 +4.588,-1.8299,-1.6244,-1.3279,-0.18926,1.8299,0 +4.589,-1.8294,-1.6243,-1.3275,-0.18985,1.8294,0 +4.59,-1.8289,-1.6241,-1.3271,-0.19044,1.8289,0 +4.591,-1.8284,-1.6239,-1.3266,-0.19103,1.8284,0 +4.592,-1.8279,-1.6238,-1.3262,-0.19161,1.8279,0 +4.593,-1.8274,-1.6236,-1.3258,-0.1922,1.8274,0 +4.594,-1.8269,-1.6234,-1.3254,-0.19279,1.8269,0 +4.595,-1.8264,-1.6233,-1.3249,-0.19338,1.8264,0 +4.596,-1.8259,-1.6231,-1.3245,-0.19397,1.8259,0 +4.597,-1.8254,-1.6229,-1.3241,-0.19455,1.8254,0 +4.598,-1.8249,-1.6228,-1.3237,-0.19514,1.8249,0 +4.599,-1.8245,-1.6226,-1.3233,-0.19573,1.8245,0 +4.6,-1.824,-1.6224,-1.3228,-0.19632,1.824,0 +4.601,-1.8235,-1.6223,-1.3224,-0.19691,1.8235,0 +4.602,-1.823,-1.6221,-1.322,-0.1975,1.823,0 +4.603,-1.8225,-1.6219,-1.3216,-0.19808,1.8225,0 +4.604,-1.822,-1.6218,-1.3211,-0.19867,1.822,0 +4.605,-1.8215,-1.6216,-1.3207,-0.19926,1.8215,0 +4.606,-1.821,-1.6214,-1.3203,-0.19985,1.821,0 +4.607,-1.8205,-1.6213,-1.3199,-0.20043,1.8205,0 +4.608,-1.82,-1.6211,-1.3195,-0.20102,1.82,0 +4.609,-1.8195,-1.621,-1.319,-0.2016,1.8195,0 +4.61,-1.819,-1.6208,-1.3186,-0.20218,1.819,0 +4.611,-1.8185,-1.6207,-1.3182,-0.20276,1.8185,0 +4.612,-1.818,-1.6205,-1.3177,-0.20334,1.818,0 +4.613,-1.8175,-1.6204,-1.3173,-0.20392,1.8175,0 +4.614,-1.817,-1.6202,-1.3169,-0.20449,1.817,0 +4.615,-1.8164,-1.6201,-1.3165,-0.20507,1.8164,0 +4.616,-1.8159,-1.6199,-1.316,-0.20564,1.8159,0 +4.617,-1.8154,-1.6198,-1.3156,-0.20621,1.8154,0 +4.618,-1.8148,-1.6197,-1.3151,-0.20679,1.8148,0 +4.619,-1.8143,-1.6195,-1.3147,-0.20736,1.8143,0 +4.62,-1.8138,-1.6194,-1.3143,-0.20793,1.8138,0 +4.621,-1.8132,-1.6192,-1.3138,-0.2085,1.8132,0 +4.622,-1.8127,-1.6191,-1.3134,-0.20908,1.8127,0 +4.623,-1.8122,-1.619,-1.313,-0.20965,1.8122,0 +4.624,-1.8117,-1.6188,-1.3125,-0.21022,1.8117,0 +4.625,-1.8111,-1.6187,-1.3121,-0.21079,1.8111,0 +4.626,-1.8106,-1.6186,-1.3117,-0.21136,1.8106,0 +4.627,-1.8101,-1.6184,-1.3112,-0.21194,1.8101,0 +4.628,-1.8095,-1.6183,-1.3108,-0.21251,1.8095,0 +4.629,-1.809,-1.6181,-1.3104,-0.21308,1.809,0 +4.63,-1.8085,-1.618,-1.3099,-0.21365,1.8085,0 +4.631,-1.808,-1.6179,-1.3095,-0.21423,1.808,0 +4.632,-1.8074,-1.6177,-1.3091,-0.2148,1.8074,0 +4.633,-1.8069,-1.6176,-1.3086,-0.21537,1.8069,0 +4.634,-1.8064,-1.6174,-1.3082,-0.21594,1.8064,0 +4.635,-1.8058,-1.6173,-1.3078,-0.21652,1.8058,0 +4.636,-1.8053,-1.6172,-1.3073,-0.21709,1.8053,0 +4.637,-1.8048,-1.617,-1.3069,-0.21766,1.8048,0 +4.638,-1.8042,-1.6169,-1.3065,-0.21823,1.8042,0 +4.639,-1.8037,-1.6168,-1.306,-0.21881,1.8037,0 +4.64,-1.8032,-1.6166,-1.3056,-0.21938,1.8032,0 +4.641,-1.8027,-1.6165,-1.3052,-0.21995,1.8027,0 +4.642,-1.8021,-1.6163,-1.3047,-0.22052,1.8021,0 +4.643,-1.8016,-1.6162,-1.3043,-0.2211,1.8016,0 +4.644,-1.8011,-1.6161,-1.3039,-0.22167,1.8011,0 +4.645,-1.8005,-1.6159,-1.3034,-0.22224,1.8005,0 +4.646,-1.8,-1.6158,-1.303,-0.22281,1.8,0 +4.647,-1.7995,-1.6156,-1.3026,-0.22339,1.7995,0 +4.648,-1.7989,-1.6155,-1.3021,-0.22396,1.7989,0 +4.649,-1.7984,-1.6154,-1.3017,-0.22453,1.7984,0 +4.65,-1.7979,-1.6152,-1.3013,-0.2251,1.7979,0 +4.651,-1.7974,-1.6151,-1.3008,-0.22568,1.7974,0 +4.652,-1.7968,-1.615,-1.3004,-0.22625,1.7968,0 +4.653,-1.7963,-1.6148,-1.3,-0.22682,1.7963,0 +4.654,-1.7958,-1.6147,-1.2995,-0.22739,1.7958,0 +4.655,-1.7952,-1.6145,-1.2991,-0.22797,1.7952,0 +4.656,-1.7947,-1.6144,-1.2987,-0.22854,1.7947,0 +4.657,-1.7942,-1.6143,-1.2982,-0.22911,1.7942,0 +4.658,-1.7937,-1.6141,-1.2978,-0.22968,1.7937,0 +4.659,-1.7931,-1.614,-1.2974,-0.23026,1.7931,0 +4.66,-1.7926,-1.6138,-1.2969,-0.23083,1.7926,0 +4.661,-1.7921,-1.6137,-1.2965,-0.2314,1.7921,0 +4.662,-1.7915,-1.6136,-1.2961,-0.23197,1.7915,0 +4.663,-1.791,-1.6134,-1.2956,-0.23255,1.791,0 +4.664,-1.7905,-1.6133,-1.2952,-0.23312,1.7905,0 +4.665,-1.7899,-1.6132,-1.2947,-0.23369,1.7899,0 +4.666,-1.7894,-1.613,-1.2943,-0.23426,1.7894,0 +4.667,-1.7889,-1.6129,-1.2939,-0.23484,1.7889,0 +4.668,-1.7884,-1.6127,-1.2934,-0.23541,1.7884,0 +4.669,-1.7878,-1.6126,-1.293,-0.23598,1.7878,0 +4.67,-1.7873,-1.6125,-1.2926,-0.23655,1.7873,0 +4.671,-1.7868,-1.6123,-1.2921,-0.23713,1.7868,0 +4.672,-1.7862,-1.6122,-1.2917,-0.2377,1.7862,0 +4.673,-1.7857,-1.612,-1.2913,-0.23827,1.7857,0 +4.674,-1.7852,-1.6119,-1.2908,-0.23884,1.7852,0 +4.675,-1.7847,-1.6118,-1.2904,-0.23942,1.7847,0 +4.676,-1.7841,-1.6116,-1.29,-0.23999,1.7841,0 +4.677,-1.7836,-1.6115,-1.2895,-0.24056,1.7836,0 +4.678,-1.7831,-1.6114,-1.2891,-0.24113,1.7831,0 +4.679,-1.7825,-1.6112,-1.2887,-0.24171,1.7825,0 +4.68,-1.782,-1.6111,-1.2882,-0.24228,1.782,0 +4.681,-1.7815,-1.6109,-1.2878,-0.24285,1.7815,0 +4.682,-1.7809,-1.6108,-1.2874,-0.24342,1.7809,0 +4.683,-1.7804,-1.6107,-1.2869,-0.24399,1.7804,0 +4.684,-1.7799,-1.6105,-1.2865,-0.24457,1.7799,0 +4.685,-1.7794,-1.6104,-1.2861,-0.24514,1.7794,0 +4.686,-1.7788,-1.6102,-1.2856,-0.24571,1.7788,0 +4.687,-1.7783,-1.6101,-1.2852,-0.24628,1.7783,0 +4.688,-1.7778,-1.61,-1.2848,-0.24686,1.7778,0 +4.689,-1.7772,-1.6098,-1.2843,-0.24743,1.7772,0 +4.69,-1.7767,-1.6097,-1.2839,-0.248,1.7767,0 +4.691,-1.7762,-1.6096,-1.2835,-0.24856,1.7762,0 +4.692,-1.7756,-1.6094,-1.283,-0.24912,1.7756,0 +4.693,-1.7751,-1.6093,-1.2826,-0.24967,1.7751,0 +4.694,-1.7745,-1.6092,-1.2822,-0.25022,1.7745,0 +4.695,-1.774,-1.6091,-1.2818,-0.25077,1.774,0 +4.696,-1.7735,-1.6089,-1.2813,-0.25131,1.7735,0 +4.697,-1.7729,-1.6088,-1.2809,-0.25185,1.7729,0 +4.698,-1.7724,-1.6087,-1.2805,-0.25238,1.7724,0 +4.699,-1.7718,-1.6086,-1.2801,-0.25291,1.7718,0 +4.7,-1.7712,-1.6085,-1.2796,-0.25345,1.7712,0 +4.701,-1.7707,-1.6084,-1.2792,-0.25398,1.7707,0 +4.702,-1.7701,-1.6083,-1.2788,-0.25451,1.7701,0 +4.703,-1.7696,-1.6082,-1.2784,-0.25504,1.7696,0 +4.704,-1.769,-1.6081,-1.278,-0.25557,1.769,0 +4.705,-1.7685,-1.608,-1.2775,-0.2561,1.7685,0 +4.706,-1.7679,-1.6078,-1.2771,-0.25663,1.7679,0 +4.707,-1.7674,-1.6077,-1.2767,-0.25716,1.7674,0 +4.708,-1.7668,-1.6076,-1.2763,-0.25769,1.7668,0 +4.709,-1.7663,-1.6075,-1.2759,-0.25822,1.7663,0 +4.71,-1.7657,-1.6074,-1.2754,-0.25875,1.7657,0 +4.711,-1.7652,-1.6073,-1.275,-0.25928,1.7652,0 +4.712,-1.7646,-1.6072,-1.2746,-0.25982,1.7646,0 +4.713,-1.764,-1.6071,-1.2742,-0.26035,1.764,0 +4.714,-1.7635,-1.607,-1.2738,-0.26088,1.7635,0 +4.715,-1.7629,-1.6068,-1.2733,-0.26141,1.7629,0 +4.716,-1.7624,-1.6067,-1.2729,-0.26194,1.7624,0 +4.717,-1.7618,-1.6066,-1.2725,-0.26247,1.7618,0 +4.718,-1.7613,-1.6065,-1.2721,-0.263,1.7613,0 +4.719,-1.7607,-1.6064,-1.2717,-0.26353,1.7607,0 +4.72,-1.7602,-1.6063,-1.2712,-0.26406,1.7602,0 +4.721,-1.7596,-1.6062,-1.2708,-0.26459,1.7596,0 +4.722,-1.7591,-1.6061,-1.2704,-0.26512,1.7591,0 +4.723,-1.7585,-1.606,-1.27,-0.26565,1.7585,0 +4.724,-1.7579,-1.6059,-1.2695,-0.26619,1.7579,0 +4.725,-1.7574,-1.6057,-1.2691,-0.26672,1.7574,0 +4.726,-1.7568,-1.6056,-1.2687,-0.26725,1.7568,0 +4.727,-1.7563,-1.6055,-1.2683,-0.26778,1.7563,0 +4.728,-1.7557,-1.6054,-1.2679,-0.26831,1.7557,0 +4.729,-1.7552,-1.6053,-1.2674,-0.26884,1.7552,0 +4.73,-1.7546,-1.6052,-1.267,-0.26937,1.7546,0 +4.731,-1.7541,-1.6051,-1.2666,-0.2699,1.7541,0 +4.732,-1.7535,-1.605,-1.2662,-0.27043,1.7535,0 +4.733,-1.753,-1.6049,-1.2658,-0.27096,1.753,0 +4.734,-1.7524,-1.6048,-1.2653,-0.27149,1.7524,0 +4.735,-1.7519,-1.6046,-1.2649,-0.27202,1.7519,0 +4.736,-1.7513,-1.6045,-1.2645,-0.27256,1.7513,0 +4.737,-1.7507,-1.6044,-1.2641,-0.27309,1.7507,0 +4.738,-1.7502,-1.6043,-1.2637,-0.27362,1.7502,0 +4.739,-1.7496,-1.6042,-1.2632,-0.27415,1.7496,0 +4.74,-1.7491,-1.6041,-1.2628,-0.27468,1.7491,0 +4.741,-1.7485,-1.604,-1.2624,-0.27521,1.7485,0 +4.742,-1.748,-1.6039,-1.262,-0.27574,1.748,0 +4.743,-1.7474,-1.6038,-1.2616,-0.27627,1.7474,0 +4.744,-1.7469,-1.6037,-1.2611,-0.2768,1.7469,0 +4.745,-1.7463,-1.6035,-1.2607,-0.27733,1.7463,0 +4.746,-1.7458,-1.6034,-1.2603,-0.27786,1.7458,0 +4.747,-1.7452,-1.6033,-1.2599,-0.27839,1.7452,0 +4.748,-1.7447,-1.6032,-1.2595,-0.27893,1.7447,0 +4.749,-1.7441,-1.6031,-1.259,-0.27946,1.7441,0 +4.75,-1.7435,-1.603,-1.2586,-0.27999,1.7435,0 +4.751,-1.743,-1.6029,-1.2582,-0.28052,1.743,0 +4.752,-1.7424,-1.6028,-1.2578,-0.28105,1.7424,0 +4.753,-1.7419,-1.6027,-1.2573,-0.28158,1.7419,0 +4.754,-1.7413,-1.6026,-1.2569,-0.28211,1.7413,0 +4.755,-1.7408,-1.6024,-1.2565,-0.28264,1.7408,0 +4.756,-1.7402,-1.6023,-1.2561,-0.28317,1.7402,0 +4.757,-1.7397,-1.6022,-1.2557,-0.2837,1.7397,0 +4.758,-1.7391,-1.6021,-1.2552,-0.28423,1.7391,0 +4.759,-1.7386,-1.602,-1.2548,-0.28477,1.7386,0 +4.76,-1.738,-1.6019,-1.2544,-0.2853,1.738,0 +4.761,-1.7374,-1.6018,-1.254,-0.28583,1.7374,0 +4.762,-1.7369,-1.6017,-1.2536,-0.28636,1.7369,0 +4.763,-1.7363,-1.6016,-1.2531,-0.28689,1.7363,0 +4.764,-1.7358,-1.6015,-1.2527,-0.28742,1.7358,0 +4.765,-1.7352,-1.6013,-1.2523,-0.28795,1.7352,0 +4.766,-1.7347,-1.6012,-1.2519,-0.28848,1.7347,0 +4.767,-1.7341,-1.6011,-1.2515,-0.28901,1.7341,0 +4.768,-1.7336,-1.601,-1.251,-0.28954,1.7336,0 +4.769,-1.733,-1.6009,-1.2506,-0.29007,1.733,0 +4.77,-1.7325,-1.6008,-1.2502,-0.2906,1.7325,0 +4.771,-1.7319,-1.6007,-1.2498,-0.29114,1.7319,0 +4.772,-1.7314,-1.6006,-1.2494,-0.29166,1.7314,0 +4.773,-1.7308,-1.6005,-1.2489,-0.29219,1.7308,0 +4.774,-1.7302,-1.6004,-1.2485,-0.29271,1.7302,0 +4.775,-1.7297,-1.6003,-1.2481,-0.29323,1.7297,0 +4.776,-1.7291,-1.6002,-1.2477,-0.29374,1.7291,0 +4.777,-1.7285,-1.6001,-1.2473,-0.29425,1.7285,0 +4.778,-1.728,-1.6,-1.2469,-0.29475,1.728,0 +4.779,-1.7274,-1.5999,-1.2465,-0.29525,1.7274,0 +4.78,-1.7268,-1.5998,-1.2461,-0.29574,1.7268,0 +4.781,-1.7262,-1.5997,-1.2457,-0.29624,1.7262,0 +4.782,-1.7256,-1.5996,-1.2453,-0.29672,1.7256,0 +4.783,-1.725,-1.5995,-1.2449,-0.29721,1.725,0 +4.784,-1.7245,-1.5994,-1.2445,-0.2977,1.7245,0 +4.785,-1.7239,-1.5993,-1.2441,-0.29819,1.7239,0 +4.786,-1.7233,-1.5992,-1.2437,-0.29867,1.7233,0 +4.787,-1.7227,-1.5992,-1.2433,-0.29916,1.7227,0 +4.788,-1.7221,-1.5991,-1.2429,-0.29965,1.7221,0 +4.789,-1.7215,-1.599,-1.2425,-0.30014,1.7215,0 +4.79,-1.7209,-1.5989,-1.2421,-0.30062,1.7209,0 +4.791,-1.7204,-1.5988,-1.2417,-0.30111,1.7204,0 +4.792,-1.7198,-1.5987,-1.2413,-0.3016,1.7198,0 +4.793,-1.7192,-1.5986,-1.2409,-0.30209,1.7192,0 +4.794,-1.7186,-1.5985,-1.2405,-0.30258,1.7186,0 +4.795,-1.718,-1.5984,-1.2401,-0.30306,1.718,0 +4.796,-1.7174,-1.5984,-1.2397,-0.30355,1.7174,0 +4.797,-1.7168,-1.5983,-1.2393,-0.30404,1.7168,0 +4.798,-1.7163,-1.5982,-1.2389,-0.30453,1.7163,0 +4.799,-1.7157,-1.5981,-1.2385,-0.30501,1.7157,0 +4.8,-1.7151,-1.598,-1.2381,-0.3055,1.7151,0 +4.801,-1.7145,-1.5979,-1.2377,-0.30599,1.7145,0 +4.802,-1.7139,-1.5978,-1.2373,-0.30648,1.7139,0 +4.803,-1.7133,-1.5977,-1.2369,-0.30696,1.7133,0 +4.804,-1.7127,-1.5977,-1.2365,-0.30745,1.7127,0 +4.805,-1.7121,-1.5976,-1.2361,-0.30794,1.7121,0 +4.806,-1.7116,-1.5975,-1.2357,-0.30843,1.7116,0 +4.807,-1.711,-1.5974,-1.2353,-0.30892,1.711,0 +4.808,-1.7104,-1.5973,-1.2349,-0.3094,1.7104,0 +4.809,-1.7098,-1.5972,-1.2345,-0.30989,1.7098,0 +4.81,-1.7092,-1.5971,-1.2341,-0.31038,1.7092,0 +4.811,-1.7086,-1.597,-1.2337,-0.31087,1.7086,0 +4.812,-1.708,-1.5969,-1.2333,-0.31135,1.708,0 +4.813,-1.7075,-1.5969,-1.2329,-0.31184,1.7075,0 +4.814,-1.7069,-1.5968,-1.2325,-0.31233,1.7069,0 +4.815,-1.7063,-1.5967,-1.2321,-0.31282,1.7063,0 +4.816,-1.7057,-1.5966,-1.2317,-0.3133,1.7057,0 +4.817,-1.7051,-1.5965,-1.2313,-0.31379,1.7051,0 +4.818,-1.7045,-1.5964,-1.2309,-0.31428,1.7045,0 +4.819,-1.7039,-1.5963,-1.2305,-0.31477,1.7039,0 +4.82,-1.7034,-1.5962,-1.2301,-0.31526,1.7034,0 +4.821,-1.7028,-1.5962,-1.2297,-0.31574,1.7028,0 +4.822,-1.7022,-1.5961,-1.2293,-0.31623,1.7022,0 +4.823,-1.7016,-1.596,-1.2289,-0.31672,1.7016,0 +4.824,-1.701,-1.5959,-1.2285,-0.31721,1.701,0 +4.825,-1.7004,-1.5958,-1.2281,-0.31769,1.7004,0 +4.826,-1.6998,-1.5957,-1.2277,-0.31818,1.6998,0 +4.827,-1.6993,-1.5956,-1.2273,-0.31867,1.6993,0 +4.828,-1.6987,-1.5955,-1.2269,-0.31916,1.6987,0 +4.829,-1.6981,-1.5954,-1.2265,-0.31964,1.6981,0 +4.83,-1.6975,-1.5954,-1.2261,-0.32013,1.6975,0 +4.831,-1.6969,-1.5953,-1.2257,-0.32062,1.6969,0 +4.832,-1.6963,-1.5952,-1.2253,-0.32111,1.6963,0 +4.833,-1.6957,-1.5951,-1.2249,-0.3216,1.6957,0 +4.834,-1.6952,-1.595,-1.2245,-0.32208,1.6952,0 +4.835,-1.6946,-1.5949,-1.2241,-0.32257,1.6946,0 +4.836,-1.694,-1.5948,-1.2237,-0.32306,1.694,0 +4.837,-1.6934,-1.5947,-1.2233,-0.32355,1.6934,0 +4.838,-1.6928,-1.5946,-1.2229,-0.32403,1.6928,0 +4.839,-1.6922,-1.5946,-1.2225,-0.32452,1.6922,0 +4.84,-1.6916,-1.5945,-1.2221,-0.32501,1.6916,0 +4.841,-1.6911,-1.5944,-1.2217,-0.3255,1.6911,0 +4.842,-1.6905,-1.5943,-1.2213,-0.32598,1.6905,0 +4.843,-1.6899,-1.5942,-1.2209,-0.32647,1.6899,0 +4.844,-1.6893,-1.5941,-1.2205,-0.32696,1.6893,0 +4.845,-1.6887,-1.594,-1.2201,-0.32745,1.6887,0 +4.846,-1.6881,-1.5939,-1.2197,-0.32794,1.6881,0 +4.847,-1.6875,-1.5939,-1.2193,-0.32842,1.6875,0 +4.848,-1.6869,-1.5938,-1.2189,-0.32891,1.6869,0 +4.849,-1.6864,-1.5937,-1.2185,-0.3294,1.6864,0 +4.85,-1.6858,-1.5936,-1.2181,-0.32989,1.6858,0 +4.851,-1.6852,-1.5935,-1.2177,-0.33037,1.6852,0 +4.852,-1.6846,-1.5934,-1.2173,-0.33086,1.6846,0 +4.853,-1.684,-1.5933,-1.2169,-0.33135,1.684,0 +4.854,-1.6834,-1.5932,-1.2165,-0.33184,1.6834,0 +4.855,-1.6828,-1.5931,-1.2161,-0.33232,1.6828,0 +4.856,-1.6823,-1.5931,-1.2157,-0.33279,1.6823,0 +4.857,-1.6817,-1.593,-1.2154,-0.33324,1.6817,0 +4.858,-1.6811,-1.5929,-1.215,-0.33368,1.6811,0 +4.859,-1.6806,-1.5928,-1.2147,-0.33411,1.6806,0 +4.86,-1.68,-1.5927,-1.2143,-0.33453,1.68,0 +4.861,-1.6795,-1.5927,-1.214,-0.33493,1.6795,0 +4.862,-1.679,-1.5926,-1.2137,-0.33531,1.679,0 +4.863,-1.6784,-1.5925,-1.2134,-0.33569,1.6784,0 +4.864,-1.6779,-1.5924,-1.2131,-0.33605,1.6779,0 +4.865,-1.6774,-1.5924,-1.2128,-0.3364,1.6774,0 +4.866,-1.6769,-1.5923,-1.2125,-0.33675,1.6769,0 +4.867,-1.6763,-1.5922,-1.2122,-0.3371,1.6763,0 +4.868,-1.6758,-1.5922,-1.212,-0.33745,1.6758,0 +4.869,-1.6753,-1.5921,-1.2117,-0.3378,1.6753,0 +4.87,-1.6748,-1.592,-1.2114,-0.33815,1.6748,0 +4.871,-1.6743,-1.592,-1.2111,-0.3385,1.6743,0 +4.872,-1.6737,-1.5919,-1.2108,-0.33885,1.6737,0 +4.873,-1.6732,-1.5918,-1.2106,-0.33921,1.6732,0 +4.874,-1.6727,-1.5918,-1.2103,-0.33956,1.6727,0 +4.875,-1.6722,-1.5917,-1.21,-0.33991,1.6722,0 +4.876,-1.6717,-1.5916,-1.2097,-0.34026,1.6717,0 +4.877,-1.6711,-1.5916,-1.2094,-0.34061,1.6711,0 +4.878,-1.6706,-1.5915,-1.2091,-0.34096,1.6706,0 +4.879,-1.6701,-1.5914,-1.2089,-0.34131,1.6701,0 +4.88,-1.6696,-1.5914,-1.2086,-0.34166,1.6696,0 +4.881,-1.6691,-1.5913,-1.2083,-0.34201,1.6691,0 +4.882,-1.6686,-1.5912,-1.208,-0.34236,1.6686,0 +4.883,-1.668,-1.5912,-1.2077,-0.34272,1.668,0 +4.884,-1.6675,-1.5911,-1.2074,-0.34307,1.6675,0 +4.885,-1.667,-1.591,-1.2072,-0.34342,1.667,0 +4.886,-1.6665,-1.591,-1.2069,-0.34377,1.6665,0 +4.887,-1.666,-1.5909,-1.2066,-0.34412,1.666,0 +4.888,-1.6654,-1.5908,-1.2063,-0.34447,1.6654,0 +4.889,-1.6649,-1.5907,-1.206,-0.34482,1.6649,0 +4.89,-1.6644,-1.5907,-1.2057,-0.34517,1.6644,0 +4.891,-1.6639,-1.5906,-1.2055,-0.34552,1.6639,0 +4.892,-1.6634,-1.5905,-1.2052,-0.34588,1.6634,0 +4.893,-1.6628,-1.5905,-1.2049,-0.34623,1.6628,0 +4.894,-1.6623,-1.5904,-1.2046,-0.34658,1.6623,0 +4.895,-1.6618,-1.5903,-1.2043,-0.34693,1.6618,0 +4.896,-1.6613,-1.5903,-1.204,-0.34728,1.6613,0 +4.897,-1.6608,-1.5902,-1.2038,-0.34763,1.6608,0 +4.898,-1.6602,-1.5901,-1.2035,-0.34798,1.6602,0 +4.899,-1.6597,-1.5901,-1.2032,-0.34833,1.6597,0 +4.9,-1.6592,-1.59,-1.2029,-0.34868,1.6592,0 +4.901,-1.6587,-1.5899,-1.2026,-0.34903,1.6587,0 +4.902,-1.6582,-1.5899,-1.2023,-0.34939,1.6582,0 +4.903,-1.6577,-1.5898,-1.2021,-0.34974,1.6577,0 +4.904,-1.6571,-1.5897,-1.2018,-0.35009,1.6571,0 +4.905,-1.6566,-1.5897,-1.2015,-0.35044,1.6566,0 +4.906,-1.6561,-1.5896,-1.2012,-0.35079,1.6561,0 +4.907,-1.6556,-1.5895,-1.2009,-0.35114,1.6556,0 +4.908,-1.6551,-1.5895,-1.2006,-0.35149,1.6551,0 +4.909,-1.6545,-1.5894,-1.2004,-0.35184,1.6545,0 +4.91,-1.654,-1.5893,-1.2001,-0.35219,1.654,0 +4.911,-1.6535,-1.5892,-1.1998,-0.35254,1.6535,0 +4.912,-1.653,-1.5892,-1.1995,-0.3529,1.653,0 +4.913,-1.6525,-1.5891,-1.1992,-0.35325,1.6525,0 +4.914,-1.6519,-1.589,-1.1989,-0.3536,1.6519,0 +4.915,-1.6514,-1.589,-1.1987,-0.35395,1.6514,0 +4.916,-1.6509,-1.5889,-1.1984,-0.3543,1.6509,0 +4.917,-1.6504,-1.5888,-1.1981,-0.35465,1.6504,0 +4.918,-1.6499,-1.5888,-1.1978,-0.355,1.6499,0 +4.919,-1.6493,-1.5887,-1.1975,-0.35535,1.6493,0 +4.92,-1.6488,-1.5886,-1.1973,-0.3557,1.6488,0 +4.921,-1.6483,-1.5886,-1.197,-0.35605,1.6483,0 +4.922,-1.6478,-1.5885,-1.1967,-0.35641,1.6478,0 +4.923,-1.6473,-1.5884,-1.1964,-0.35676,1.6473,0 +4.924,-1.6468,-1.5884,-1.1961,-0.35711,1.6468,0 +4.925,-1.6462,-1.5883,-1.1958,-0.35746,1.6462,0 +4.926,-1.6457,-1.5882,-1.1956,-0.35781,1.6457,0 +4.927,-1.6452,-1.5882,-1.1953,-0.35816,1.6452,0 +4.928,-1.6447,-1.5881,-1.195,-0.35851,1.6447,0 +4.929,-1.6442,-1.588,-1.1947,-0.35886,1.6442,0 +4.93,-1.6436,-1.588,-1.1944,-0.35921,1.6436,0 +4.931,-1.6431,-1.5879,-1.1941,-0.35957,1.6431,0 +4.932,-1.6426,-1.5878,-1.1939,-0.35992,1.6426,0 +4.933,-1.6421,-1.5878,-1.1936,-0.36027,1.6421,0 +4.934,-1.6416,-1.5877,-1.1933,-0.36062,1.6416,0 +4.935,-1.641,-1.5876,-1.193,-0.36097,1.641,0 +4.936,-1.6405,-1.5875,-1.1927,-0.36132,1.6405,0 +4.937,-1.64,-1.5875,-1.1924,-0.36167,1.64,0 +4.938,-1.6395,-1.5874,-1.1922,-0.36202,1.6395,0 +4.939,-1.639,-1.5873,-1.1919,-0.36237,1.639,0 +4.94,-1.6385,-1.5873,-1.1916,-0.36271,1.6385,0 +4.941,-1.6379,-1.5872,-1.1913,-0.36305,1.6379,0 +4.942,-1.6374,-1.5872,-1.191,-0.36338,1.6374,0 +4.943,-1.6369,-1.5871,-1.1908,-0.36372,1.6369,0 +4.944,-1.6364,-1.587,-1.1905,-0.36404,1.6364,0 +4.945,-1.6359,-1.587,-1.1902,-0.36437,1.6359,0 +4.946,-1.6354,-1.5869,-1.19,-0.36469,1.6354,0 +4.947,-1.6348,-1.5869,-1.1897,-0.36501,1.6348,0 +4.948,-1.6343,-1.5868,-1.1894,-0.36532,1.6343,0 +4.949,-1.6338,-1.5868,-1.1892,-0.36564,1.6338,0 +4.95,-1.6333,-1.5867,-1.1889,-0.36596,1.6333,0 +4.951,-1.6328,-1.5867,-1.1886,-0.36627,1.6328,0 +4.952,-1.6323,-1.5866,-1.1884,-0.36659,1.6323,0 +4.953,-1.6318,-1.5866,-1.1881,-0.3669,1.6318,0 +4.954,-1.6313,-1.5865,-1.1878,-0.36722,1.6313,0 +4.955,-1.6307,-1.5865,-1.1876,-0.36753,1.6307,0 +4.956,-1.6302,-1.5865,-1.1873,-0.36785,1.6302,0 +4.957,-1.6297,-1.5864,-1.187,-0.36817,1.6297,0 +4.958,-1.6292,-1.5864,-1.1868,-0.36848,1.6292,0 +4.959,-1.6287,-1.5863,-1.1865,-0.3688,1.6287,0 +4.96,-1.6282,-1.5863,-1.1862,-0.36911,1.6282,0 +4.961,-1.6277,-1.5862,-1.186,-0.36943,1.6277,0 +4.962,-1.6272,-1.5862,-1.1857,-0.36975,1.6272,0 +4.963,-1.6267,-1.5861,-1.1854,-0.37006,1.6267,0 +4.964,-1.6261,-1.5861,-1.1852,-0.37038,1.6261,0 +4.965,-1.6256,-1.586,-1.1849,-0.37069,1.6256,0 +4.966,-1.6251,-1.586,-1.1846,-0.37101,1.6251,0 +4.967,-1.6246,-1.5859,-1.1844,-0.37132,1.6246,0 +4.968,-1.6241,-1.5859,-1.1841,-0.37164,1.6241,0 +4.969,-1.6236,-1.5858,-1.1838,-0.37196,1.6236,0 +4.97,-1.6231,-1.5858,-1.1836,-0.37227,1.6231,0 +4.971,-1.6226,-1.5857,-1.1833,-0.37259,1.6226,0 +4.972,-1.622,-1.5857,-1.183,-0.3729,1.622,0 +4.973,-1.6215,-1.5856,-1.1828,-0.37322,1.6215,0 +4.974,-1.621,-1.5856,-1.1825,-0.37354,1.621,0 +4.975,-1.6205,-1.5855,-1.1822,-0.37385,1.6205,0 +4.976,-1.62,-1.5855,-1.182,-0.37417,1.62,0 +4.977,-1.6195,-1.5854,-1.1817,-0.37448,1.6195,0 +4.978,-1.619,-1.5854,-1.1814,-0.3748,1.619,0 +4.979,-1.6185,-1.5853,-1.1812,-0.37511,1.6185,0 +4.98,-1.6179,-1.5853,-1.1809,-0.37543,1.6179,0 +4.981,-1.6174,-1.5852,-1.1806,-0.37575,1.6174,0 +4.982,-1.6169,-1.5852,-1.1804,-0.37606,1.6169,0 +4.983,-1.6164,-1.5851,-1.1801,-0.37638,1.6164,0 +4.984,-1.6159,-1.5851,-1.1798,-0.37669,1.6159,0 +4.985,-1.6154,-1.585,-1.1796,-0.37701,1.6154,0 +4.986,-1.6149,-1.585,-1.1793,-0.37733,1.6149,0 +4.987,-1.6144,-1.5849,-1.179,-0.37764,1.6144,0 +4.988,-1.6138,-1.5849,-1.1788,-0.37796,1.6138,0 +4.989,-1.6133,-1.5848,-1.1785,-0.37827,1.6133,0 +4.99,-1.6128,-1.5848,-1.1782,-0.37859,1.6128,0 +4.991,-1.6123,-1.5847,-1.178,-0.3789,1.6123,0 +4.992,-1.6118,-1.5847,-1.1777,-0.37922,1.6118,0 +4.993,-1.6113,-1.5846,-1.1774,-0.37954,1.6113,0 +4.994,-1.6108,-1.5846,-1.1772,-0.37985,1.6108,0 +4.995,-1.6103,-1.5845,-1.1769,-0.38017,1.6103,0 +4.996,-1.6097,-1.5845,-1.1766,-0.38048,1.6097,0 +4.997,-1.6092,-1.5844,-1.1764,-0.3808,1.6092,0 +4.998,-1.6087,-1.5844,-1.1761,-0.38112,1.6087,0 +4.999,-1.6082,-1.5843,-1.1758,-0.38143,1.6082,0 +5,-1.6077,-1.5843,-1.1756,-0.38175,1.6077,0 +5.001,-1.6072,-1.5842,-1.1753,-0.38206,1.6072,0 +5.002,-1.6067,-1.5842,-1.175,-0.38238,1.6067,0 +5.003,-1.6062,-1.5841,-1.1748,-0.38269,1.6062,0 +5.004,-1.6056,-1.5841,-1.1745,-0.38301,1.6056,0 +5.005,-1.6051,-1.584,-1.1742,-0.38333,1.6051,0 +5.006,-1.6046,-1.584,-1.174,-0.38364,1.6046,0 +5.007,-1.6041,-1.5839,-1.1737,-0.38396,1.6041,0 +5.008,-1.6036,-1.5839,-1.1734,-0.38427,1.6036,0 +5.009,-1.6031,-1.5838,-1.1732,-0.38459,1.6031,0 +5.01,-1.6026,-1.5838,-1.1729,-0.38491,1.6026,0 +5.011,-1.6021,-1.5837,-1.1726,-0.38522,1.6021,0 +5.012,-1.6015,-1.5837,-1.1724,-0.38554,1.6015,0 +5.013,-1.601,-1.5836,-1.1721,-0.38585,1.601,0 +5.014,-1.6005,-1.5836,-1.1718,-0.38617,1.6005,0 +5.015,-1.6,-1.5835,-1.1716,-0.38648,1.6,0 +5.016,-1.5995,-1.5835,-1.1713,-0.3868,1.5995,0 +5.017,-1.599,-1.5834,-1.171,-0.38712,1.599,0 +5.018,-1.5985,-1.5834,-1.1708,-0.38743,1.5985,0 +5.019,-1.598,-1.5834,-1.1705,-0.38775,1.598,0 +5.02,-1.5975,-1.5833,-1.1702,-0.38806,1.5975,0 +5.021,-1.5969,-1.5833,-1.17,-0.38837,1.5969,0 +5.022,-1.5964,-1.5832,-1.1697,-0.38867,1.5964,0 +5.023,-1.5959,-1.5831,-1.1695,-0.38896,1.5959,0 +5.024,-1.5953,-1.5831,-1.1693,-0.38923,1.5953,0 +5.025,-1.5948,-1.583,-1.1691,-0.3895,1.5948,0 +5.026,-1.5943,-1.5829,-1.1689,-0.38975,1.5943,0 +5.027,-1.5937,-1.5829,-1.1687,-0.38999,1.5937,0 +5.028,-1.5931,-1.5828,-1.1686,-0.39022,1.5931,0 +5.029,-1.5926,-1.5827,-1.1684,-0.39043,1.5926,0 +5.03,-1.592,-1.5826,-1.1683,-0.39064,1.592,0 +5.031,-1.5914,-1.5826,-1.1682,-0.39084,1.5914,0 +5.032,-1.5908,-1.5825,-1.1681,-0.39103,1.5908,0 +5.033,-1.5903,-1.5824,-1.168,-0.39123,1.5903,0 +5.034,-1.5897,-1.5823,-1.1679,-0.39143,1.5897,0 +5.035,-1.5891,-1.5822,-1.1677,-0.39163,1.5891,0 +5.036,-1.5885,-1.5821,-1.1676,-0.39183,1.5885,0 +5.037,-1.5879,-1.5821,-1.1675,-0.39203,1.5879,0 +5.038,-1.5874,-1.582,-1.1674,-0.39223,1.5874,0 +5.039,-1.5868,-1.5819,-1.1673,-0.39243,1.5868,0 +5.04,-1.5862,-1.5818,-1.1672,-0.39262,1.5862,0 +5.041,-1.5856,-1.5817,-1.167,-0.39282,1.5856,0 +5.042,-1.585,-1.5816,-1.1669,-0.39302,1.585,0 +5.043,-1.5845,-1.5816,-1.1668,-0.39322,1.5845,0 +5.044,-1.5839,-1.5815,-1.1667,-0.39342,1.5839,0 +5.045,-1.5833,-1.5814,-1.1666,-0.39362,1.5833,0 +5.046,-1.5827,-1.5813,-1.1665,-0.39382,1.5827,0 +5.047,-1.5821,-1.5812,-1.1664,-0.39402,1.5821,0 +5.048,-1.5816,-1.5811,-1.1662,-0.39422,1.5816,0 +5.049,-1.581,-1.5811,-1.1661,-0.39441,1.581,0 +5.05,-1.5804,-1.581,-1.166,-0.39461,1.5804,0 +5.051,-1.5798,-1.5809,-1.1659,-0.39481,1.5798,0 +5.052,-1.5792,-1.5808,-1.1658,-0.39501,1.5792,0 +5.053,-1.5787,-1.5807,-1.1657,-0.39521,1.5787,0 +5.054,-1.5781,-1.5806,-1.1655,-0.39541,1.5781,0 +5.055,-1.5775,-1.5806,-1.1654,-0.39561,1.5775,0 +5.056,-1.5769,-1.5805,-1.1653,-0.39581,1.5769,0 +5.057,-1.5764,-1.5804,-1.1652,-0.396,1.5764,0 +5.058,-1.5758,-1.5803,-1.1651,-0.3962,1.5758,0 +5.059,-1.5752,-1.5802,-1.165,-0.3964,1.5752,0 +5.06,-1.5746,-1.5801,-1.1648,-0.3966,1.5746,0 +5.061,-1.574,-1.5801,-1.1647,-0.3968,1.574,0 +5.062,-1.5735,-1.58,-1.1646,-0.397,1.5735,0 +5.063,-1.5729,-1.5799,-1.1645,-0.3972,1.5729,0 +5.064,-1.5723,-1.5798,-1.1644,-0.3974,1.5723,0 +5.065,-1.5717,-1.5797,-1.1643,-0.39759,1.5717,0 +5.066,-1.5711,-1.5796,-1.1642,-0.39779,1.5711,0 +5.067,-1.5706,-1.5796,-1.164,-0.39799,1.5706,0 +5.068,-1.57,-1.5795,-1.1639,-0.39819,1.57,0 +5.069,-1.5694,-1.5794,-1.1638,-0.39839,1.5694,0 +5.07,-1.5688,-1.5793,-1.1637,-0.39859,1.5688,0 +5.071,-1.5682,-1.5792,-1.1636,-0.39879,1.5682,0 +5.072,-1.5677,-1.5791,-1.1635,-0.39899,1.5677,0 +5.073,-1.5671,-1.5791,-1.1633,-0.39918,1.5671,0 +5.074,-1.5665,-1.579,-1.1632,-0.39938,1.5665,0 +5.075,-1.5659,-1.5789,-1.1631,-0.39958,1.5659,0 +5.076,-1.5653,-1.5788,-1.163,-0.39978,1.5653,0 +5.077,-1.5648,-1.5787,-1.1629,-0.39998,1.5648,0 +5.078,-1.5642,-1.5786,-1.1628,-0.40018,1.5642,0 +5.079,-1.5636,-1.5786,-1.1627,-0.40038,1.5636,0 +5.08,-1.563,-1.5785,-1.1625,-0.40058,1.563,0 +5.081,-1.5625,-1.5784,-1.1624,-0.40077,1.5625,0 +5.082,-1.5619,-1.5783,-1.1623,-0.40097,1.5619,0 +5.083,-1.5613,-1.5782,-1.1622,-0.40117,1.5613,0 +5.084,-1.5607,-1.5781,-1.1621,-0.40137,1.5607,0 +5.085,-1.5601,-1.5781,-1.162,-0.40157,1.5601,0 +5.086,-1.5596,-1.578,-1.1618,-0.40177,1.5596,0 +5.087,-1.559,-1.5779,-1.1617,-0.40197,1.559,0 +5.088,-1.5584,-1.5778,-1.1616,-0.40217,1.5584,0 +5.089,-1.5578,-1.5777,-1.1615,-0.40237,1.5578,0 +5.09,-1.5572,-1.5776,-1.1614,-0.40256,1.5572,0 +5.091,-1.5567,-1.5776,-1.1613,-0.40276,1.5567,0 +5.092,-1.5561,-1.5775,-1.1612,-0.40296,1.5561,0 +5.093,-1.5555,-1.5774,-1.161,-0.40316,1.5555,0 +5.094,-1.5549,-1.5773,-1.1609,-0.40336,1.5549,0 +5.095,-1.5543,-1.5772,-1.1608,-0.40356,1.5543,0 +5.096,-1.5538,-1.5771,-1.1607,-0.40376,1.5538,0 +5.097,-1.5532,-1.5771,-1.1606,-0.40396,1.5532,0 +5.098,-1.5526,-1.577,-1.1605,-0.40415,1.5526,0 +5.099,-1.552,-1.5769,-1.1603,-0.40435,1.552,0 +5.1,-1.5514,-1.5768,-1.1602,-0.40455,1.5514,0 +5.101,-1.5509,-1.5767,-1.1601,-0.40475,1.5509,0 +5.102,-1.5503,-1.5766,-1.16,-0.40495,1.5503,0 +5.103,-1.5497,-1.5766,-1.1599,-0.40515,1.5497,0 +5.104,-1.5491,-1.5765,-1.1598,-0.40534,1.5491,0 +5.105,-1.5486,-1.5764,-1.1597,-0.40552,1.5486,0 +5.106,-1.548,-1.5763,-1.1596,-0.40568,1.548,0 +5.107,-1.5474,-1.5762,-1.1595,-0.40583,1.5474,0 +5.108,-1.5469,-1.5761,-1.1595,-0.40597,1.5469,0 +5.109,-1.5463,-1.576,-1.1595,-0.4061,1.5463,0 +5.11,-1.5458,-1.576,-1.1594,-0.40621,1.5458,0 +5.111,-1.5452,-1.5759,-1.1594,-0.40631,1.5452,0 +5.112,-1.5447,-1.5758,-1.1594,-0.4064,1.5447,0 +5.113,-1.5442,-1.5757,-1.1595,-0.40647,1.5442,0 +5.114,-1.5437,-1.5756,-1.1595,-0.40653,1.5437,0 +5.115,-1.5431,-1.5755,-1.1595,-0.4066,1.5431,0 +5.116,-1.5426,-1.5754,-1.1595,-0.40667,1.5426,0 +5.117,-1.5421,-1.5753,-1.1596,-0.40673,1.5421,0 +5.118,-1.5415,-1.5752,-1.1596,-0.4068,1.5415,0 +5.119,-1.541,-1.5751,-1.1596,-0.40687,1.541,0 +5.12,-1.5405,-1.575,-1.1597,-0.40693,1.5405,0 +5.121,-1.54,-1.5749,-1.1597,-0.407,1.54,0 +5.122,-1.5394,-1.5748,-1.1597,-0.40707,1.5394,0 +5.123,-1.5389,-1.5747,-1.1597,-0.40713,1.5389,0 +5.124,-1.5384,-1.5746,-1.1598,-0.4072,1.5384,0 +5.125,-1.5379,-1.5745,-1.1598,-0.40727,1.5379,0 +5.126,-1.5373,-1.5744,-1.1598,-0.40733,1.5373,0 +5.127,-1.5368,-1.5743,-1.1599,-0.4074,1.5368,0 +5.128,-1.5363,-1.5742,-1.1599,-0.40747,1.5363,0 +5.129,-1.5358,-1.5741,-1.1599,-0.40754,1.5358,0 +5.13,-1.5352,-1.574,-1.1599,-0.4076,1.5352,0 +5.131,-1.5347,-1.5739,-1.16,-0.40767,1.5347,0 +5.132,-1.5342,-1.5739,-1.16,-0.40774,1.5342,0 +5.133,-1.5336,-1.5738,-1.16,-0.4078,1.5336,0 +5.134,-1.5331,-1.5737,-1.1601,-0.40787,1.5331,0 +5.135,-1.5326,-1.5736,-1.1601,-0.40794,1.5326,0 +5.136,-1.5321,-1.5735,-1.1601,-0.408,1.5321,0 +5.137,-1.5315,-1.5734,-1.1601,-0.40807,1.5315,0 +5.138,-1.531,-1.5733,-1.1602,-0.40814,1.531,0 +5.139,-1.5305,-1.5732,-1.1602,-0.4082,1.5305,0 +5.14,-1.53,-1.5731,-1.1602,-0.40827,1.53,0 +5.141,-1.5294,-1.573,-1.1603,-0.40834,1.5294,0 +5.142,-1.5289,-1.5729,-1.1603,-0.4084,1.5289,0 +5.143,-1.5284,-1.5728,-1.1603,-0.40847,1.5284,0 +5.144,-1.5278,-1.5727,-1.1604,-0.40854,1.5278,0 +5.145,-1.5273,-1.5726,-1.1604,-0.4086,1.5273,0 +5.146,-1.5268,-1.5725,-1.1604,-0.40867,1.5268,0 +5.147,-1.5263,-1.5724,-1.1604,-0.40874,1.5263,0 +5.148,-1.5257,-1.5723,-1.1605,-0.4088,1.5257,0 +5.149,-1.5252,-1.5722,-1.1605,-0.40887,1.5252,0 +5.15,-1.5247,-1.5721,-1.1605,-0.40894,1.5247,0 +5.151,-1.5242,-1.572,-1.1606,-0.409,1.5242,0 +5.152,-1.5236,-1.5719,-1.1606,-0.40907,1.5236,0 +5.153,-1.5231,-1.5718,-1.1606,-0.40914,1.5231,0 +5.154,-1.5226,-1.5718,-1.1606,-0.4092,1.5226,0 +5.155,-1.5221,-1.5717,-1.1607,-0.40927,1.5221,0 +5.156,-1.5215,-1.5716,-1.1607,-0.40934,1.5215,0 +5.157,-1.521,-1.5715,-1.1607,-0.4094,1.521,0 +5.158,-1.5205,-1.5714,-1.1608,-0.40947,1.5205,0 +5.159,-1.5199,-1.5713,-1.1608,-0.40954,1.5199,0 +5.16,-1.5194,-1.5712,-1.1608,-0.4096,1.5194,0 +5.161,-1.5189,-1.5711,-1.1608,-0.40967,1.5189,0 +5.162,-1.5184,-1.571,-1.1609,-0.40974,1.5184,0 +5.163,-1.5178,-1.5709,-1.1609,-0.4098,1.5178,0 +5.164,-1.5173,-1.5708,-1.1609,-0.40987,1.5173,0 +5.165,-1.5168,-1.5707,-1.161,-0.40994,1.5168,0 +5.166,-1.5163,-1.5706,-1.161,-0.41,1.5163,0 +5.167,-1.5157,-1.5705,-1.161,-0.41007,1.5157,0 +5.168,-1.5152,-1.5704,-1.161,-0.41014,1.5152,0 +5.169,-1.5147,-1.5703,-1.1611,-0.4102,1.5147,0 +5.17,-1.5142,-1.5702,-1.1611,-0.41027,1.5142,0 +5.171,-1.5136,-1.5701,-1.1611,-0.41034,1.5136,0 +5.172,-1.5131,-1.57,-1.1612,-0.4104,1.5131,0 +5.173,-1.5126,-1.5699,-1.1612,-0.41047,1.5126,0 +5.174,-1.512,-1.5698,-1.1612,-0.41054,1.512,0 +5.175,-1.5115,-1.5697,-1.1612,-0.4106,1.5115,0 +5.176,-1.511,-1.5696,-1.1613,-0.41067,1.511,0 +5.177,-1.5105,-1.5696,-1.1613,-0.41074,1.5105,0 +5.178,-1.5099,-1.5695,-1.1613,-0.4108,1.5099,0 +5.179,-1.5094,-1.5694,-1.1614,-0.41087,1.5094,0 +5.18,-1.5089,-1.5693,-1.1614,-0.41094,1.5089,0 +5.181,-1.5084,-1.5692,-1.1614,-0.411,1.5084,0 +5.182,-1.5078,-1.5691,-1.1614,-0.41107,1.5078,0 +5.183,-1.5073,-1.569,-1.1615,-0.41114,1.5073,0 +5.184,-1.5068,-1.5689,-1.1615,-0.4112,1.5068,0 +5.185,-1.5062,-1.5688,-1.1615,-0.41127,1.5062,0 +5.186,-1.5057,-1.5687,-1.1616,-0.41134,1.5057,0 +5.187,-1.5052,-1.5686,-1.1616,-0.4114,1.5052,0 +5.188,-1.5047,-1.5685,-1.1616,-0.41145,1.5047,0 +5.189,-1.5041,-1.5684,-1.1617,-0.4115,1.5041,0 +5.19,-1.5036,-1.5683,-1.1618,-0.41154,1.5036,0 +5.191,-1.5031,-1.5682,-1.1618,-0.41157,1.5031,0 +5.192,-1.5026,-1.5681,-1.1619,-0.41159,1.5026,0 +5.193,-1.5021,-1.568,-1.162,-0.4116,1.5021,0 +5.194,-1.5015,-1.5679,-1.1621,-0.41161,1.5015,0 +5.195,-1.501,-1.5678,-1.1622,-0.41161,1.501,0 +5.196,-1.5005,-1.5677,-1.1623,-0.4116,1.5005,0 +5.197,-1.5,-1.5676,-1.1624,-0.41159,1.5,0 +5.198,-1.4995,-1.5675,-1.1625,-0.41157,1.4995,0 +5.199,-1.499,-1.5674,-1.1626,-0.41156,1.499,0 +5.2,-1.4985,-1.5673,-1.1628,-0.41155,1.4985,0 +5.201,-1.498,-1.5672,-1.1629,-0.41154,1.498,0 +5.202,-1.4974,-1.5671,-1.163,-0.41152,1.4974,0 +5.203,-1.4969,-1.567,-1.1631,-0.41151,1.4969,0 +5.204,-1.4964,-1.5669,-1.1632,-0.4115,1.4964,0 +5.205,-1.4959,-1.5668,-1.1633,-0.41149,1.4959,0 +5.206,-1.4954,-1.5667,-1.1635,-0.41147,1.4954,0 +5.207,-1.4949,-1.5666,-1.1636,-0.41146,1.4949,0 +5.208,-1.4944,-1.5665,-1.1637,-0.41145,1.4944,0 +5.209,-1.4938,-1.5664,-1.1638,-0.41144,1.4938,0 +5.21,-1.4933,-1.5662,-1.1639,-0.41142,1.4933,0 +5.211,-1.4928,-1.5661,-1.164,-0.41141,1.4928,0 +5.212,-1.4923,-1.566,-1.1642,-0.4114,1.4923,0 +5.213,-1.4918,-1.5659,-1.1643,-0.41139,1.4918,0 +5.214,-1.4913,-1.5658,-1.1644,-0.41137,1.4913,0 +5.215,-1.4908,-1.5657,-1.1645,-0.41136,1.4908,0 +5.216,-1.4902,-1.5656,-1.1646,-0.41135,1.4902,0 +5.217,-1.4897,-1.5655,-1.1647,-0.41133,1.4897,0 +5.218,-1.4892,-1.5654,-1.1648,-0.41132,1.4892,0 +5.219,-1.4887,-1.5653,-1.165,-0.41131,1.4887,0 +5.22,-1.4882,-1.5652,-1.1651,-0.4113,1.4882,0 +5.221,-1.4877,-1.5651,-1.1652,-0.41128,1.4877,0 +5.222,-1.4872,-1.565,-1.1653,-0.41127,1.4872,0 +5.223,-1.4866,-1.5649,-1.1654,-0.41126,1.4866,0 +5.224,-1.4861,-1.5648,-1.1655,-0.41125,1.4861,0 +5.225,-1.4856,-1.5647,-1.1657,-0.41123,1.4856,0 +5.226,-1.4851,-1.5646,-1.1658,-0.41122,1.4851,0 +5.227,-1.4846,-1.5645,-1.1659,-0.41121,1.4846,0 +5.228,-1.4841,-1.5644,-1.166,-0.4112,1.4841,0 +5.229,-1.4836,-1.5643,-1.1661,-0.41118,1.4836,0 +5.23,-1.4831,-1.5642,-1.1662,-0.41117,1.4831,0 +5.231,-1.4825,-1.5641,-1.1664,-0.41116,1.4825,0 +5.232,-1.482,-1.564,-1.1665,-0.41115,1.482,0 +5.233,-1.4815,-1.5639,-1.1666,-0.41113,1.4815,0 +5.234,-1.481,-1.5638,-1.1667,-0.41112,1.481,0 +5.235,-1.4805,-1.5637,-1.1668,-0.41111,1.4805,0 +5.236,-1.48,-1.5636,-1.1669,-0.4111,1.48,0 +5.237,-1.4795,-1.5635,-1.1671,-0.41108,1.4795,0 +5.238,-1.4789,-1.5634,-1.1672,-0.41107,1.4789,0 +5.239,-1.4784,-1.5633,-1.1673,-0.41106,1.4784,0 +5.24,-1.4779,-1.5631,-1.1674,-0.41105,1.4779,0 +5.241,-1.4774,-1.563,-1.1675,-0.41103,1.4774,0 +5.242,-1.4769,-1.5629,-1.1676,-0.41102,1.4769,0 +5.243,-1.4764,-1.5628,-1.1677,-0.41101,1.4764,0 +5.244,-1.4759,-1.5627,-1.1679,-0.411,1.4759,0 +5.245,-1.4753,-1.5626,-1.168,-0.41098,1.4753,0 +5.246,-1.4748,-1.5625,-1.1681,-0.41097,1.4748,0 +5.247,-1.4743,-1.5624,-1.1682,-0.41096,1.4743,0 +5.248,-1.4738,-1.5623,-1.1683,-0.41095,1.4738,0 +5.249,-1.4733,-1.5622,-1.1684,-0.41093,1.4733,0 +5.25,-1.4728,-1.5621,-1.1686,-0.41092,1.4728,0 +5.251,-1.4723,-1.562,-1.1687,-0.41091,1.4723,0 +5.252,-1.4717,-1.5619,-1.1688,-0.4109,1.4717,0 +5.253,-1.4712,-1.5618,-1.1689,-0.41088,1.4712,0 +5.254,-1.4707,-1.5617,-1.169,-0.41087,1.4707,0 +5.255,-1.4702,-1.5616,-1.1691,-0.41086,1.4702,0 +5.256,-1.4697,-1.5615,-1.1693,-0.41085,1.4697,0 +5.257,-1.4692,-1.5614,-1.1694,-0.41083,1.4692,0 +5.258,-1.4687,-1.5613,-1.1695,-0.41082,1.4687,0 +5.259,-1.4682,-1.5612,-1.1696,-0.41081,1.4682,0 +5.26,-1.4676,-1.5611,-1.1697,-0.41079,1.4676,0 +5.261,-1.4671,-1.561,-1.1698,-0.41078,1.4671,0 +5.262,-1.4666,-1.5609,-1.17,-0.41077,1.4666,0 +5.263,-1.4661,-1.5608,-1.1701,-0.41076,1.4661,0 +5.264,-1.4656,-1.5607,-1.1702,-0.41074,1.4656,0 +5.265,-1.4651,-1.5606,-1.1703,-0.41073,1.4651,0 +5.266,-1.4646,-1.5605,-1.1704,-0.41072,1.4646,0 +5.267,-1.464,-1.5604,-1.1705,-0.41071,1.464,0 +5.268,-1.4635,-1.5603,-1.1706,-0.41069,1.4635,0 +5.269,-1.463,-1.5601,-1.1708,-0.41068,1.463,0 +5.27,-1.4625,-1.56,-1.1709,-0.41066,1.4625,0 +5.271,-1.462,-1.5599,-1.171,-0.41064,1.462,0 +5.272,-1.4615,-1.5598,-1.1711,-0.41061,1.4615,0 +5.273,-1.4609,-1.5597,-1.1713,-0.41057,1.4609,0 +5.274,-1.4604,-1.5596,-1.1714,-0.41053,1.4604,0 +5.275,-1.4599,-1.5595,-1.1716,-0.41048,1.4599,0 +5.276,-1.4594,-1.5594,-1.1718,-0.41043,1.4594,0 +5.277,-1.4589,-1.5593,-1.1719,-0.41036,1.4589,0 +5.278,-1.4583,-1.5592,-1.1721,-0.41029,1.4583,0 +5.279,-1.4578,-1.5591,-1.1723,-0.41022,1.4578,0 +5.28,-1.4573,-1.559,-1.1725,-0.41014,1.4573,0 +5.281,-1.4568,-1.5589,-1.1727,-0.41006,1.4568,0 +5.282,-1.4562,-1.5587,-1.1729,-0.40998,1.4562,0 +5.283,-1.4557,-1.5586,-1.1731,-0.4099,1.4557,0 +5.284,-1.4552,-1.5585,-1.1732,-0.40983,1.4552,0 +5.285,-1.4547,-1.5584,-1.1734,-0.40975,1.4547,0 +5.286,-1.4541,-1.5583,-1.1736,-0.40967,1.4541,0 +5.287,-1.4536,-1.5582,-1.1738,-0.40959,1.4536,0 +5.288,-1.4531,-1.5581,-1.174,-0.40951,1.4531,0 +5.289,-1.4526,-1.558,-1.1742,-0.40944,1.4526,0 +5.29,-1.4521,-1.5579,-1.1744,-0.40936,1.4521,0 +5.291,-1.4515,-1.5577,-1.1746,-0.40928,1.4515,0 +5.292,-1.451,-1.5576,-1.1748,-0.4092,1.451,0 +5.293,-1.4505,-1.5575,-1.1749,-0.40912,1.4505,0 +5.294,-1.45,-1.5574,-1.1751,-0.40904,1.45,0 +5.295,-1.4494,-1.5573,-1.1753,-0.40897,1.4494,0 +5.296,-1.4489,-1.5572,-1.1755,-0.40889,1.4489,0 +5.297,-1.4484,-1.5571,-1.1757,-0.40881,1.4484,0 +5.298,-1.4479,-1.557,-1.1759,-0.40873,1.4479,0 +5.299,-1.4473,-1.5569,-1.1761,-0.40865,1.4473,0 +5.3,-1.4468,-1.5568,-1.1763,-0.40858,1.4468,0 +5.301,-1.4463,-1.5566,-1.1765,-0.4085,1.4463,0 +5.302,-1.4458,-1.5565,-1.1766,-0.40842,1.4458,0 +5.303,-1.4452,-1.5564,-1.1768,-0.40834,1.4452,0 +5.304,-1.4447,-1.5563,-1.177,-0.40826,1.4447,0 +5.305,-1.4442,-1.5562,-1.1772,-0.40819,1.4442,0 +5.306,-1.4437,-1.5561,-1.1774,-0.40811,1.4437,0 +5.307,-1.4431,-1.556,-1.1776,-0.40803,1.4431,0 +5.308,-1.4426,-1.5559,-1.1778,-0.40795,1.4426,0 +5.309,-1.4421,-1.5558,-1.178,-0.40787,1.4421,0 +5.31,-1.4416,-1.5556,-1.1782,-0.40779,1.4416,0 +5.311,-1.441,-1.5555,-1.1783,-0.40772,1.441,0 +5.312,-1.4405,-1.5554,-1.1785,-0.40764,1.4405,0 +5.313,-1.44,-1.5553,-1.1787,-0.40756,1.44,0 +5.314,-1.4395,-1.5552,-1.1789,-0.40748,1.4395,0 +5.315,-1.4389,-1.5551,-1.1791,-0.4074,1.4389,0 +5.316,-1.4384,-1.555,-1.1793,-0.40733,1.4384,0 +5.317,-1.4379,-1.5549,-1.1795,-0.40725,1.4379,0 +5.318,-1.4374,-1.5548,-1.1797,-0.40717,1.4374,0 +5.319,-1.4368,-1.5546,-1.1799,-0.40709,1.4368,0 +5.32,-1.4363,-1.5545,-1.18,-0.40701,1.4363,0 +5.321,-1.4358,-1.5544,-1.1802,-0.40693,1.4358,0 +5.322,-1.4353,-1.5543,-1.1804,-0.40686,1.4353,0 +5.323,-1.4347,-1.5542,-1.1806,-0.40678,1.4347,0 +5.324,-1.4342,-1.5541,-1.1808,-0.4067,1.4342,0 +5.325,-1.4337,-1.554,-1.181,-0.40662,1.4337,0 +5.326,-1.4332,-1.5539,-1.1812,-0.40654,1.4332,0 +5.327,-1.4326,-1.5538,-1.1814,-0.40647,1.4326,0 +5.328,-1.4321,-1.5536,-1.1816,-0.40639,1.4321,0 +5.329,-1.4316,-1.5535,-1.1817,-0.40631,1.4316,0 +5.33,-1.4311,-1.5534,-1.1819,-0.40623,1.4311,0 +5.331,-1.4305,-1.5533,-1.1821,-0.40615,1.4305,0 +5.332,-1.43,-1.5532,-1.1823,-0.40608,1.43,0 +5.333,-1.4295,-1.5531,-1.1825,-0.406,1.4295,0 +5.334,-1.429,-1.553,-1.1827,-0.40592,1.429,0 +5.335,-1.4284,-1.5529,-1.1829,-0.40584,1.4284,0 +5.336,-1.4279,-1.5528,-1.1831,-0.40576,1.4279,0 +5.337,-1.4274,-1.5527,-1.1833,-0.40568,1.4274,0 +5.338,-1.4269,-1.5525,-1.1834,-0.40561,1.4269,0 +5.339,-1.4264,-1.5524,-1.1836,-0.40553,1.4264,0 +5.34,-1.4258,-1.5523,-1.1838,-0.40545,1.4258,0 +5.341,-1.4253,-1.5522,-1.184,-0.40537,1.4253,0 +5.342,-1.4248,-1.5521,-1.1842,-0.40529,1.4248,0 +5.343,-1.4243,-1.552,-1.1844,-0.40522,1.4243,0 +5.344,-1.4237,-1.5519,-1.1846,-0.40514,1.4237,0 +5.345,-1.4232,-1.5518,-1.1848,-0.40506,1.4232,0 +5.346,-1.4227,-1.5517,-1.185,-0.40498,1.4227,0 +5.347,-1.4222,-1.5515,-1.1851,-0.4049,1.4222,0 +5.348,-1.4216,-1.5514,-1.1853,-0.40482,1.4216,0 +5.349,-1.4211,-1.5513,-1.1855,-0.40475,1.4211,0 +5.35,-1.4206,-1.5512,-1.1857,-0.40467,1.4206,0 +5.351,-1.4201,-1.5511,-1.1859,-0.40459,1.4201,0 +5.352,-1.4195,-1.551,-1.1861,-0.40451,1.4195,0 +5.353,-1.419,-1.5509,-1.1863,-0.40443,1.419,0 +5.354,-1.4185,-1.5508,-1.1865,-0.40434,1.4185,0 +5.355,-1.418,-1.5507,-1.1867,-0.40424,1.418,0 +5.356,-1.4174,-1.5505,-1.1869,-0.40413,1.4174,0 +5.357,-1.4169,-1.5504,-1.1872,-0.40401,1.4169,0 +5.358,-1.4164,-1.5503,-1.1874,-0.40389,1.4164,0 +5.359,-1.4159,-1.5502,-1.1876,-0.40376,1.4159,0 +5.36,-1.4153,-1.5501,-1.1879,-0.40362,1.4153,0 +5.361,-1.4148,-1.55,-1.1882,-0.40348,1.4148,0 +5.362,-1.4143,-1.5498,-1.1884,-0.40332,1.4143,0 +5.363,-1.4138,-1.5497,-1.1887,-0.40317,1.4138,0 +5.364,-1.4132,-1.5496,-1.189,-0.40301,1.4132,0 +5.365,-1.4127,-1.5495,-1.1893,-0.40285,1.4127,0 +5.366,-1.4122,-1.5494,-1.1895,-0.4027,1.4122,0 +5.367,-1.4117,-1.5492,-1.1898,-0.40254,1.4117,0 +5.368,-1.4111,-1.5491,-1.1901,-0.40239,1.4111,0 +5.369,-1.4106,-1.549,-1.1904,-0.40223,1.4106,0 +5.37,-1.4101,-1.5489,-1.1906,-0.40207,1.4101,0 +5.371,-1.4096,-1.5488,-1.1909,-0.40192,1.4096,0 +5.372,-1.409,-1.5486,-1.1912,-0.40176,1.409,0 +5.373,-1.4085,-1.5485,-1.1915,-0.4016,1.4085,0 +5.374,-1.408,-1.5484,-1.1917,-0.40145,1.408,0 +5.375,-1.4075,-1.5483,-1.192,-0.40129,1.4075,0 +5.376,-1.4069,-1.5482,-1.1923,-0.40114,1.4069,0 +5.377,-1.4064,-1.548,-1.1926,-0.40098,1.4064,0 +5.378,-1.4059,-1.5479,-1.1928,-0.40082,1.4059,0 +5.379,-1.4054,-1.5478,-1.1931,-0.40067,1.4054,0 +5.38,-1.4048,-1.5477,-1.1934,-0.40051,1.4048,0 +5.381,-1.4043,-1.5476,-1.1937,-0.40035,1.4043,0 +5.382,-1.4038,-1.5475,-1.1939,-0.4002,1.4038,0 +5.383,-1.4033,-1.5473,-1.1942,-0.40004,1.4033,0 +5.384,-1.4027,-1.5472,-1.1945,-0.39989,1.4027,0 +5.385,-1.4022,-1.5471,-1.1948,-0.39973,1.4022,0 +5.386,-1.4017,-1.547,-1.195,-0.39957,1.4017,0 +5.387,-1.4012,-1.5469,-1.1953,-0.39942,1.4012,0 +5.388,-1.4006,-1.5467,-1.1956,-0.39926,1.4006,0 +5.389,-1.4001,-1.5466,-1.1959,-0.39911,1.4001,0 +5.39,-1.3996,-1.5465,-1.1961,-0.39895,1.3996,0 +5.391,-1.3991,-1.5464,-1.1964,-0.39879,1.3991,0 +5.392,-1.3985,-1.5463,-1.1967,-0.39864,1.3985,0 +5.393,-1.398,-1.5461,-1.197,-0.39848,1.398,0 +5.394,-1.3975,-1.546,-1.1972,-0.39832,1.3975,0 +5.395,-1.397,-1.5459,-1.1975,-0.39817,1.397,0 +5.396,-1.3964,-1.5458,-1.1978,-0.39801,1.3964,0 +5.397,-1.3959,-1.5457,-1.1981,-0.39786,1.3959,0 +5.398,-1.3954,-1.5455,-1.1983,-0.3977,1.3954,0 +5.399,-1.3949,-1.5454,-1.1986,-0.39754,1.3949,0 +5.4,-1.3943,-1.5453,-1.1989,-0.39739,1.3943,0 +5.401,-1.3938,-1.5452,-1.1992,-0.39723,1.3938,0 +5.402,-1.3933,-1.5451,-1.1995,-0.39707,1.3933,0 +5.403,-1.3928,-1.5449,-1.1997,-0.39692,1.3928,0 +5.404,-1.3922,-1.5448,-1.2,-0.39676,1.3922,0 +5.405,-1.3917,-1.5447,-1.2003,-0.39661,1.3917,0 +5.406,-1.3912,-1.5446,-1.2006,-0.39645,1.3912,0 +5.407,-1.3907,-1.5445,-1.2008,-0.39629,1.3907,0 +5.408,-1.3902,-1.5444,-1.2011,-0.39614,1.3902,0 +5.409,-1.3896,-1.5442,-1.2014,-0.39598,1.3896,0 +5.41,-1.3891,-1.5441,-1.2017,-0.39583,1.3891,0 +5.411,-1.3886,-1.544,-1.2019,-0.39567,1.3886,0 +5.412,-1.3881,-1.5439,-1.2022,-0.39551,1.3881,0 +5.413,-1.3875,-1.5438,-1.2025,-0.39536,1.3875,0 +5.414,-1.387,-1.5436,-1.2028,-0.3952,1.387,0 +5.415,-1.3865,-1.5435,-1.203,-0.39504,1.3865,0 +5.416,-1.386,-1.5434,-1.2033,-0.39489,1.386,0 +5.417,-1.3854,-1.5433,-1.2036,-0.39473,1.3854,0 +5.418,-1.3849,-1.5432,-1.2039,-0.39458,1.3849,0 +5.419,-1.3844,-1.543,-1.2041,-0.39442,1.3844,0 +5.42,-1.3839,-1.5429,-1.2044,-0.39426,1.3839,0 +5.421,-1.3833,-1.5428,-1.2047,-0.39411,1.3833,0 +5.422,-1.3828,-1.5427,-1.205,-0.39395,1.3828,0 +5.423,-1.3823,-1.5426,-1.2052,-0.39379,1.3823,0 +5.424,-1.3818,-1.5424,-1.2055,-0.39364,1.3818,0 +5.425,-1.3812,-1.5423,-1.2058,-0.39348,1.3812,0 +5.426,-1.3807,-1.5422,-1.2061,-0.39333,1.3807,0 +5.427,-1.3802,-1.5421,-1.2063,-0.39317,1.3802,0 +5.428,-1.3797,-1.542,-1.2066,-0.39301,1.3797,0 +5.429,-1.3791,-1.5418,-1.2069,-0.39286,1.3791,0 +5.43,-1.3786,-1.5417,-1.2072,-0.3927,1.3786,0 +5.431,-1.3781,-1.5416,-1.2074,-0.39255,1.3781,0 +5.432,-1.3776,-1.5415,-1.2077,-0.39239,1.3776,0 +5.433,-1.377,-1.5414,-1.208,-0.39223,1.377,0 +5.434,-1.3765,-1.5412,-1.2083,-0.39208,1.3765,0 +5.435,-1.376,-1.5411,-1.2085,-0.39192,1.376,0 +5.436,-1.3755,-1.541,-1.2088,-0.39176,1.3755,0 +5.437,-1.3749,-1.5409,-1.2091,-0.39159,1.3749,0 +5.438,-1.3744,-1.5408,-1.2094,-0.39142,1.3744,0 +5.439,-1.3739,-1.5407,-1.2097,-0.39125,1.3739,0 +5.44,-1.3734,-1.5405,-1.21,-0.39107,1.3734,0 +5.441,-1.3729,-1.5404,-1.2103,-0.39088,1.3729,0 +5.442,-1.3723,-1.5403,-1.2106,-0.39069,1.3723,0 +5.443,-1.3718,-1.5402,-1.2109,-0.3905,1.3718,0 +5.444,-1.3713,-1.5401,-1.2112,-0.3903,1.3713,0 +5.445,-1.3708,-1.54,-1.2115,-0.39009,1.3708,0 +5.446,-1.3703,-1.5398,-1.2119,-0.38988,1.3703,0 +5.447,-1.3698,-1.5397,-1.2122,-0.38968,1.3698,0 +5.448,-1.3692,-1.5396,-1.2125,-0.38947,1.3692,0 +5.449,-1.3687,-1.5395,-1.2128,-0.38926,1.3687,0 +5.45,-1.3682,-1.5394,-1.2132,-0.38906,1.3682,0 +5.451,-1.3677,-1.5393,-1.2135,-0.38885,1.3677,0 +5.452,-1.3672,-1.5392,-1.2138,-0.38864,1.3672,0 +5.453,-1.3667,-1.539,-1.2141,-0.38843,1.3667,0 +5.454,-1.3662,-1.5389,-1.2144,-0.38823,1.3662,0 +5.455,-1.3656,-1.5388,-1.2148,-0.38802,1.3656,0 +5.456,-1.3651,-1.5387,-1.2151,-0.38781,1.3651,0 +5.457,-1.3646,-1.5386,-1.2154,-0.38761,1.3646,0 +5.458,-1.3641,-1.5385,-1.2157,-0.3874,1.3641,0 +5.459,-1.3636,-1.5383,-1.2161,-0.38719,1.3636,0 +5.46,-1.3631,-1.5382,-1.2164,-0.38699,1.3631,0 +5.461,-1.3626,-1.5381,-1.2167,-0.38678,1.3626,0 +5.462,-1.362,-1.538,-1.217,-0.38657,1.362,0 +5.463,-1.3615,-1.5379,-1.2173,-0.38636,1.3615,0 +5.464,-1.361,-1.5378,-1.2177,-0.38616,1.361,0 +5.465,-1.3605,-1.5377,-1.218,-0.38595,1.3605,0 +5.466,-1.36,-1.5375,-1.2183,-0.38574,1.36,0 +5.467,-1.3595,-1.5374,-1.2186,-0.38554,1.3595,0 +5.468,-1.359,-1.5373,-1.2189,-0.38533,1.359,0 +5.469,-1.3584,-1.5372,-1.2193,-0.38512,1.3584,0 +5.47,-1.3579,-1.5371,-1.2196,-0.38492,1.3579,0 +5.471,-1.3574,-1.537,-1.2199,-0.38471,1.3574,0 +5.472,-1.3569,-1.5369,-1.2202,-0.3845,1.3569,0 +5.473,-1.3564,-1.5367,-1.2206,-0.38429,1.3564,0 +5.474,-1.3559,-1.5366,-1.2209,-0.38409,1.3559,0 +5.475,-1.3554,-1.5365,-1.2212,-0.38388,1.3554,0 +5.476,-1.3548,-1.5364,-1.2215,-0.38367,1.3548,0 +5.477,-1.3543,-1.5363,-1.2218,-0.38347,1.3543,0 +5.478,-1.3538,-1.5362,-1.2222,-0.38326,1.3538,0 +5.479,-1.3533,-1.536,-1.2225,-0.38305,1.3533,0 +5.48,-1.3528,-1.5359,-1.2228,-0.38285,1.3528,0 +5.481,-1.3523,-1.5358,-1.2231,-0.38264,1.3523,0 +5.482,-1.3518,-1.5357,-1.2235,-0.38243,1.3518,0 +5.483,-1.3512,-1.5356,-1.2238,-0.38223,1.3512,0 +5.484,-1.3507,-1.5355,-1.2241,-0.38202,1.3507,0 +5.485,-1.3502,-1.5354,-1.2244,-0.38181,1.3502,0 +5.486,-1.3497,-1.5352,-1.2247,-0.3816,1.3497,0 +5.487,-1.3492,-1.5351,-1.2251,-0.3814,1.3492,0 +5.488,-1.3487,-1.535,-1.2254,-0.38119,1.3487,0 +5.489,-1.3482,-1.5349,-1.2257,-0.38098,1.3482,0 +5.49,-1.3476,-1.5348,-1.226,-0.38078,1.3476,0 +5.491,-1.3471,-1.5347,-1.2264,-0.38057,1.3471,0 +5.492,-1.3466,-1.5346,-1.2267,-0.38036,1.3466,0 +5.493,-1.3461,-1.5344,-1.227,-0.38016,1.3461,0 +5.494,-1.3456,-1.5343,-1.2273,-0.37995,1.3456,0 +5.495,-1.3451,-1.5342,-1.2276,-0.37974,1.3451,0 +5.496,-1.3446,-1.5341,-1.228,-0.37953,1.3446,0 +5.497,-1.344,-1.534,-1.2283,-0.37933,1.344,0 +5.498,-1.3435,-1.5339,-1.2286,-0.37912,1.3435,0 +5.499,-1.343,-1.5338,-1.2289,-0.37891,1.343,0 +5.5,-1.3425,-1.5336,-1.2293,-0.37871,1.3425,0 +5.501,-1.342,-1.5335,-1.2296,-0.3785,1.342,0 +5.502,-1.3415,-1.5334,-1.2299,-0.37829,1.3415,0 +5.503,-1.341,-1.5333,-1.2302,-0.37809,1.341,0 +5.504,-1.3404,-1.5332,-1.2305,-0.37788,1.3404,0 +5.505,-1.3399,-1.5331,-1.2309,-0.37767,1.3399,0 +5.506,-1.3394,-1.5329,-1.2312,-0.37746,1.3394,0 +5.507,-1.3389,-1.5328,-1.2315,-0.37726,1.3389,0 +5.508,-1.3384,-1.5327,-1.2318,-0.37705,1.3384,0 +5.509,-1.3379,-1.5326,-1.2321,-0.37684,1.3379,0 +5.51,-1.3374,-1.5325,-1.2325,-0.37664,1.3374,0 +5.511,-1.3368,-1.5324,-1.2328,-0.37643,1.3368,0 +5.512,-1.3363,-1.5323,-1.2331,-0.37622,1.3363,0 +5.513,-1.3358,-1.5321,-1.2334,-0.37602,1.3358,0 +5.514,-1.3353,-1.532,-1.2338,-0.37581,1.3353,0 +5.515,-1.3348,-1.5319,-1.2341,-0.3756,1.3348,0 +5.516,-1.3343,-1.5318,-1.2344,-0.3754,1.3343,0 +5.517,-1.3338,-1.5317,-1.2347,-0.37519,1.3338,0 +5.518,-1.3332,-1.5316,-1.235,-0.37498,1.3332,0 +5.519,-1.3327,-1.5315,-1.2354,-0.37477,1.3327,0 +5.52,-1.3322,-1.5313,-1.2357,-0.37455,1.3322,0 +5.521,-1.3317,-1.5312,-1.236,-0.37433,1.3317,0 +5.522,-1.3312,-1.5311,-1.2364,-0.37411,1.3312,0 +5.523,-1.3307,-1.531,-1.2367,-0.37388,1.3307,0 +5.524,-1.3301,-1.5309,-1.2371,-0.37364,1.3301,0 +5.525,-1.3296,-1.5308,-1.2374,-0.3734,1.3296,0 +5.526,-1.3291,-1.5307,-1.2378,-0.37315,1.3291,0 +5.527,-1.3286,-1.5306,-1.2381,-0.3729,1.3286,0 +5.528,-1.328,-1.5304,-1.2385,-0.37264,1.328,0 +5.529,-1.3275,-1.5303,-1.2389,-0.37239,1.3275,0 +5.53,-1.327,-1.5302,-1.2392,-0.37213,1.327,0 +5.531,-1.3264,-1.5301,-1.2396,-0.37187,1.3264,0 +5.532,-1.3259,-1.53,-1.24,-0.37162,1.3259,0 +5.533,-1.3254,-1.5299,-1.2403,-0.37136,1.3254,0 +5.534,-1.3249,-1.5298,-1.2407,-0.3711,1.3249,0 +5.535,-1.3243,-1.5297,-1.2411,-0.37085,1.3243,0 +5.536,-1.3238,-1.5296,-1.2414,-0.37059,1.3238,0 +5.537,-1.3233,-1.5295,-1.2418,-0.37033,1.3233,0 +5.538,-1.3228,-1.5293,-1.2422,-0.37007,1.3228,0 +5.539,-1.3222,-1.5292,-1.2425,-0.36982,1.3222,0 +5.54,-1.3217,-1.5291,-1.2429,-0.36956,1.3217,0 +5.541,-1.3212,-1.529,-1.2433,-0.3693,1.3212,0 +5.542,-1.3206,-1.5289,-1.2436,-0.36905,1.3206,0 +5.543,-1.3201,-1.5288,-1.244,-0.36879,1.3201,0 +5.544,-1.3196,-1.5287,-1.2444,-0.36853,1.3196,0 +5.545,-1.3191,-1.5286,-1.2447,-0.36828,1.3191,0 +5.546,-1.3185,-1.5285,-1.2451,-0.36802,1.3185,0 +5.547,-1.318,-1.5284,-1.2455,-0.36776,1.318,0 +5.548,-1.3175,-1.5283,-1.2458,-0.3675,1.3175,0 +5.549,-1.3169,-1.5281,-1.2462,-0.36725,1.3169,0 +5.55,-1.3164,-1.528,-1.2466,-0.36699,1.3164,0 +5.551,-1.3159,-1.5279,-1.2469,-0.36673,1.3159,0 +5.552,-1.3154,-1.5278,-1.2473,-0.36648,1.3154,0 +5.553,-1.3148,-1.5277,-1.2477,-0.36622,1.3148,0 +5.554,-1.3143,-1.5276,-1.248,-0.36596,1.3143,0 +5.555,-1.3138,-1.5275,-1.2484,-0.36571,1.3138,0 +5.556,-1.3133,-1.5274,-1.2488,-0.36545,1.3133,0 +5.557,-1.3127,-1.5273,-1.2491,-0.36519,1.3127,0 +5.558,-1.3122,-1.5272,-1.2495,-0.36493,1.3122,0 +5.559,-1.3117,-1.527,-1.2499,-0.36468,1.3117,0 +5.56,-1.3111,-1.5269,-1.2502,-0.36442,1.3111,0 +5.561,-1.3106,-1.5268,-1.2506,-0.36416,1.3106,0 +5.562,-1.3101,-1.5267,-1.251,-0.36391,1.3101,0 +5.563,-1.3096,-1.5266,-1.2513,-0.36365,1.3096,0 +5.564,-1.309,-1.5265,-1.2517,-0.36339,1.309,0 +5.565,-1.3085,-1.5264,-1.2521,-0.36314,1.3085,0 +5.566,-1.308,-1.5263,-1.2524,-0.36288,1.308,0 +5.567,-1.3075,-1.5262,-1.2528,-0.36262,1.3075,0 +5.568,-1.3069,-1.5261,-1.2532,-0.36237,1.3069,0 +5.569,-1.3064,-1.526,-1.2535,-0.36211,1.3064,0 +5.57,-1.3059,-1.5258,-1.2539,-0.36185,1.3059,0 +5.571,-1.3053,-1.5257,-1.2543,-0.36159,1.3053,0 +5.572,-1.3048,-1.5256,-1.2546,-0.36134,1.3048,0 +5.573,-1.3043,-1.5255,-1.255,-0.36108,1.3043,0 +5.574,-1.3038,-1.5254,-1.2554,-0.36082,1.3038,0 +5.575,-1.3032,-1.5253,-1.2557,-0.36057,1.3032,0 +5.576,-1.3027,-1.5252,-1.2561,-0.36031,1.3027,0 +5.577,-1.3022,-1.5251,-1.2565,-0.36005,1.3022,0 +5.578,-1.3016,-1.525,-1.2568,-0.3598,1.3016,0 +5.579,-1.3011,-1.5249,-1.2572,-0.35954,1.3011,0 +5.58,-1.3006,-1.5247,-1.2576,-0.35928,1.3006,0 +5.581,-1.3001,-1.5246,-1.2579,-0.35902,1.3001,0 +5.582,-1.2995,-1.5245,-1.2583,-0.35877,1.2995,0 +5.583,-1.299,-1.5244,-1.2587,-0.35851,1.299,0 +5.584,-1.2985,-1.5243,-1.259,-0.35825,1.2985,0 +5.585,-1.298,-1.5242,-1.2594,-0.358,1.298,0 +5.586,-1.2974,-1.5241,-1.2598,-0.35774,1.2974,0 +5.587,-1.2969,-1.524,-1.2601,-0.35748,1.2969,0 +5.588,-1.2964,-1.5239,-1.2605,-0.35723,1.2964,0 +5.589,-1.2958,-1.5238,-1.2609,-0.35697,1.2958,0 +5.59,-1.2953,-1.5237,-1.2612,-0.35671,1.2953,0 +5.591,-1.2948,-1.5235,-1.2616,-0.35645,1.2948,0 +5.592,-1.2943,-1.5234,-1.262,-0.3562,1.2943,0 +5.593,-1.2937,-1.5233,-1.2623,-0.35594,1.2937,0 +5.594,-1.2932,-1.5232,-1.2627,-0.35568,1.2932,0 +5.595,-1.2927,-1.5231,-1.2631,-0.35543,1.2927,0 +5.596,-1.2921,-1.523,-1.2634,-0.35517,1.2921,0 +5.597,-1.2916,-1.5229,-1.2638,-0.35491,1.2916,0 +5.598,-1.2911,-1.5228,-1.2642,-0.35466,1.2911,0 +5.599,-1.2906,-1.5227,-1.2645,-0.3544,1.2906,0 +5.6,-1.29,-1.5226,-1.2649,-0.35414,1.29,0 +5.601,-1.2895,-1.5224,-1.2653,-0.35388,1.2895,0 +5.602,-1.289,-1.5223,-1.2656,-0.35362,1.289,0 +5.603,-1.2884,-1.5222,-1.266,-0.35335,1.2884,0 +5.604,-1.2879,-1.5221,-1.2664,-0.35307,1.2879,0 +5.605,-1.2874,-1.522,-1.2668,-0.35278,1.2874,0 +5.606,-1.2868,-1.5219,-1.2672,-0.35249,1.2868,0 +5.607,-1.2863,-1.5218,-1.2676,-0.35219,1.2863,0 +5.608,-1.2857,-1.5217,-1.268,-0.35188,1.2857,0 +5.609,-1.2852,-1.5216,-1.2684,-0.35157,1.2852,0 +5.61,-1.2846,-1.5215,-1.2689,-0.35124,1.2846,0 +5.611,-1.2841,-1.5214,-1.2693,-0.35091,1.2841,0 +5.612,-1.2835,-1.5213,-1.2698,-0.35058,1.2835,0 +5.613,-1.283,-1.5212,-1.2702,-0.35025,1.283,0 +5.614,-1.2824,-1.5211,-1.2706,-0.34991,1.2824,0 +5.615,-1.2819,-1.5209,-1.2711,-0.34958,1.2819,0 +5.616,-1.2813,-1.5208,-1.2715,-0.34925,1.2813,0 +5.617,-1.2808,-1.5207,-1.2719,-0.34892,1.2808,0 +5.618,-1.2802,-1.5206,-1.2724,-0.34859,1.2802,0 +5.619,-1.2796,-1.5205,-1.2728,-0.34826,1.2796,0 +5.62,-1.2791,-1.5204,-1.2733,-0.34792,1.2791,0 +5.621,-1.2785,-1.5203,-1.2737,-0.34759,1.2785,0 +5.622,-1.278,-1.5202,-1.2741,-0.34726,1.278,0 +5.623,-1.2774,-1.5201,-1.2746,-0.34693,1.2774,0 +5.624,-1.2769,-1.52,-1.275,-0.3466,1.2769,0 +5.625,-1.2763,-1.5199,-1.2754,-0.34626,1.2763,0 +5.626,-1.2758,-1.5198,-1.2759,-0.34593,1.2758,0 +5.627,-1.2752,-1.5197,-1.2763,-0.3456,1.2752,0 +5.628,-1.2746,-1.5196,-1.2768,-0.34527,1.2746,0 +5.629,-1.2741,-1.5195,-1.2772,-0.34494,1.2741,0 +5.63,-1.2735,-1.5193,-1.2776,-0.34461,1.2735,0 +5.631,-1.273,-1.5192,-1.2781,-0.34427,1.273,0 +5.632,-1.2724,-1.5191,-1.2785,-0.34394,1.2724,0 +5.633,-1.2719,-1.519,-1.279,-0.34361,1.2719,0 +5.634,-1.2713,-1.5189,-1.2794,-0.34328,1.2713,0 +5.635,-1.2708,-1.5188,-1.2798,-0.34295,1.2708,0 +5.636,-1.2702,-1.5187,-1.2803,-0.34261,1.2702,0 +5.637,-1.2697,-1.5186,-1.2807,-0.34228,1.2697,0 +5.638,-1.2691,-1.5185,-1.2811,-0.34195,1.2691,0 +5.639,-1.2685,-1.5184,-1.2816,-0.34162,1.2685,0 +5.64,-1.268,-1.5183,-1.282,-0.34129,1.268,0 +5.641,-1.2674,-1.5182,-1.2825,-0.34096,1.2674,0 +5.642,-1.2669,-1.5181,-1.2829,-0.34062,1.2669,0 +5.643,-1.2663,-1.518,-1.2833,-0.34029,1.2663,0 +5.644,-1.2658,-1.5179,-1.2838,-0.33996,1.2658,0 +5.645,-1.2652,-1.5178,-1.2842,-0.33963,1.2652,0 +5.646,-1.2647,-1.5176,-1.2846,-0.3393,1.2647,0 +5.647,-1.2641,-1.5175,-1.2851,-0.33896,1.2641,0 +5.648,-1.2635,-1.5174,-1.2855,-0.33863,1.2635,0 +5.649,-1.263,-1.5173,-1.286,-0.3383,1.263,0 +5.65,-1.2624,-1.5172,-1.2864,-0.33797,1.2624,0 +5.651,-1.2619,-1.5171,-1.2868,-0.33764,1.2619,0 +5.652,-1.2613,-1.517,-1.2873,-0.33731,1.2613,0 +5.653,-1.2608,-1.5169,-1.2877,-0.33697,1.2608,0 +5.654,-1.2602,-1.5168,-1.2882,-0.33664,1.2602,0 +5.655,-1.2597,-1.5167,-1.2886,-0.33631,1.2597,0 +5.656,-1.2591,-1.5166,-1.289,-0.33598,1.2591,0 +5.657,-1.2586,-1.5165,-1.2895,-0.33565,1.2586,0 +5.658,-1.258,-1.5164,-1.2899,-0.33531,1.258,0 +5.659,-1.2574,-1.5163,-1.2903,-0.33498,1.2574,0 +5.66,-1.2569,-1.5162,-1.2908,-0.33465,1.2569,0 +5.661,-1.2563,-1.5161,-1.2912,-0.33432,1.2563,0 +5.662,-1.2558,-1.5159,-1.2917,-0.33399,1.2558,0 +5.663,-1.2552,-1.5158,-1.2921,-0.33366,1.2552,0 +5.664,-1.2547,-1.5157,-1.2925,-0.33332,1.2547,0 +5.665,-1.2541,-1.5156,-1.293,-0.33299,1.2541,0 +5.666,-1.2536,-1.5155,-1.2934,-0.33266,1.2536,0 +5.667,-1.253,-1.5154,-1.2938,-0.33233,1.253,0 +5.668,-1.2524,-1.5153,-1.2943,-0.332,1.2524,0 +5.669,-1.2519,-1.5152,-1.2947,-0.33166,1.2519,0 +5.67,-1.2513,-1.5151,-1.2952,-0.33133,1.2513,0 +5.671,-1.2508,-1.515,-1.2956,-0.331,1.2508,0 +5.672,-1.2502,-1.5149,-1.296,-0.33067,1.2502,0 +5.673,-1.2497,-1.5148,-1.2965,-0.33034,1.2497,0 +5.674,-1.2491,-1.5147,-1.2969,-0.33001,1.2491,0 +5.675,-1.2486,-1.5146,-1.2974,-0.32967,1.2486,0 +5.676,-1.248,-1.5145,-1.2978,-0.32934,1.248,0 +5.677,-1.2474,-1.5144,-1.2982,-0.32901,1.2474,0 +5.678,-1.2469,-1.5142,-1.2987,-0.32868,1.2469,0 +5.679,-1.2463,-1.5141,-1.2991,-0.32835,1.2463,0 +5.68,-1.2458,-1.514,-1.2995,-0.32801,1.2458,0 +5.681,-1.2452,-1.5139,-1.3,-0.32768,1.2452,0 +5.682,-1.2447,-1.5138,-1.3004,-0.32735,1.2447,0 +5.683,-1.2441,-1.5137,-1.3009,-0.32702,1.2441,0 +5.684,-1.2436,-1.5136,-1.3013,-0.32669,1.2436,0 +5.685,-1.243,-1.5135,-1.3017,-0.32635,1.243,0 +5.686,-1.2425,-1.5134,-1.3022,-0.32601,1.2425,0 +5.687,-1.2419,-1.5133,-1.3026,-0.32566,1.2419,0 +5.688,-1.2414,-1.5132,-1.3031,-0.32531,1.2414,0 +5.689,-1.2408,-1.5131,-1.3035,-0.32496,1.2408,0 +5.69,-1.2403,-1.513,-1.304,-0.3246,1.2403,0 +5.691,-1.2398,-1.5129,-1.3045,-0.32423,1.2398,0 +5.692,-1.2393,-1.5128,-1.3049,-0.32386,1.2393,0 +5.693,-1.2388,-1.5127,-1.3054,-0.32348,1.2388,0 +5.694,-1.2382,-1.5126,-1.3059,-0.3231,1.2382,0 +5.695,-1.2377,-1.5125,-1.3063,-0.32272,1.2377,0 +5.696,-1.2372,-1.5125,-1.3068,-0.32234,1.2372,0 +5.697,-1.2367,-1.5124,-1.3073,-0.32196,1.2367,0 +5.698,-1.2362,-1.5123,-1.3077,-0.32158,1.2362,0 +5.699,-1.2357,-1.5122,-1.3082,-0.3212,1.2357,0 +5.7,-1.2352,-1.5121,-1.3087,-0.32082,1.2352,0 +5.701,-1.2346,-1.512,-1.3091,-0.32044,1.2346,0 +5.702,-1.2341,-1.5119,-1.3096,-0.32006,1.2341,0 +5.703,-1.2336,-1.5118,-1.3101,-0.31968,1.2336,0 +5.704,-1.2331,-1.5117,-1.3106,-0.3193,1.2331,0 +5.705,-1.2326,-1.5116,-1.311,-0.31892,1.2326,0 +5.706,-1.2321,-1.5116,-1.3115,-0.31854,1.2321,0 +5.707,-1.2316,-1.5115,-1.312,-0.31816,1.2316,0 +5.708,-1.2311,-1.5114,-1.3124,-0.31778,1.2311,0 +5.709,-1.2305,-1.5113,-1.3129,-0.3174,1.2305,0 +5.71,-1.23,-1.5112,-1.3134,-0.31702,1.23,0 +5.711,-1.2295,-1.5111,-1.3139,-0.31664,1.2295,0 +5.712,-1.229,-1.511,-1.3143,-0.31626,1.229,0 +5.713,-1.2285,-1.5109,-1.3148,-0.31588,1.2285,0 +5.714,-1.228,-1.5108,-1.3153,-0.3155,1.228,0 +5.715,-1.2275,-1.5107,-1.3157,-0.31512,1.2275,0 +5.716,-1.2269,-1.5107,-1.3162,-0.31474,1.2269,0 +5.717,-1.2264,-1.5106,-1.3167,-0.31436,1.2264,0 +5.718,-1.2259,-1.5105,-1.3171,-0.31398,1.2259,0 +5.719,-1.2254,-1.5104,-1.3176,-0.3136,1.2254,0 +5.72,-1.2249,-1.5103,-1.3181,-0.31322,1.2249,0 +5.721,-1.2244,-1.5102,-1.3186,-0.31284,1.2244,0 +5.722,-1.2239,-1.5101,-1.319,-0.31246,1.2239,0 +5.723,-1.2234,-1.51,-1.3195,-0.31208,1.2234,0 +5.724,-1.2228,-1.5099,-1.32,-0.3117,1.2228,0 +5.725,-1.2223,-1.5098,-1.3204,-0.31132,1.2223,0 +5.726,-1.2218,-1.5098,-1.3209,-0.31094,1.2218,0 +5.727,-1.2213,-1.5097,-1.3214,-0.31056,1.2213,0 +5.728,-1.2208,-1.5096,-1.3218,-0.31018,1.2208,0 +5.729,-1.2203,-1.5095,-1.3223,-0.3098,1.2203,0 +5.73,-1.2198,-1.5094,-1.3228,-0.30942,1.2198,0 +5.731,-1.2192,-1.5093,-1.3233,-0.30904,1.2192,0 +5.732,-1.2187,-1.5092,-1.3237,-0.30866,1.2187,0 +5.733,-1.2182,-1.5091,-1.3242,-0.30828,1.2182,0 +5.734,-1.2177,-1.509,-1.3247,-0.30789,1.2177,0 +5.735,-1.2172,-1.5089,-1.3251,-0.30751,1.2172,0 +5.736,-1.2167,-1.5089,-1.3256,-0.30713,1.2167,0 +5.737,-1.2162,-1.5088,-1.3261,-0.30675,1.2162,0 +5.738,-1.2157,-1.5087,-1.3265,-0.30637,1.2157,0 +5.739,-1.2151,-1.5086,-1.327,-0.30599,1.2151,0 +5.74,-1.2146,-1.5085,-1.3275,-0.30561,1.2146,0 +5.741,-1.2141,-1.5084,-1.328,-0.30523,1.2141,0 +5.742,-1.2136,-1.5083,-1.3284,-0.30485,1.2136,0 +5.743,-1.2131,-1.5082,-1.3289,-0.30447,1.2131,0 +5.744,-1.2126,-1.5081,-1.3294,-0.30409,1.2126,0 +5.745,-1.2121,-1.508,-1.3298,-0.30371,1.2121,0 +5.746,-1.2116,-1.5079,-1.3303,-0.30333,1.2116,0 +5.747,-1.211,-1.5079,-1.3308,-0.30295,1.211,0 +5.748,-1.2105,-1.5078,-1.3313,-0.30257,1.2105,0 +5.749,-1.21,-1.5077,-1.3317,-0.30219,1.21,0 +5.75,-1.2095,-1.5076,-1.3322,-0.30181,1.2095,0 +5.751,-1.209,-1.5075,-1.3327,-0.30143,1.209,0 +5.752,-1.2085,-1.5074,-1.3331,-0.30105,1.2085,0 +5.753,-1.208,-1.5073,-1.3336,-0.30067,1.208,0 +5.754,-1.2074,-1.5072,-1.3341,-0.30029,1.2074,0 +5.755,-1.2069,-1.5071,-1.3345,-0.29991,1.2069,0 +5.756,-1.2064,-1.507,-1.335,-0.29953,1.2064,0 +5.757,-1.2059,-1.507,-1.3355,-0.29915,1.2059,0 +5.758,-1.2054,-1.5069,-1.336,-0.29877,1.2054,0 +5.759,-1.2049,-1.5068,-1.3364,-0.29839,1.2049,0 +5.76,-1.2044,-1.5067,-1.3369,-0.29801,1.2044,0 +5.761,-1.2039,-1.5066,-1.3374,-0.29763,1.2039,0 +5.762,-1.2033,-1.5065,-1.3378,-0.29725,1.2033,0 +5.763,-1.2028,-1.5064,-1.3383,-0.29687,1.2028,0 +5.764,-1.2023,-1.5063,-1.3388,-0.29649,1.2023,0 +5.765,-1.2018,-1.5062,-1.3392,-0.29611,1.2018,0 +5.766,-1.2013,-1.5061,-1.3397,-0.29573,1.2013,0 +5.767,-1.2008,-1.5061,-1.3402,-0.29535,1.2008,0 +5.768,-1.2003,-1.506,-1.3407,-0.29496,1.2003,0 +5.769,-1.1997,-1.5059,-1.3411,-0.29458,1.1997,0 +5.77,-1.1992,-1.5058,-1.3416,-0.29418,1.1992,0 +5.771,-1.1987,-1.5057,-1.3421,-0.29379,1.1987,0 +5.772,-1.1982,-1.5056,-1.3426,-0.29339,1.1982,0 +5.773,-1.1977,-1.5056,-1.343,-0.29299,1.1977,0 +5.774,-1.1972,-1.5055,-1.3435,-0.29259,1.1972,0 +5.775,-1.1967,-1.5054,-1.344,-0.29218,1.1967,0 +5.776,-1.1962,-1.5054,-1.3445,-0.29176,1.1962,0 +5.777,-1.1956,-1.5053,-1.345,-0.29135,1.1956,0 +5.778,-1.1951,-1.5052,-1.3454,-0.29093,1.1951,0 +5.779,-1.1946,-1.5052,-1.3459,-0.29052,1.1946,0 +5.78,-1.1941,-1.5051,-1.3464,-0.2901,1.1941,0 +5.781,-1.1936,-1.505,-1.3469,-0.28968,1.1936,0 +5.782,-1.1931,-1.505,-1.3474,-0.28927,1.1931,0 +5.783,-1.1926,-1.5049,-1.3479,-0.28885,1.1926,0 +5.784,-1.1921,-1.5048,-1.3483,-0.28844,1.1921,0 +5.785,-1.1916,-1.5048,-1.3488,-0.28802,1.1916,0 +5.786,-1.191,-1.5047,-1.3493,-0.28761,1.191,0 +5.787,-1.1905,-1.5046,-1.3498,-0.28719,1.1905,0 +5.788,-1.19,-1.5046,-1.3503,-0.28677,1.19,0 +5.789,-1.1895,-1.5045,-1.3507,-0.28636,1.1895,0 +5.79,-1.189,-1.5044,-1.3512,-0.28594,1.189,0 +5.791,-1.1885,-1.5044,-1.3517,-0.28553,1.1885,0 +5.792,-1.188,-1.5043,-1.3522,-0.28511,1.188,0 +5.793,-1.1875,-1.5042,-1.3527,-0.28469,1.1875,0 +5.794,-1.187,-1.5042,-1.3532,-0.28428,1.187,0 +5.795,-1.1864,-1.5041,-1.3536,-0.28386,1.1864,0 +5.796,-1.1859,-1.504,-1.3541,-0.28345,1.1859,0 +5.797,-1.1854,-1.504,-1.3546,-0.28303,1.1854,0 +5.798,-1.1849,-1.5039,-1.3551,-0.28262,1.1849,0 +5.799,-1.1844,-1.5038,-1.3556,-0.2822,1.1844,0 +5.8,-1.1839,-1.5038,-1.3561,-0.28178,1.1839,0 +5.801,-1.1834,-1.5037,-1.3565,-0.28137,1.1834,0 +5.802,-1.1829,-1.5036,-1.357,-0.28095,1.1829,0 +5.803,-1.1824,-1.5036,-1.3575,-0.28054,1.1824,0 +5.804,-1.1818,-1.5035,-1.358,-0.28012,1.1818,0 +5.805,-1.1813,-1.5034,-1.3585,-0.2797,1.1813,0 +5.806,-1.1808,-1.5034,-1.359,-0.27929,1.1808,0 +5.807,-1.1803,-1.5033,-1.3594,-0.27887,1.1803,0 +5.808,-1.1798,-1.5032,-1.3599,-0.27846,1.1798,0 +5.809,-1.1793,-1.5032,-1.3604,-0.27804,1.1793,0 +5.81,-1.1788,-1.5031,-1.3609,-0.27763,1.1788,0 +5.811,-1.1783,-1.503,-1.3614,-0.27721,1.1783,0 +5.812,-1.1777,-1.503,-1.3618,-0.27679,1.1777,0 +5.813,-1.1772,-1.5029,-1.3623,-0.27638,1.1772,0 +5.814,-1.1767,-1.5028,-1.3628,-0.27596,1.1767,0 +5.815,-1.1762,-1.5028,-1.3633,-0.27555,1.1762,0 +5.816,-1.1757,-1.5027,-1.3638,-0.27513,1.1757,0 +5.817,-1.1752,-1.5026,-1.3643,-0.27471,1.1752,0 +5.818,-1.1747,-1.5026,-1.3647,-0.2743,1.1747,0 +5.819,-1.1742,-1.5025,-1.3652,-0.27388,1.1742,0 +5.82,-1.1737,-1.5024,-1.3657,-0.27347,1.1737,0 +5.821,-1.1731,-1.5024,-1.3662,-0.27305,1.1731,0 +5.822,-1.1726,-1.5023,-1.3667,-0.27264,1.1726,0 +5.823,-1.1721,-1.5022,-1.3672,-0.27222,1.1721,0 +5.824,-1.1716,-1.5022,-1.3676,-0.2718,1.1716,0 +5.825,-1.1711,-1.5021,-1.3681,-0.27139,1.1711,0 +5.826,-1.1706,-1.502,-1.3686,-0.27097,1.1706,0 +5.827,-1.1701,-1.502,-1.3691,-0.27056,1.1701,0 +5.828,-1.1696,-1.5019,-1.3696,-0.27014,1.1696,0 +5.829,-1.1691,-1.5018,-1.37,-0.26972,1.1691,0 +5.83,-1.1685,-1.5018,-1.3705,-0.26931,1.1685,0 +5.831,-1.168,-1.5017,-1.371,-0.26889,1.168,0 +5.832,-1.1675,-1.5016,-1.3715,-0.26848,1.1675,0 +5.833,-1.167,-1.5016,-1.372,-0.26806,1.167,0 +5.834,-1.1665,-1.5015,-1.3725,-0.26765,1.1665,0 +5.835,-1.166,-1.5014,-1.3729,-0.26723,1.166,0 +5.836,-1.1655,-1.5014,-1.3734,-0.26681,1.1655,0 +5.837,-1.165,-1.5013,-1.3739,-0.2664,1.165,0 +5.838,-1.1645,-1.5012,-1.3744,-0.26598,1.1645,0 +5.839,-1.1639,-1.5012,-1.3749,-0.26557,1.1639,0 +5.84,-1.1634,-1.5011,-1.3754,-0.26515,1.1634,0 +5.841,-1.1629,-1.501,-1.3758,-0.26473,1.1629,0 +5.842,-1.1624,-1.501,-1.3763,-0.26432,1.1624,0 +5.843,-1.1619,-1.5009,-1.3768,-0.2639,1.1619,0 +5.844,-1.1614,-1.5008,-1.3773,-0.26349,1.1614,0 +5.845,-1.1609,-1.5008,-1.3778,-0.26307,1.1609,0 +5.846,-1.1604,-1.5007,-1.3783,-0.26266,1.1604,0 +5.847,-1.1598,-1.5006,-1.3787,-0.26224,1.1598,0 +5.848,-1.1593,-1.5006,-1.3792,-0.26182,1.1593,0 +5.849,-1.1588,-1.5005,-1.3797,-0.26141,1.1588,0 +5.85,-1.1583,-1.5004,-1.3802,-0.26099,1.1583,0 +5.851,-1.1578,-1.5004,-1.3807,-0.26057,1.1578,0 +5.852,-1.1573,-1.5003,-1.3812,-0.26013,1.1573,0 +5.853,-1.1568,-1.5002,-1.3817,-0.25969,1.1568,0 +5.854,-1.1563,-1.5002,-1.3822,-0.25924,1.1563,0 +5.855,-1.1558,-1.5001,-1.3827,-0.25878,1.1558,0 +5.856,-1.1553,-1.5001,-1.3832,-0.25831,1.1553,0 +5.857,-1.1548,-1.5,-1.3838,-0.25784,1.1548,0 +5.858,-1.1543,-1.4999,-1.3843,-0.25735,1.1543,0 +5.859,-1.1538,-1.4999,-1.3848,-0.25686,1.1538,0 +5.86,-1.1533,-1.4998,-1.3854,-0.25636,1.1533,0 +5.861,-1.1528,-1.4998,-1.3859,-0.25586,1.1528,0 +5.862,-1.1523,-1.4997,-1.3865,-0.25536,1.1523,0 +5.863,-1.1518,-1.4997,-1.387,-0.25485,1.1518,0 +5.864,-1.1513,-1.4996,-1.3876,-0.25435,1.1513,0 +5.865,-1.1508,-1.4996,-1.3881,-0.25385,1.1508,0 +5.866,-1.1503,-1.4995,-1.3887,-0.25335,1.1503,0 +5.867,-1.1498,-1.4995,-1.3892,-0.25285,1.1498,0 +5.868,-1.1493,-1.4994,-1.3898,-0.25235,1.1493,0 +5.869,-1.1488,-1.4994,-1.3904,-0.25185,1.1488,0 +5.87,-1.1483,-1.4993,-1.3909,-0.25135,1.1483,0 +5.871,-1.1478,-1.4993,-1.3915,-0.25085,1.1478,0 +5.872,-1.1473,-1.4992,-1.392,-0.25034,1.1473,0 +5.873,-1.1468,-1.4992,-1.3926,-0.24984,1.1468,0 +5.874,-1.1463,-1.4991,-1.3931,-0.24934,1.1463,0 +5.875,-1.1458,-1.4991,-1.3937,-0.24884,1.1458,0 +5.876,-1.1453,-1.499,-1.3942,-0.24834,1.1453,0 +5.877,-1.1448,-1.499,-1.3948,-0.24784,1.1448,0 +5.878,-1.1443,-1.4989,-1.3953,-0.24734,1.1443,0 +5.879,-1.1438,-1.4989,-1.3959,-0.24684,1.1438,0 +5.88,-1.1433,-1.4988,-1.3964,-0.24634,1.1433,0 +5.881,-1.1428,-1.4988,-1.397,-0.24584,1.1428,0 +5.882,-1.1423,-1.4987,-1.3975,-0.24533,1.1423,0 +5.883,-1.1418,-1.4987,-1.3981,-0.24483,1.1418,0 +5.884,-1.1413,-1.4986,-1.3986,-0.24433,1.1413,0 +5.885,-1.1408,-1.4986,-1.3992,-0.24383,1.1408,0 +5.886,-1.1403,-1.4985,-1.3997,-0.24333,1.1403,0 +5.887,-1.1398,-1.4985,-1.4003,-0.24283,1.1398,0 +5.888,-1.1393,-1.4984,-1.4008,-0.24233,1.1393,0 +5.889,-1.1388,-1.4984,-1.4014,-0.24183,1.1388,0 +5.89,-1.1383,-1.4983,-1.4019,-0.24133,1.1383,0 +5.891,-1.1378,-1.4983,-1.4025,-0.24082,1.1378,0 +5.892,-1.1373,-1.4982,-1.403,-0.24032,1.1373,0 +5.893,-1.1368,-1.4982,-1.4036,-0.23982,1.1368,0 +5.894,-1.1363,-1.4981,-1.4041,-0.23932,1.1363,0 +5.895,-1.1358,-1.4981,-1.4047,-0.23882,1.1358,0 +5.896,-1.1353,-1.498,-1.4052,-0.23832,1.1353,0 +5.897,-1.1348,-1.498,-1.4058,-0.23782,1.1348,0 +5.898,-1.1343,-1.4979,-1.4063,-0.23732,1.1343,0 +5.899,-1.1338,-1.4979,-1.4069,-0.23682,1.1338,0 +5.9,-1.1333,-1.4978,-1.4074,-0.23632,1.1333,0 +5.901,-1.1328,-1.4978,-1.408,-0.23581,1.1328,0 +5.902,-1.1323,-1.4977,-1.4085,-0.23531,1.1323,0 +5.903,-1.1318,-1.4977,-1.4091,-0.23481,1.1318,0 +5.904,-1.1313,-1.4976,-1.4096,-0.23431,1.1313,0 +5.905,-1.1308,-1.4976,-1.4102,-0.23381,1.1308,0 +5.906,-1.1303,-1.4975,-1.4108,-0.23331,1.1303,0 +5.907,-1.1298,-1.4975,-1.4113,-0.23281,1.1298,0 +5.908,-1.1293,-1.4974,-1.4119,-0.23231,1.1293,0 +5.909,-1.1288,-1.4974,-1.4124,-0.23181,1.1288,0 +5.91,-1.1283,-1.4973,-1.413,-0.2313,1.1283,0 +5.911,-1.1278,-1.4973,-1.4135,-0.2308,1.1278,0 +5.912,-1.1273,-1.4972,-1.4141,-0.2303,1.1273,0 +5.913,-1.1268,-1.4972,-1.4146,-0.2298,1.1268,0 +5.914,-1.1263,-1.4971,-1.4152,-0.2293,1.1263,0 +5.915,-1.1258,-1.4971,-1.4157,-0.2288,1.1258,0 +5.916,-1.1253,-1.497,-1.4163,-0.2283,1.1253,0 +5.917,-1.1248,-1.497,-1.4168,-0.2278,1.1248,0 +5.918,-1.1243,-1.4969,-1.4174,-0.2273,1.1243,0 +5.919,-1.1238,-1.4969,-1.4179,-0.2268,1.1238,0 +5.92,-1.1233,-1.4968,-1.4185,-0.22629,1.1233,0 +5.921,-1.1228,-1.4968,-1.419,-0.22579,1.1228,0 +5.922,-1.1223,-1.4967,-1.4196,-0.22529,1.1223,0 +5.923,-1.1218,-1.4967,-1.4201,-0.22479,1.1218,0 +5.924,-1.1213,-1.4966,-1.4207,-0.22429,1.1213,0 +5.925,-1.1208,-1.4966,-1.4212,-0.22379,1.1208,0 +5.926,-1.1203,-1.4965,-1.4218,-0.22329,1.1203,0 +5.927,-1.1198,-1.4965,-1.4223,-0.22279,1.1198,0 +5.928,-1.1193,-1.4964,-1.4229,-0.22229,1.1193,0 +5.929,-1.1188,-1.4964,-1.4234,-0.22179,1.1188,0 +5.93,-1.1183,-1.4963,-1.424,-0.22128,1.1183,0 +5.931,-1.1178,-1.4963,-1.4245,-0.22078,1.1178,0 +5.932,-1.1173,-1.4962,-1.4251,-0.22028,1.1173,0 +5.933,-1.1168,-1.4962,-1.4256,-0.21978,1.1168,0 +5.934,-1.1163,-1.4961,-1.4262,-0.21928,1.1163,0 +5.935,-1.1158,-1.4961,-1.4267,-0.21878,1.1158,0 +5.936,-1.1153,-1.496,-1.4273,-0.21829,1.1153,0 +5.937,-1.1149,-1.496,-1.4278,-0.21779,1.1149,0 +5.938,-1.1144,-1.496,-1.4283,-0.2173,1.1144,0 +5.939,-1.114,-1.4959,-1.4289,-0.21681,1.114,0 +5.94,-1.1135,-1.4959,-1.4294,-0.21632,1.1135,0 +5.941,-1.1131,-1.4959,-1.4299,-0.21583,1.1131,0 +5.942,-1.1127,-1.4959,-1.4304,-0.21534,1.1127,0 +5.943,-1.1123,-1.4958,-1.4309,-0.21485,1.1123,0 +5.944,-1.1118,-1.4958,-1.4314,-0.21437,1.1118,0 +5.945,-1.1114,-1.4958,-1.4319,-0.21388,1.1114,0 +5.946,-1.111,-1.4958,-1.4324,-0.21339,1.111,0 +5.947,-1.1106,-1.4957,-1.4329,-0.21291,1.1106,0 +5.948,-1.1102,-1.4957,-1.4334,-0.21242,1.1102,0 +5.949,-1.1098,-1.4957,-1.4339,-0.21194,1.1098,0 +5.95,-1.1093,-1.4957,-1.4345,-0.21145,1.1093,0 +5.951,-1.1089,-1.4957,-1.435,-0.21096,1.1089,0 +5.952,-1.1085,-1.4956,-1.4355,-0.21048,1.1085,0 +5.953,-1.1081,-1.4956,-1.436,-0.20999,1.1081,0 +5.954,-1.1077,-1.4956,-1.4365,-0.2095,1.1077,0 +5.955,-1.1072,-1.4956,-1.437,-0.20902,1.1072,0 +5.956,-1.1068,-1.4956,-1.4375,-0.20853,1.1068,0 +5.957,-1.1064,-1.4955,-1.438,-0.20805,1.1064,0 +5.958,-1.106,-1.4955,-1.4385,-0.20756,1.106,0 +5.959,-1.1056,-1.4955,-1.439,-0.20707,1.1056,0 +5.96,-1.1052,-1.4955,-1.4395,-0.20659,1.1052,0 +5.961,-1.1047,-1.4955,-1.44,-0.2061,1.1047,0 +5.962,-1.1043,-1.4954,-1.4405,-0.20561,1.1043,0 +5.963,-1.1039,-1.4954,-1.4411,-0.20513,1.1039,0 +5.964,-1.1035,-1.4954,-1.4416,-0.20464,1.1035,0 +5.965,-1.1031,-1.4954,-1.4421,-0.20416,1.1031,0 +5.966,-1.1027,-1.4953,-1.4426,-0.20367,1.1027,0 +5.967,-1.1022,-1.4953,-1.4431,-0.20318,1.1022,0 +5.968,-1.1018,-1.4953,-1.4436,-0.2027,1.1018,0 +5.969,-1.1014,-1.4953,-1.4441,-0.20221,1.1014,0 +5.97,-1.101,-1.4953,-1.4446,-0.20172,1.101,0 +5.971,-1.1006,-1.4952,-1.4451,-0.20124,1.1006,0 +5.972,-1.1001,-1.4952,-1.4456,-0.20075,1.1001,0 +5.973,-1.0997,-1.4952,-1.4461,-0.20027,1.0997,0 +5.974,-1.0993,-1.4952,-1.4466,-0.19978,1.0993,0 +5.975,-1.0989,-1.4952,-1.4471,-0.19929,1.0989,0 +5.976,-1.0985,-1.4951,-1.4476,-0.19881,1.0985,0 +5.977,-1.0981,-1.4951,-1.4482,-0.19832,1.0981,0 +5.978,-1.0976,-1.4951,-1.4487,-0.19783,1.0976,0 +5.979,-1.0972,-1.4951,-1.4492,-0.19735,1.0972,0 +5.98,-1.0968,-1.4951,-1.4497,-0.19686,1.0968,0 +5.981,-1.0964,-1.495,-1.4502,-0.19638,1.0964,0 +5.982,-1.096,-1.495,-1.4507,-0.19589,1.096,0 +5.983,-1.0956,-1.495,-1.4512,-0.1954,1.0956,0 +5.984,-1.0951,-1.495,-1.4517,-0.19492,1.0951,0 +5.985,-1.0947,-1.4949,-1.4522,-0.19443,1.0947,0 +5.986,-1.0943,-1.4949,-1.4527,-0.19394,1.0943,0 +5.987,-1.0939,-1.4949,-1.4532,-0.19346,1.0939,0 +5.988,-1.0935,-1.4949,-1.4537,-0.19297,1.0935,0 +5.989,-1.093,-1.4949,-1.4542,-0.19249,1.093,0 +5.99,-1.0926,-1.4948,-1.4548,-0.192,1.0926,0 +5.991,-1.0922,-1.4948,-1.4553,-0.19151,1.0922,0 +5.992,-1.0918,-1.4948,-1.4558,-0.19103,1.0918,0 +5.993,-1.0914,-1.4948,-1.4563,-0.19054,1.0914,0 +5.994,-1.091,-1.4948,-1.4568,-0.19005,1.091,0 +5.995,-1.0905,-1.4947,-1.4573,-0.18957,1.0905,0 +5.996,-1.0901,-1.4947,-1.4578,-0.18908,1.0901,0 +5.997,-1.0897,-1.4947,-1.4583,-0.1886,1.0897,0 +5.998,-1.0893,-1.4947,-1.4588,-0.18811,1.0893,0 +5.999,-1.0889,-1.4947,-1.4593,-0.18762,1.0889,0 +6,-1.0885,-1.4946,-1.4598,-0.18714,1.0885,0 +6.001,-1.088,-1.4946,-1.4603,-0.18665,1.088,0 +6.002,-1.0876,-1.4946,-1.4608,-0.18616,1.0876,0 +6.003,-1.0872,-1.4946,-1.4613,-0.18568,1.0872,0 +6.004,-1.0868,-1.4945,-1.4619,-0.18519,1.0868,0 +6.005,-1.0864,-1.4945,-1.4624,-0.18471,1.0864,0 +6.006,-1.0859,-1.4945,-1.4629,-0.18422,1.0859,0 +6.007,-1.0855,-1.4945,-1.4634,-0.18373,1.0855,0 +6.008,-1.0851,-1.4945,-1.4639,-0.18325,1.0851,0 +6.009,-1.0847,-1.4944,-1.4644,-0.18276,1.0847,0 +6.01,-1.0843,-1.4944,-1.4649,-0.18227,1.0843,0 +6.011,-1.0839,-1.4944,-1.4654,-0.18179,1.0839,0 +6.012,-1.0834,-1.4944,-1.4659,-0.1813,1.0834,0 +6.013,-1.083,-1.4944,-1.4664,-0.18082,1.083,0 +6.014,-1.0826,-1.4943,-1.4669,-0.18033,1.0826,0 +6.015,-1.0822,-1.4943,-1.4674,-0.17984,1.0822,0 +6.016,-1.0818,-1.4943,-1.4679,-0.17936,1.0818,0 +6.017,-1.0814,-1.4943,-1.4684,-0.17887,1.0814,0 +6.018,-1.081,-1.4943,-1.4689,-0.17838,1.081,0 +6.019,-1.0806,-1.4942,-1.4694,-0.1779,1.0806,0 +6.02,-1.0802,-1.4942,-1.4699,-0.17741,1.0802,0 +6.021,-1.0798,-1.4942,-1.4704,-0.17693,1.0798,0 +6.022,-1.0794,-1.4942,-1.4709,-0.17644,1.0794,0 +6.023,-1.079,-1.4942,-1.4714,-0.17596,1.079,0 +6.024,-1.0786,-1.4942,-1.4719,-0.17547,1.0786,0 +6.025,-1.0783,-1.4942,-1.4724,-0.17499,1.0783,0 +6.026,-1.0779,-1.4942,-1.4729,-0.1745,1.0779,0 +6.027,-1.0775,-1.4942,-1.4734,-0.17402,1.0775,0 +6.028,-1.0772,-1.4942,-1.4738,-0.17353,1.0772,0 +6.029,-1.0768,-1.4942,-1.4743,-0.17305,1.0768,0 +6.03,-1.0765,-1.4942,-1.4748,-0.17256,1.0765,0 +6.031,-1.0761,-1.4942,-1.4753,-0.17208,1.0761,0 +6.032,-1.0757,-1.4942,-1.4758,-0.1716,1.0757,0 +6.033,-1.0754,-1.4942,-1.4763,-0.17111,1.0754,0 +6.034,-1.075,-1.4942,-1.4767,-0.17063,1.075,0 +6.035,-1.0746,-1.4942,-1.4772,-0.17014,1.0746,0 +6.036,-1.0743,-1.4942,-1.4777,-0.16966,1.0743,0 +6.037,-1.0739,-1.4942,-1.4782,-0.16917,1.0739,0 +6.038,-1.0736,-1.4942,-1.4787,-0.16869,1.0736,0 +6.039,-1.0732,-1.4942,-1.4792,-0.1682,1.0732,0 +6.04,-1.0728,-1.4942,-1.4796,-0.16772,1.0728,0 +6.041,-1.0725,-1.4942,-1.4801,-0.16723,1.0725,0 +6.042,-1.0721,-1.4942,-1.4806,-0.16675,1.0721,0 +6.043,-1.0717,-1.4942,-1.4811,-0.16626,1.0717,0 +6.044,-1.0714,-1.4942,-1.4816,-0.16578,1.0714,0 +6.045,-1.071,-1.4943,-1.482,-0.16529,1.071,0 +6.046,-1.0707,-1.4943,-1.4825,-0.16481,1.0707,0 +6.047,-1.0703,-1.4943,-1.483,-0.16433,1.0703,0 +6.048,-1.0699,-1.4943,-1.4835,-0.16384,1.0699,0 +6.049,-1.0696,-1.4943,-1.484,-0.16336,1.0696,0 +6.05,-1.0692,-1.4943,-1.4845,-0.16287,1.0692,0 +6.051,-1.0688,-1.4943,-1.4849,-0.16239,1.0688,0 +6.052,-1.0685,-1.4943,-1.4854,-0.1619,1.0685,0 +6.053,-1.0681,-1.4943,-1.4859,-0.16142,1.0681,0 +6.054,-1.0678,-1.4943,-1.4864,-0.16093,1.0678,0 +6.055,-1.0674,-1.4943,-1.4869,-0.16045,1.0674,0 +6.056,-1.067,-1.4943,-1.4874,-0.15996,1.067,0 +6.057,-1.0667,-1.4943,-1.4878,-0.15948,1.0667,0 +6.058,-1.0663,-1.4943,-1.4883,-0.15899,1.0663,0 +6.059,-1.0659,-1.4943,-1.4888,-0.15851,1.0659,0 +6.06,-1.0656,-1.4943,-1.4893,-0.15802,1.0656,0 +6.061,-1.0652,-1.4943,-1.4898,-0.15754,1.0652,0 +6.062,-1.0649,-1.4943,-1.4903,-0.15706,1.0649,0 +6.063,-1.0645,-1.4943,-1.4907,-0.15657,1.0645,0 +6.064,-1.0641,-1.4943,-1.4912,-0.15609,1.0641,0 +6.065,-1.0638,-1.4943,-1.4917,-0.1556,1.0638,0 +6.066,-1.0634,-1.4943,-1.4922,-0.15512,1.0634,0 +6.067,-1.063,-1.4943,-1.4927,-0.15463,1.063,0 +6.068,-1.0627,-1.4943,-1.4931,-0.15415,1.0627,0 +6.069,-1.0623,-1.4943,-1.4936,-0.15366,1.0623,0 +6.07,-1.062,-1.4943,-1.4941,-0.15318,1.062,0 +6.071,-1.0616,-1.4943,-1.4946,-0.15269,1.0616,0 +6.072,-1.0612,-1.4943,-1.4951,-0.15221,1.0612,0 +6.073,-1.0609,-1.4943,-1.4956,-0.15172,1.0609,0 +6.074,-1.0605,-1.4943,-1.496,-0.15124,1.0605,0 +6.075,-1.0601,-1.4943,-1.4965,-0.15075,1.0601,0 +6.076,-1.0598,-1.4943,-1.497,-0.15027,1.0598,0 +6.077,-1.0594,-1.4943,-1.4975,-0.14979,1.0594,0 +6.078,-1.0591,-1.4943,-1.498,-0.1493,1.0591,0 +6.079,-1.0587,-1.4943,-1.4985,-0.14882,1.0587,0 +6.08,-1.0583,-1.4943,-1.4989,-0.14833,1.0583,0 +6.081,-1.058,-1.4943,-1.4994,-0.14785,1.058,0 +6.082,-1.0576,-1.4943,-1.4999,-0.14736,1.0576,0 +6.083,-1.0572,-1.4943,-1.5004,-0.14688,1.0572,0 +6.084,-1.0569,-1.4943,-1.5009,-0.14639,1.0569,0 +6.085,-1.0565,-1.4943,-1.5014,-0.14591,1.0565,0 +6.086,-1.0562,-1.4943,-1.5018,-0.14542,1.0562,0 +6.087,-1.0558,-1.4943,-1.5023,-0.14494,1.0558,0 +6.088,-1.0554,-1.4943,-1.5028,-0.14445,1.0554,0 +6.089,-1.0551,-1.4943,-1.5033,-0.14397,1.0551,0 +6.09,-1.0547,-1.4943,-1.5038,-0.14348,1.0547,0 +6.091,-1.0543,-1.4943,-1.5042,-0.143,1.0543,0 +6.092,-1.054,-1.4943,-1.5047,-0.14252,1.054,0 +6.093,-1.0536,-1.4943,-1.5052,-0.14203,1.0536,0 +6.094,-1.0533,-1.4944,-1.5057,-0.14155,1.0533,0 +6.095,-1.0529,-1.4944,-1.5062,-0.14106,1.0529,0 +6.096,-1.0525,-1.4944,-1.5067,-0.14058,1.0525,0 +6.097,-1.0522,-1.4944,-1.5071,-0.14009,1.0522,0 +6.098,-1.0518,-1.4944,-1.5076,-0.13961,1.0518,0 +6.099,-1.0515,-1.4944,-1.5081,-0.13912,1.0515,0 +6.1,-1.0511,-1.4944,-1.5086,-0.13863,1.0511,0 +6.101,-1.0507,-1.4944,-1.5091,-0.13814,1.0507,0 +6.102,-1.0504,-1.4944,-1.5096,-0.13764,1.0504,0 +6.103,-1.0501,-1.4944,-1.5101,-0.13713,1.0501,0 +6.104,-1.0497,-1.4944,-1.5106,-0.13662,1.0497,0 +6.105,-1.0494,-1.4944,-1.5111,-0.13611,1.0494,0 +6.106,-1.0491,-1.4944,-1.5116,-0.13559,1.0491,0 +6.107,-1.0488,-1.4944,-1.5121,-0.13506,1.0488,0 +6.108,-1.0485,-1.4944,-1.5126,-0.13453,1.0485,0 +6.109,-1.0482,-1.4945,-1.5131,-0.134,1.0482,0 +6.11,-1.0479,-1.4945,-1.5137,-0.13347,1.0479,0 +6.111,-1.0476,-1.4945,-1.5142,-0.13294,1.0476,0 +6.112,-1.0473,-1.4945,-1.5147,-0.13241,1.0473,0 +6.113,-1.047,-1.4945,-1.5152,-0.13187,1.047,0 +6.114,-1.0467,-1.4945,-1.5157,-0.13134,1.0467,0 +6.115,-1.0464,-1.4945,-1.5162,-0.13081,1.0464,0 +6.116,-1.0461,-1.4946,-1.5168,-0.13028,1.0461,0 +6.117,-1.0458,-1.4946,-1.5173,-0.12974,1.0458,0 +6.118,-1.0454,-1.4946,-1.5178,-0.12921,1.0454,0 +6.119,-1.0451,-1.4946,-1.5183,-0.12868,1.0451,0 +6.12,-1.0448,-1.4946,-1.5188,-0.12815,1.0448,0 +6.121,-1.0445,-1.4946,-1.5194,-0.12761,1.0445,0 +6.122,-1.0442,-1.4946,-1.5199,-0.12708,1.0442,0 +6.123,-1.0439,-1.4947,-1.5204,-0.12655,1.0439,0 +6.124,-1.0436,-1.4947,-1.5209,-0.12602,1.0436,0 +6.125,-1.0433,-1.4947,-1.5214,-0.12549,1.0433,0 +6.126,-1.043,-1.4947,-1.5219,-0.12495,1.043,0 +6.127,-1.0427,-1.4947,-1.5225,-0.12442,1.0427,0 +6.128,-1.0424,-1.4947,-1.523,-0.12389,1.0424,0 +6.129,-1.0421,-1.4947,-1.5235,-0.12336,1.0421,0 +6.13,-1.0418,-1.4948,-1.524,-0.12282,1.0418,0 +6.131,-1.0415,-1.4948,-1.5245,-0.12229,1.0415,0 +6.132,-1.0412,-1.4948,-1.5251,-0.12176,1.0412,0 +6.133,-1.0409,-1.4948,-1.5256,-0.12123,1.0409,0 +6.134,-1.0406,-1.4948,-1.5261,-0.1207,1.0406,0 +6.135,-1.0403,-1.4948,-1.5266,-0.12016,1.0403,0 +6.136,-1.04,-1.4948,-1.5271,-0.11963,1.04,0 +6.137,-1.0397,-1.4949,-1.5276,-0.1191,1.0397,0 +6.138,-1.0394,-1.4949,-1.5282,-0.11857,1.0394,0 +6.139,-1.0391,-1.4949,-1.5287,-0.11803,1.0391,0 +6.14,-1.0388,-1.4949,-1.5292,-0.1175,1.0388,0 +6.141,-1.0385,-1.4949,-1.5297,-0.11697,1.0385,0 +6.142,-1.0382,-1.4949,-1.5302,-0.11644,1.0382,0 +6.143,-1.0379,-1.4949,-1.5307,-0.1159,1.0379,0 +6.144,-1.0376,-1.495,-1.5313,-0.11537,1.0376,0 +6.145,-1.0373,-1.495,-1.5318,-0.11484,1.0373,0 +6.146,-1.037,-1.495,-1.5323,-0.11431,1.037,0 +6.147,-1.0367,-1.495,-1.5328,-0.11378,1.0367,0 +6.148,-1.0364,-1.495,-1.5333,-0.11324,1.0364,0 +6.149,-1.0361,-1.495,-1.5339,-0.11271,1.0361,0 +6.15,-1.0358,-1.495,-1.5344,-0.11218,1.0358,0 +6.151,-1.0355,-1.4951,-1.5349,-0.11165,1.0355,0 +6.152,-1.0352,-1.4951,-1.5354,-0.11111,1.0352,0 +6.153,-1.0349,-1.4951,-1.5359,-0.11058,1.0349,0 +6.154,-1.0346,-1.4951,-1.5364,-0.11005,1.0346,0 +6.155,-1.0343,-1.4951,-1.537,-0.10952,1.0343,0 +6.156,-1.034,-1.4951,-1.5375,-0.10898,1.034,0 +6.157,-1.0336,-1.4951,-1.538,-0.10845,1.0336,0 +6.158,-1.0333,-1.4952,-1.5385,-0.10792,1.0333,0 +6.159,-1.033,-1.4952,-1.539,-0.10739,1.033,0 +6.16,-1.0327,-1.4952,-1.5396,-0.10686,1.0327,0 +6.161,-1.0324,-1.4952,-1.5401,-0.10632,1.0324,0 +6.162,-1.0321,-1.4952,-1.5406,-0.10579,1.0321,0 +6.163,-1.0318,-1.4952,-1.5411,-0.10526,1.0318,0 +6.164,-1.0315,-1.4952,-1.5416,-0.10473,1.0315,0 +6.165,-1.0312,-1.4953,-1.5421,-0.10419,1.0312,0 +6.166,-1.0309,-1.4953,-1.5427,-0.10366,1.0309,0 +6.167,-1.0306,-1.4953,-1.5432,-0.10313,1.0306,0 +6.168,-1.0303,-1.4953,-1.5437,-0.1026,1.0303,0 +6.169,-1.03,-1.4953,-1.5442,-0.10207,1.03,0 +6.17,-1.0297,-1.4953,-1.5447,-0.10153,1.0297,0 +6.171,-1.0294,-1.4953,-1.5453,-0.101,1.0294,0 +6.172,-1.0291,-1.4954,-1.5458,-0.10047,1.0291,0 +6.173,-1.0288,-1.4954,-1.5463,-0.099936,1.0288,0 +6.174,-1.0285,-1.4954,-1.5468,-0.099404,1.0285,0 +6.175,-1.0282,-1.4954,-1.5473,-0.098872,1.0282,0 +6.176,-1.0279,-1.4954,-1.5478,-0.098339,1.0279,0 +6.177,-1.0276,-1.4954,-1.5484,-0.097807,1.0276,0 +6.178,-1.0273,-1.4954,-1.5489,-0.097275,1.0273,0 +6.179,-1.027,-1.4955,-1.5494,-0.096742,1.027,0 +6.18,-1.0267,-1.4955,-1.5499,-0.09621,1.0267,0 +6.181,-1.0264,-1.4955,-1.5504,-0.095678,1.0264,0 +6.182,-1.0261,-1.4955,-1.551,-0.095146,1.0261,0 +6.183,-1.0258,-1.4955,-1.5515,-0.094615,1.0258,0 +6.184,-1.0255,-1.4955,-1.552,-0.094086,1.0255,0 +6.185,-1.0252,-1.4956,-1.5525,-0.093558,1.0252,0 +6.186,-1.0249,-1.4956,-1.553,-0.093031,1.0249,0 +6.187,-1.0246,-1.4956,-1.5535,-0.092506,1.0246,0 +6.188,-1.0244,-1.4956,-1.554,-0.091982,1.0244,0 +6.189,-1.0241,-1.4957,-1.5545,-0.091459,1.0241,0 +6.19,-1.0238,-1.4957,-1.555,-0.090937,1.0238,0 +6.191,-1.0236,-1.4957,-1.5555,-0.090417,1.0236,0 +6.192,-1.0233,-1.4958,-1.5559,-0.089898,1.0233,0 +6.193,-1.023,-1.4958,-1.5564,-0.089378,1.023,0 +6.194,-1.0228,-1.4958,-1.5569,-0.088859,1.0228,0 +6.195,-1.0225,-1.4959,-1.5574,-0.088339,1.0225,0 +6.196,-1.0223,-1.4959,-1.5579,-0.08782,1.0223,0 +6.197,-1.022,-1.4959,-1.5584,-0.087301,1.022,0 +6.198,-1.0217,-1.496,-1.5588,-0.086781,1.0217,0 +6.199,-1.0215,-1.496,-1.5593,-0.086262,1.0215,0 +6.2,-1.0212,-1.496,-1.5598,-0.085742,1.0212,0 +6.201,-1.021,-1.4961,-1.5603,-0.085223,1.021,0 +6.202,-1.0207,-1.4961,-1.5608,-0.084704,1.0207,0 +6.203,-1.0204,-1.4961,-1.5613,-0.084184,1.0204,0 +6.204,-1.0202,-1.4962,-1.5618,-0.083665,1.0202,0 +6.205,-1.0199,-1.4962,-1.5622,-0.083145,1.0199,0 +6.206,-1.0197,-1.4962,-1.5627,-0.082626,1.0197,0 +6.207,-1.0194,-1.4963,-1.5632,-0.082107,1.0194,0 +6.208,-1.0191,-1.4963,-1.5637,-0.081587,1.0191,0 +6.209,-1.0189,-1.4964,-1.5642,-0.081068,1.0189,0 +6.21,-1.0186,-1.4964,-1.5647,-0.080548,1.0186,0 +6.211,-1.0184,-1.4964,-1.5651,-0.080029,1.0184,0 +6.212,-1.0181,-1.4965,-1.5656,-0.07951,1.0181,0 +6.213,-1.0178,-1.4965,-1.5661,-0.07899,1.0178,0 +6.214,-1.0176,-1.4965,-1.5666,-0.078471,1.0176,0 +6.215,-1.0173,-1.4966,-1.5671,-0.077951,1.0173,0 +6.216,-1.0171,-1.4966,-1.5676,-0.077432,1.0171,0 +6.217,-1.0168,-1.4966,-1.5681,-0.076913,1.0168,0 +6.218,-1.0165,-1.4967,-1.5685,-0.076393,1.0165,0 +6.219,-1.0163,-1.4967,-1.569,-0.075874,1.0163,0 +6.22,-1.016,-1.4967,-1.5695,-0.075354,1.016,0 +6.221,-1.0158,-1.4968,-1.57,-0.074835,1.0158,0 +6.222,-1.0155,-1.4968,-1.5705,-0.074316,1.0155,0 +6.223,-1.0152,-1.4968,-1.571,-0.073796,1.0152,0 +6.224,-1.015,-1.4969,-1.5714,-0.073277,1.015,0 +6.225,-1.0147,-1.4969,-1.5719,-0.072757,1.0147,0 +6.226,-1.0145,-1.4969,-1.5724,-0.072238,1.0145,0 +6.227,-1.0142,-1.497,-1.5729,-0.071718,1.0142,0 +6.228,-1.0139,-1.497,-1.5734,-0.071199,1.0139,0 +6.229,-1.0137,-1.497,-1.5739,-0.07068,1.0137,0 +6.23,-1.0134,-1.4971,-1.5744,-0.07016,1.0134,0 +6.231,-1.0132,-1.4971,-1.5748,-0.069641,1.0132,0 +6.232,-1.0129,-1.4972,-1.5753,-0.069121,1.0129,0 +6.233,-1.0126,-1.4972,-1.5758,-0.068602,1.0126,0 +6.234,-1.0124,-1.4972,-1.5763,-0.068083,1.0124,0 +6.235,-1.0121,-1.4973,-1.5768,-0.067563,1.0121,0 +6.236,-1.0119,-1.4973,-1.5773,-0.067044,1.0119,0 +6.237,-1.0116,-1.4973,-1.5777,-0.066524,1.0116,0 +6.238,-1.0113,-1.4974,-1.5782,-0.066005,1.0113,0 +6.239,-1.0111,-1.4974,-1.5787,-0.065486,1.0111,0 +6.24,-1.0108,-1.4974,-1.5792,-0.064966,1.0108,0 +6.241,-1.0106,-1.4975,-1.5797,-0.064447,1.0106,0 +6.242,-1.0103,-1.4975,-1.5802,-0.063927,1.0103,0 +6.243,-1.01,-1.4975,-1.5806,-0.063408,1.01,0 +6.244,-1.0098,-1.4976,-1.5811,-0.062889,1.0098,0 +6.245,-1.0095,-1.4976,-1.5816,-0.062369,1.0095,0 +6.246,-1.0093,-1.4976,-1.5821,-0.06185,1.0093,0 +6.247,-1.009,-1.4977,-1.5826,-0.06133,1.009,0 +6.248,-1.0087,-1.4977,-1.5831,-0.060811,1.0087,0 +6.249,-1.0085,-1.4977,-1.5836,-0.060292,1.0085,0 +6.25,-1.0082,-1.4978,-1.584,-0.059772,1.0082,0 +6.251,-1.008,-1.4978,-1.5845,-0.059253,1.008,0 +6.252,-1.0077,-1.4978,-1.585,-0.058733,1.0077,0 +6.253,-1.0074,-1.4979,-1.5855,-0.058214,1.0074,0 +6.254,-1.0072,-1.4979,-1.586,-0.057695,1.0072,0 +6.255,-1.0069,-1.498,-1.5865,-0.057175,1.0069,0 +6.256,-1.0067,-1.498,-1.5869,-0.056656,1.0067,0 +6.257,-1.0064,-1.498,-1.5874,-0.056136,1.0064,0 +6.258,-1.0061,-1.4981,-1.5879,-0.055617,1.0061,0 +6.259,-1.0059,-1.4981,-1.5884,-0.055098,1.0059,0 +6.26,-1.0056,-1.4981,-1.5889,-0.054578,1.0056,0 +6.261,-1.0054,-1.4982,-1.5894,-0.054059,1.0054,0 +6.262,-1.0051,-1.4982,-1.5899,-0.053539,1.0051,0 +6.263,-1.0048,-1.4982,-1.5903,-0.05302,1.0048,0 +6.264,-1.0046,-1.4983,-1.5908,-0.0525,1.0046,0 +6.265,-1.0043,-1.4983,-1.5913,-0.051982,1.0043,0 +6.266,-1.0041,-1.4983,-1.5918,-0.051464,1.0041,0 +6.267,-1.0038,-1.4984,-1.5923,-0.050948,1.0038,0 +6.268,-1.0036,-1.4984,-1.5927,-0.050433,1.0036,0 +6.269,-1.0034,-1.4984,-1.5932,-0.049919,1.0034,0 +6.27,-1.0031,-1.4985,-1.5937,-0.049406,1.0031,0 +6.271,-1.0029,-1.4985,-1.5942,-0.048895,1.0029,0 +6.272,-1.0027,-1.4986,-1.5946,-0.048385,1.0027,0 +6.273,-1.0025,-1.4986,-1.5951,-0.047877,1.0025,0 +6.274,-1.0023,-1.4987,-1.5956,-0.047369,1.0023,0 +6.275,-1.0021,-1.4987,-1.596,-0.046863,1.0021,0 +6.276,-1.0019,-1.4987,-1.5965,-0.046356,1.0019,0 +6.277,-1.0017,-1.4988,-1.597,-0.04585,1.0017,0 +6.278,-1.0015,-1.4988,-1.5974,-0.045343,1.0015,0 +6.279,-1.0013,-1.4989,-1.5979,-0.044837,1.0013,0 +6.28,-1.0012,-1.4989,-1.5984,-0.044331,1.0012,0 +6.281,-1.001,-1.499,-1.5988,-0.043824,1.001,0 +6.282,-1.0008,-1.499,-1.5993,-0.043318,1.0008,0 +6.283,-1.0006,-1.499,-1.5997,-0.042811,1.0006,0 +6.284,-1.0004,-1.4991,-1.6002,-0.042305,1.0004,0 +6.285,-1.0002,-1.4991,-1.6007,-0.041798,1.0002,0 +6.286,-1,-1.4992,-1.6011,-0.041292,1,0 +6.287,-0.99981,-1.4992,-1.6016,-0.040785,0.99981,0 +6.288,-0.99962,-1.4992,-1.6021,-0.040279,0.99962,0 +6.289,-0.99943,-1.4993,-1.6025,-0.039772,0.99943,0 +6.29,-0.99924,-1.4993,-1.603,-0.039266,0.99924,0 +6.291,-0.99905,-1.4994,-1.6035,-0.038759,0.99905,0 +6.292,-0.99886,-1.4994,-1.6039,-0.038253,0.99886,0 +6.293,-0.99867,-1.4995,-1.6044,-0.037746,0.99867,0 +6.294,-0.99847,-1.4995,-1.6048,-0.03724,0.99847,0 +6.295,-0.99828,-1.4995,-1.6053,-0.036733,0.99828,0 +6.296,-0.99809,-1.4996,-1.6058,-0.036227,0.99809,0 +6.297,-0.9979,-1.4996,-1.6062,-0.03572,0.9979,0 +6.298,-0.99771,-1.4997,-1.6067,-0.035214,0.99771,0 +6.299,-0.99752,-1.4997,-1.6072,-0.034707,0.99752,0 +6.3,-0.99732,-1.4998,-1.6076,-0.034201,0.99732,0 +6.301,-0.99713,-1.4998,-1.6081,-0.033694,0.99713,0 +6.302,-0.99694,-1.4998,-1.6086,-0.033188,0.99694,0 +6.303,-0.99675,-1.4999,-1.609,-0.032681,0.99675,0 +6.304,-0.99656,-1.4999,-1.6095,-0.032175,0.99656,0 +6.305,-0.99637,-1.5,-1.61,-0.031668,0.99637,0 +6.306,-0.99617,-1.5,-1.6104,-0.031162,0.99617,0 +6.307,-0.99598,-1.5001,-1.6109,-0.030655,0.99598,0 +6.308,-0.99579,-1.5001,-1.6113,-0.030149,0.99579,0 +6.309,-0.9956,-1.5001,-1.6118,-0.029642,0.9956,0 +6.31,-0.99541,-1.5002,-1.6123,-0.029136,0.99541,0 +6.311,-0.99522,-1.5002,-1.6127,-0.02863,0.99522,0 +6.312,-0.99502,-1.5003,-1.6132,-0.028123,0.99502,0 +6.313,-0.99483,-1.5003,-1.6137,-0.027617,0.99483,0 +6.314,-0.99464,-1.5004,-1.6141,-0.02711,0.99464,0 +6.315,-0.99445,-1.5004,-1.6146,-0.026604,0.99445,0 +6.316,-0.99426,-1.5004,-1.6151,-0.026097,0.99426,0 +6.317,-0.99407,-1.5005,-1.6155,-0.025591,0.99407,0 +6.318,-0.99387,-1.5005,-1.616,-0.025084,0.99387,0 +6.319,-0.99368,-1.5006,-1.6164,-0.024578,0.99368,0 +6.32,-0.99349,-1.5006,-1.6169,-0.024071,0.99349,0 +6.321,-0.9933,-1.5007,-1.6174,-0.023565,0.9933,0 +6.322,-0.99311,-1.5007,-1.6178,-0.023058,0.99311,0 +6.323,-0.99292,-1.5007,-1.6183,-0.022552,0.99292,0 +6.324,-0.99272,-1.5008,-1.6188,-0.022045,0.99272,0 +6.325,-0.99253,-1.5008,-1.6192,-0.021539,0.99253,0 +6.326,-0.99234,-1.5009,-1.6197,-0.021032,0.99234,0 +6.327,-0.99215,-1.5009,-1.6202,-0.020526,0.99215,0 +6.328,-0.99196,-1.5009,-1.6206,-0.020019,0.99196,0 +6.329,-0.99177,-1.501,-1.6211,-0.019513,0.99177,0 +6.33,-0.99157,-1.501,-1.6216,-0.019006,0.99157,0 +6.331,-0.99138,-1.5011,-1.622,-0.0185,0.99138,0 +6.332,-0.99119,-1.5011,-1.6225,-0.017993,0.99119,0 +6.333,-0.991,-1.5012,-1.6229,-0.017487,0.991,0 +6.334,-0.99081,-1.5012,-1.6234,-0.01698,0.99081,0 +6.335,-0.99062,-1.5012,-1.6239,-0.016474,0.99062,0 +6.336,-0.99042,-1.5013,-1.6243,-0.015967,0.99042,0 +6.337,-0.99023,-1.5013,-1.6248,-0.015461,0.99023,0 +6.338,-0.99004,-1.5014,-1.6253,-0.014954,0.99004,0 +6.339,-0.98985,-1.5014,-1.6257,-0.014448,0.98985,0 +6.34,-0.98966,-1.5015,-1.6262,-0.013941,0.98966,0 +6.341,-0.98947,-1.5015,-1.6267,-0.013435,0.98947,0 +6.342,-0.98927,-1.5015,-1.6271,-0.012929,0.98927,0 +6.343,-0.98908,-1.5016,-1.6276,-0.012422,0.98908,0 +6.344,-0.98889,-1.5016,-1.628,-0.011916,0.98889,0 +6.345,-0.9887,-1.5017,-1.6285,-0.011409,0.9887,0 +6.346,-0.98851,-1.5017,-1.629,-0.010903,0.98851,0 +6.347,-0.98832,-1.5018,-1.6294,-0.010396,0.98832,0 +6.348,-0.98813,-1.5018,-1.6299,-0.0098875,0.98813,0 +6.349,-0.98794,-1.5018,-1.6304,-0.0093739,0.98794,0 +6.35,-0.98777,-1.5019,-1.6308,-0.0088555,0.98777,0 +6.351,-0.9876,-1.5019,-1.6313,-0.0083321,0.9876,0 +6.352,-0.98743,-1.502,-1.6318,-0.0078037,0.98743,0 +6.353,-0.98727,-1.502,-1.6323,-0.0072705,0.98727,0 +6.354,-0.98712,-1.5021,-1.6328,-0.0067323,0.98712,0 +6.355,-0.98697,-1.5021,-1.6333,-0.0061892,0.98697,0 +6.356,-0.98683,-1.5022,-1.6338,-0.0056412,0.98683,0 +6.357,-0.98669,-1.5022,-1.6343,-0.0050882,0.98669,0 +6.358,-0.98656,-1.5023,-1.6348,-0.0045325,0.98656,0 +6.359,-0.98642,-1.5023,-1.6353,-0.0039767,0.98642,0 +6.36,-0.98629,-1.5024,-1.6358,-0.003421,0.98629,0 +6.361,-0.98616,-1.5024,-1.6363,-0.0028652,0.98616,0 +6.362,-0.98602,-1.5025,-1.6368,-0.0023095,0.98602,0 +6.363,-0.98589,-1.5025,-1.6373,-0.0017537,0.98589,0 +6.364,-0.98576,-1.5026,-1.6378,-0.001198,0.98576,0 +6.365,-0.98562,-1.5026,-1.6383,-0.00064221,0.98562,0 +6.366,-0.98549,-1.5027,-1.6388,-8.6459e-05,0.98549,0 +6.367,-0.98536,-1.5027,-1.6393,0.00046929,0.98536,0 +6.368,-0.98523,-1.5028,-1.6399,0.001025,0.98523,0 +6.369,-0.98509,-1.5028,-1.6404,0.0015808,0.98509,0 +6.37,-0.98496,-1.5029,-1.6409,0.0021365,0.98496,0 +6.371,-0.98483,-1.5029,-1.6414,0.0026923,0.98483,0 +6.372,-0.98469,-1.503,-1.6419,0.003248,0.98469,0 +6.373,-0.98456,-1.503,-1.6424,0.0038038,0.98456,0 +6.374,-0.98443,-1.5031,-1.6429,0.0043595,0.98443,0 +6.375,-0.98429,-1.5031,-1.6434,0.0049153,0.98429,0 +6.376,-0.98416,-1.5032,-1.6439,0.0054711,0.98416,0 +6.377,-0.98403,-1.5032,-1.6444,0.0060268,0.98403,0 +6.378,-0.9839,-1.5033,-1.6449,0.0065826,0.9839,0 +6.379,-0.98376,-1.5033,-1.6454,0.0071383,0.98376,0 +6.38,-0.98363,-1.5034,-1.6459,0.0076941,0.98363,0 +6.381,-0.9835,-1.5034,-1.6464,0.0082498,0.9835,0 +6.382,-0.98336,-1.5035,-1.6469,0.0088056,0.98336,0 +6.383,-0.98323,-1.5035,-1.6474,0.0093613,0.98323,0 +6.384,-0.9831,-1.5036,-1.648,0.0099171,0.9831,0 +6.385,-0.98296,-1.5036,-1.6485,0.010473,0.98296,0 +6.386,-0.98283,-1.5037,-1.649,0.011029,0.98283,0 +6.387,-0.9827,-1.5037,-1.6495,0.011584,0.9827,0 +6.388,-0.98256,-1.5038,-1.65,0.01214,0.98256,0 +6.389,-0.98243,-1.5038,-1.6505,0.012696,0.98243,0 +6.39,-0.9823,-1.5039,-1.651,0.013252,0.9823,0 +6.391,-0.98217,-1.5039,-1.6515,0.013807,0.98217,0 +6.392,-0.98203,-1.504,-1.652,0.014363,0.98203,0 +6.393,-0.9819,-1.504,-1.6525,0.014919,0.9819,0 +6.394,-0.98177,-1.5041,-1.653,0.015475,0.98177,0 +6.395,-0.98163,-1.5041,-1.6535,0.01603,0.98163,0 +6.396,-0.9815,-1.5041,-1.654,0.016586,0.9815,0 +6.397,-0.98137,-1.5042,-1.6545,0.017142,0.98137,0 +6.398,-0.98123,-1.5042,-1.655,0.017698,0.98123,0 +6.399,-0.9811,-1.5043,-1.6555,0.018253,0.9811,0 +6.4,-0.98097,-1.5043,-1.6561,0.018809,0.98097,0 +6.401,-0.98084,-1.5044,-1.6566,0.019365,0.98084,0 +6.402,-0.9807,-1.5044,-1.6571,0.019921,0.9807,0 +6.403,-0.98057,-1.5045,-1.6576,0.020476,0.98057,0 +6.404,-0.98044,-1.5045,-1.6581,0.021032,0.98044,0 +6.405,-0.9803,-1.5046,-1.6586,0.021588,0.9803,0 +6.406,-0.98017,-1.5046,-1.6591,0.022144,0.98017,0 +6.407,-0.98004,-1.5047,-1.6596,0.022699,0.98004,0 +6.408,-0.9799,-1.5047,-1.6601,0.023255,0.9799,0 +6.409,-0.97977,-1.5048,-1.6606,0.023811,0.97977,0 +6.41,-0.97964,-1.5048,-1.6611,0.024367,0.97964,0 +6.411,-0.9795,-1.5049,-1.6616,0.024922,0.9795,0 +6.412,-0.97937,-1.5049,-1.6621,0.025478,0.97937,0 +6.413,-0.97924,-1.505,-1.6626,0.026034,0.97924,0 +6.414,-0.97911,-1.505,-1.6631,0.02659,0.97911,0 +6.415,-0.97897,-1.5051,-1.6636,0.027145,0.97897,0 +6.416,-0.97884,-1.5051,-1.6642,0.027701,0.97884,0 +6.417,-0.97871,-1.5052,-1.6647,0.028257,0.97871,0 +6.418,-0.97857,-1.5052,-1.6652,0.028813,0.97857,0 +6.419,-0.97844,-1.5053,-1.6657,0.029368,0.97844,0 +6.42,-0.97831,-1.5053,-1.6662,0.029924,0.97831,0 +6.421,-0.97817,-1.5054,-1.6667,0.03048,0.97817,0 +6.422,-0.97804,-1.5054,-1.6672,0.031036,0.97804,0 +6.423,-0.97791,-1.5055,-1.6677,0.031591,0.97791,0 +6.424,-0.97778,-1.5055,-1.6682,0.032147,0.97778,0 +6.425,-0.97764,-1.5056,-1.6687,0.032703,0.97764,0 +6.426,-0.97751,-1.5056,-1.6692,0.033259,0.97751,0 +6.427,-0.97738,-1.5057,-1.6697,0.033814,0.97738,0 +6.428,-0.97724,-1.5057,-1.6702,0.03437,0.97724,0 +6.429,-0.97711,-1.5058,-1.6707,0.034926,0.97711,0 +6.43,-0.97698,-1.5058,-1.6712,0.035482,0.97698,0 +6.431,-0.97685,-1.5059,-1.6717,0.036037,0.97685,0 +6.432,-0.97672,-1.5059,-1.6722,0.036591,0.97672,0 +6.433,-0.9766,-1.506,-1.6728,0.037144,0.9766,0 +6.434,-0.97648,-1.506,-1.6733,0.037696,0.97648,0 +6.435,-0.97637,-1.5061,-1.6737,0.038247,0.97637,0 +6.436,-0.97627,-1.5061,-1.6742,0.038796,0.97627,0 +6.437,-0.97617,-1.5062,-1.6747,0.039345,0.97617,0 +6.438,-0.97607,-1.5063,-1.6752,0.039893,0.97607,0 +6.439,-0.97598,-1.5063,-1.6757,0.040439,0.97598,0 +6.44,-0.9759,-1.5064,-1.6762,0.040984,0.9759,0 +6.441,-0.97581,-1.5064,-1.6767,0.041529,0.97581,0 +6.442,-0.97573,-1.5065,-1.6772,0.042074,0.97573,0 +6.443,-0.97565,-1.5065,-1.6777,0.042619,0.97565,0 +6.444,-0.97556,-1.5066,-1.6782,0.043163,0.97556,0 +6.445,-0.97548,-1.5067,-1.6786,0.043708,0.97548,0 +6.446,-0.9754,-1.5067,-1.6791,0.044253,0.9754,0 +6.447,-0.97531,-1.5068,-1.6796,0.044798,0.97531,0 +6.448,-0.97523,-1.5068,-1.6801,0.045342,0.97523,0 +6.449,-0.97515,-1.5069,-1.6806,0.045887,0.97515,0 +6.45,-0.97506,-1.507,-1.6811,0.046432,0.97506,0 +6.451,-0.97498,-1.507,-1.6816,0.046977,0.97498,0 +6.452,-0.9749,-1.5071,-1.682,0.047521,0.9749,0 +6.453,-0.97481,-1.5071,-1.6825,0.048066,0.97481,0 +6.454,-0.97473,-1.5072,-1.683,0.048611,0.97473,0 +6.455,-0.97465,-1.5072,-1.6835,0.049156,0.97465,0 +6.456,-0.97456,-1.5073,-1.684,0.0497,0.97456,0 +6.457,-0.97448,-1.5074,-1.6845,0.050245,0.97448,0 +6.458,-0.9744,-1.5074,-1.685,0.05079,0.9744,0 +6.459,-0.97431,-1.5075,-1.6855,0.051335,0.97431,0 +6.46,-0.97423,-1.5075,-1.6859,0.05188,0.97423,0 +6.461,-0.97415,-1.5076,-1.6864,0.052424,0.97415,0 +6.462,-0.97406,-1.5077,-1.6869,0.052969,0.97406,0 +6.463,-0.97398,-1.5077,-1.6874,0.053514,0.97398,0 +6.464,-0.9739,-1.5078,-1.6879,0.054059,0.9739,0 +6.465,-0.97381,-1.5078,-1.6884,0.054603,0.97381,0 +6.466,-0.97373,-1.5079,-1.6889,0.055148,0.97373,0 +6.467,-0.97365,-1.5079,-1.6893,0.055693,0.97365,0 +6.468,-0.97356,-1.508,-1.6898,0.056238,0.97356,0 +6.469,-0.97348,-1.5081,-1.6903,0.056782,0.97348,0 +6.47,-0.9734,-1.5081,-1.6908,0.057327,0.9734,0 +6.471,-0.97331,-1.5082,-1.6913,0.057872,0.97331,0 +6.472,-0.97323,-1.5082,-1.6918,0.058417,0.97323,0 +6.473,-0.97315,-1.5083,-1.6923,0.058961,0.97315,0 +6.474,-0.97306,-1.5083,-1.6927,0.059506,0.97306,0 +6.475,-0.97298,-1.5084,-1.6932,0.060051,0.97298,0 +6.476,-0.9729,-1.5085,-1.6937,0.060596,0.9729,0 +6.477,-0.97281,-1.5085,-1.6942,0.06114,0.97281,0 +6.478,-0.97273,-1.5086,-1.6947,0.061685,0.97273,0 +6.479,-0.97265,-1.5086,-1.6952,0.06223,0.97265,0 +6.48,-0.97257,-1.5087,-1.6957,0.062775,0.97257,0 +6.481,-0.97248,-1.5088,-1.6962,0.06332,0.97248,0 +6.482,-0.9724,-1.5088,-1.6966,0.063864,0.9724,0 +6.483,-0.97232,-1.5089,-1.6971,0.064409,0.97232,0 +6.484,-0.97223,-1.5089,-1.6976,0.064954,0.97223,0 +6.485,-0.97215,-1.509,-1.6981,0.065499,0.97215,0 +6.486,-0.97207,-1.509,-1.6986,0.066043,0.97207,0 +6.487,-0.97198,-1.5091,-1.6991,0.066588,0.97198,0 +6.488,-0.9719,-1.5092,-1.6996,0.067133,0.9719,0 +6.489,-0.97182,-1.5092,-1.7,0.067678,0.97182,0 +6.49,-0.97173,-1.5093,-1.7005,0.068222,0.97173,0 +6.491,-0.97165,-1.5093,-1.701,0.068767,0.97165,0 +6.492,-0.97157,-1.5094,-1.7015,0.069312,0.97157,0 +6.493,-0.97148,-1.5095,-1.702,0.069857,0.97148,0 +6.494,-0.9714,-1.5095,-1.7025,0.070401,0.9714,0 +6.495,-0.97132,-1.5096,-1.703,0.070946,0.97132,0 +6.496,-0.97123,-1.5096,-1.7035,0.071491,0.97123,0 +6.497,-0.97115,-1.5097,-1.7039,0.072036,0.97115,0 +6.498,-0.97107,-1.5097,-1.7044,0.07258,0.97107,0 +6.499,-0.97098,-1.5098,-1.7049,0.073125,0.97098,0 +6.5,-0.9709,-1.5099,-1.7054,0.07367,0.9709,0 +6.501,-0.97082,-1.5099,-1.7059,0.074215,0.97082,0 +6.502,-0.97073,-1.51,-1.7064,0.07476,0.97073,0 +6.503,-0.97065,-1.51,-1.7069,0.075304,0.97065,0 +6.504,-0.97057,-1.5101,-1.7073,0.075849,0.97057,0 +6.505,-0.97048,-1.5102,-1.7078,0.076394,0.97048,0 +6.506,-0.9704,-1.5102,-1.7083,0.076939,0.9704,0 +6.507,-0.97032,-1.5103,-1.7088,0.077483,0.97032,0 +6.508,-0.97023,-1.5103,-1.7093,0.078028,0.97023,0 +6.509,-0.97015,-1.5104,-1.7098,0.078573,0.97015,0 +6.51,-0.97007,-1.5104,-1.7103,0.079118,0.97007,0 +6.511,-0.96998,-1.5105,-1.7108,0.079662,0.96998,0 +6.512,-0.9699,-1.5106,-1.7112,0.080207,0.9699,0 +6.513,-0.96982,-1.5106,-1.7117,0.080752,0.96982,0 +6.514,-0.96974,-1.5107,-1.7122,0.081297,0.96974,0 +6.515,-0.96967,-1.5107,-1.7127,0.081844,0.96967,0 +6.516,-0.96962,-1.5108,-1.7132,0.082393,0.96962,0 +6.517,-0.96957,-1.5108,-1.7137,0.082942,0.96957,0 +6.518,-0.96953,-1.5109,-1.7142,0.083493,0.96953,0 +6.519,-0.96951,-1.511,-1.7147,0.084045,0.96951,0 +6.52,-0.96949,-1.511,-1.7152,0.084599,0.96949,0 +6.521,-0.96949,-1.5111,-1.7157,0.085154,0.96949,0 +6.522,-0.96949,-1.5111,-1.7162,0.08571,0.96949,0 +6.523,-0.96951,-1.5112,-1.7167,0.086268,0.96951,0 +6.524,-0.96953,-1.5112,-1.7172,0.086826,0.96953,0 +6.525,-0.96955,-1.5113,-1.7177,0.087385,0.96955,0 +6.526,-0.96957,-1.5113,-1.7182,0.087943,0.96957,0 +6.527,-0.96959,-1.5113,-1.7187,0.088501,0.96959,0 +6.528,-0.96961,-1.5114,-1.7193,0.08906,0.96961,0 +6.529,-0.96964,-1.5114,-1.7198,0.089618,0.96964,0 +6.53,-0.96966,-1.5115,-1.7203,0.090177,0.96966,0 +6.531,-0.96968,-1.5115,-1.7208,0.090735,0.96968,0 +6.532,-0.9697,-1.5116,-1.7213,0.091293,0.9697,0 +6.533,-0.96972,-1.5116,-1.7218,0.091852,0.96972,0 +6.534,-0.96974,-1.5117,-1.7223,0.09241,0.96974,0 +6.535,-0.96976,-1.5117,-1.7228,0.092968,0.96976,0 +6.536,-0.96978,-1.5118,-1.7233,0.093527,0.96978,0 +6.537,-0.9698,-1.5118,-1.7238,0.094085,0.9698,0 +6.538,-0.96982,-1.5119,-1.7244,0.094643,0.96982,0 +6.539,-0.96984,-1.5119,-1.7249,0.095202,0.96984,0 +6.54,-0.96986,-1.512,-1.7254,0.09576,0.96986,0 +6.541,-0.96988,-1.512,-1.7259,0.096318,0.96988,0 +6.542,-0.96991,-1.5121,-1.7264,0.096877,0.96991,0 +6.543,-0.96993,-1.5121,-1.7269,0.097435,0.96993,0 +6.544,-0.96995,-1.5122,-1.7274,0.097993,0.96995,0 +6.545,-0.96997,-1.5122,-1.7279,0.098552,0.96997,0 +6.546,-0.96999,-1.5123,-1.7284,0.09911,0.96999,0 +6.547,-0.97001,-1.5123,-1.7289,0.099668,0.97001,0 +6.548,-0.97003,-1.5124,-1.7294,0.10023,0.97003,0 +6.549,-0.97005,-1.5124,-1.73,0.10078,0.97005,0 +6.55,-0.97007,-1.5125,-1.7305,0.10134,0.97007,0 +6.551,-0.97009,-1.5125,-1.731,0.1019,0.97009,0 +6.552,-0.97011,-1.5126,-1.7315,0.10246,0.97011,0 +6.553,-0.97013,-1.5126,-1.732,0.10302,0.97013,0 +6.554,-0.97015,-1.5127,-1.7325,0.10358,0.97015,0 +6.555,-0.97017,-1.5127,-1.733,0.10414,0.97017,0 +6.556,-0.9702,-1.5128,-1.7335,0.10469,0.9702,0 +6.557,-0.97022,-1.5128,-1.734,0.10525,0.97022,0 +6.558,-0.97024,-1.5129,-1.7345,0.10581,0.97024,0 +6.559,-0.97026,-1.5129,-1.7351,0.10637,0.97026,0 +6.56,-0.97028,-1.513,-1.7356,0.10693,0.97028,0 +6.561,-0.9703,-1.513,-1.7361,0.10749,0.9703,0 +6.562,-0.97032,-1.5131,-1.7366,0.10804,0.97032,0 +6.563,-0.97034,-1.5131,-1.7371,0.1086,0.97034,0 +6.564,-0.97036,-1.5132,-1.7376,0.10916,0.97036,0 +6.565,-0.97038,-1.5132,-1.7381,0.10972,0.97038,0 +6.566,-0.9704,-1.5133,-1.7386,0.11028,0.9704,0 +6.567,-0.97042,-1.5133,-1.7391,0.11084,0.97042,0 +6.568,-0.97044,-1.5133,-1.7396,0.11139,0.97044,0 +6.569,-0.97047,-1.5134,-1.7401,0.11195,0.97047,0 +6.57,-0.97049,-1.5134,-1.7407,0.11251,0.97049,0 +6.571,-0.97051,-1.5135,-1.7412,0.11307,0.97051,0 +6.572,-0.97053,-1.5135,-1.7417,0.11363,0.97053,0 +6.573,-0.97055,-1.5136,-1.7422,0.11419,0.97055,0 +6.574,-0.97057,-1.5136,-1.7427,0.11474,0.97057,0 +6.575,-0.97059,-1.5137,-1.7432,0.1153,0.97059,0 +6.576,-0.97061,-1.5137,-1.7437,0.11586,0.97061,0 +6.577,-0.97063,-1.5138,-1.7442,0.11642,0.97063,0 +6.578,-0.97065,-1.5138,-1.7447,0.11698,0.97065,0 +6.579,-0.97067,-1.5139,-1.7452,0.11754,0.97067,0 +6.58,-0.97069,-1.5139,-1.7458,0.11809,0.97069,0 +6.581,-0.97071,-1.514,-1.7463,0.11865,0.97071,0 +6.582,-0.97074,-1.514,-1.7468,0.11921,0.97074,0 +6.583,-0.97076,-1.5141,-1.7473,0.11977,0.97076,0 +6.584,-0.97078,-1.5141,-1.7478,0.12033,0.97078,0 +6.585,-0.9708,-1.5142,-1.7483,0.12089,0.9708,0 +6.586,-0.97082,-1.5142,-1.7488,0.12144,0.97082,0 +6.587,-0.97084,-1.5143,-1.7493,0.122,0.97084,0 +6.588,-0.97086,-1.5143,-1.7498,0.12256,0.97086,0 +6.589,-0.97088,-1.5144,-1.7503,0.12312,0.97088,0 +6.59,-0.9709,-1.5144,-1.7508,0.12368,0.9709,0 +6.591,-0.97092,-1.5145,-1.7514,0.12424,0.97092,0 +6.592,-0.97094,-1.5145,-1.7519,0.12479,0.97094,0 +6.593,-0.97096,-1.5146,-1.7524,0.12535,0.97096,0 +6.594,-0.97098,-1.5146,-1.7529,0.12591,0.97098,0 +6.595,-0.97101,-1.5147,-1.7534,0.12647,0.97101,0 +6.596,-0.97103,-1.5147,-1.7539,0.12703,0.97103,0 +6.597,-0.97105,-1.5148,-1.7544,0.12759,0.97105,0 +6.598,-0.97108,-1.5148,-1.7549,0.12815,0.97108,0 +6.599,-0.9711,-1.5149,-1.7554,0.12871,0.9711,0 +6.6,-0.97114,-1.5149,-1.7559,0.12927,0.97114,0 +6.601,-0.97117,-1.515,-1.7565,0.12984,0.97117,0 +6.602,-0.97122,-1.515,-1.757,0.13041,0.97122,0 +6.603,-0.97126,-1.5151,-1.7575,0.13098,0.97126,0 +6.604,-0.97131,-1.5152,-1.758,0.13155,0.97131,0 +6.605,-0.97136,-1.5152,-1.7585,0.13212,0.97136,0 +6.606,-0.97141,-1.5153,-1.759,0.13269,0.97141,0 +6.607,-0.97147,-1.5153,-1.7595,0.13327,0.97147,0 +6.608,-0.97152,-1.5154,-1.76,0.13384,0.97152,0 +6.609,-0.97158,-1.5155,-1.7605,0.13442,0.97158,0 +6.61,-0.97163,-1.5155,-1.761,0.13499,0.97163,0 +6.611,-0.97169,-1.5156,-1.7616,0.13557,0.97169,0 +6.612,-0.97174,-1.5157,-1.7621,0.13614,0.97174,0 +6.613,-0.9718,-1.5157,-1.7626,0.13672,0.9718,0 +6.614,-0.97186,-1.5158,-1.7631,0.13729,0.97186,0 +6.615,-0.97191,-1.5159,-1.7636,0.13787,0.97191,0 +6.616,-0.97197,-1.5159,-1.7641,0.13844,0.97197,0 +6.617,-0.97202,-1.516,-1.7646,0.13902,0.97202,0 +6.618,-0.97208,-1.5161,-1.7651,0.13959,0.97208,0 +6.619,-0.97213,-1.5161,-1.7656,0.14017,0.97213,0 +6.62,-0.97219,-1.5162,-1.7662,0.14074,0.97219,0 +6.621,-0.97224,-1.5162,-1.7667,0.14132,0.97224,0 +6.622,-0.9723,-1.5163,-1.7672,0.14189,0.9723,0 +6.623,-0.97236,-1.5164,-1.7677,0.14247,0.97236,0 +6.624,-0.97241,-1.5164,-1.7682,0.14304,0.97241,0 +6.625,-0.97247,-1.5165,-1.7687,0.14362,0.97247,0 +6.626,-0.97252,-1.5166,-1.7692,0.14419,0.97252,0 +6.627,-0.97258,-1.5166,-1.7697,0.14477,0.97258,0 +6.628,-0.97263,-1.5167,-1.7702,0.14534,0.97263,0 +6.629,-0.97269,-1.5168,-1.7707,0.14592,0.97269,0 +6.63,-0.97274,-1.5168,-1.7713,0.14649,0.97274,0 +6.631,-0.9728,-1.5169,-1.7718,0.14707,0.9728,0 +6.632,-0.97285,-1.517,-1.7723,0.14764,0.97285,0 +6.633,-0.97291,-1.517,-1.7728,0.14822,0.97291,0 +6.634,-0.97297,-1.5171,-1.7733,0.14879,0.97297,0 +6.635,-0.97302,-1.5171,-1.7738,0.14937,0.97302,0 +6.636,-0.97308,-1.5172,-1.7743,0.14994,0.97308,0 +6.637,-0.97313,-1.5173,-1.7748,0.15052,0.97313,0 +6.638,-0.97319,-1.5173,-1.7753,0.15109,0.97319,0 +6.639,-0.97324,-1.5174,-1.7759,0.15166,0.97324,0 +6.64,-0.9733,-1.5175,-1.7764,0.15224,0.9733,0 +6.641,-0.97335,-1.5175,-1.7769,0.15281,0.97335,0 +6.642,-0.97341,-1.5176,-1.7774,0.15339,0.97341,0 +6.643,-0.97347,-1.5177,-1.7779,0.15396,0.97347,0 +6.644,-0.97352,-1.5177,-1.7784,0.15454,0.97352,0 +6.645,-0.97358,-1.5178,-1.7789,0.15511,0.97358,0 +6.646,-0.97363,-1.5179,-1.7794,0.15569,0.97363,0 +6.647,-0.97369,-1.5179,-1.7799,0.15626,0.97369,0 +6.648,-0.97374,-1.518,-1.7804,0.15684,0.97374,0 +6.649,-0.9738,-1.518,-1.781,0.15741,0.9738,0 +6.65,-0.97385,-1.5181,-1.7815,0.15799,0.97385,0 +6.651,-0.97391,-1.5182,-1.782,0.15856,0.97391,0 +6.652,-0.97397,-1.5182,-1.7825,0.15914,0.97397,0 +6.653,-0.97402,-1.5183,-1.783,0.15971,0.97402,0 +6.654,-0.97408,-1.5184,-1.7835,0.16029,0.97408,0 +6.655,-0.97413,-1.5184,-1.784,0.16086,0.97413,0 +6.656,-0.97419,-1.5185,-1.7845,0.16144,0.97419,0 +6.657,-0.97424,-1.5186,-1.785,0.16201,0.97424,0 +6.658,-0.9743,-1.5186,-1.7856,0.16259,0.9743,0 +6.659,-0.97435,-1.5187,-1.7861,0.16316,0.97435,0 +6.66,-0.97441,-1.5188,-1.7866,0.16374,0.97441,0 +6.661,-0.97447,-1.5188,-1.7871,0.16431,0.97447,0 +6.662,-0.97452,-1.5189,-1.7876,0.16489,0.97452,0 +6.663,-0.97458,-1.5189,-1.7881,0.16546,0.97458,0 +6.664,-0.97463,-1.519,-1.7886,0.16604,0.97463,0 +6.665,-0.97469,-1.5191,-1.7891,0.16661,0.97469,0 +6.666,-0.97474,-1.5191,-1.7896,0.16719,0.97474,0 +6.667,-0.9748,-1.5192,-1.7901,0.16776,0.9748,0 +6.668,-0.97485,-1.5193,-1.7907,0.16834,0.97485,0 +6.669,-0.97491,-1.5193,-1.7912,0.16891,0.97491,0 +6.67,-0.97497,-1.5194,-1.7917,0.16949,0.97497,0 +6.671,-0.97502,-1.5195,-1.7922,0.17006,0.97502,0 +6.672,-0.97508,-1.5195,-1.7927,0.17063,0.97508,0 +6.673,-0.97513,-1.5196,-1.7932,0.17121,0.97513,0 +6.674,-0.97519,-1.5197,-1.7937,0.17178,0.97519,0 +6.675,-0.97524,-1.5197,-1.7942,0.17236,0.97524,0 +6.676,-0.9753,-1.5198,-1.7947,0.17293,0.9753,0 +6.677,-0.97535,-1.5198,-1.7953,0.17351,0.97535,0 +6.678,-0.97541,-1.5199,-1.7958,0.17408,0.97541,0 +6.679,-0.97546,-1.52,-1.7963,0.17466,0.97546,0 +6.68,-0.97552,-1.52,-1.7968,0.17523,0.97552,0 +6.681,-0.97559,-1.5201,-1.7973,0.17581,0.97559,0 +6.682,-0.97566,-1.5202,-1.7978,0.17639,0.97566,0 +6.683,-0.97574,-1.5202,-1.7983,0.17697,0.97574,0 +6.684,-0.97582,-1.5203,-1.7988,0.17756,0.97582,0 +6.685,-0.97591,-1.5204,-1.7993,0.17814,0.97591,0 +6.686,-0.976,-1.5205,-1.7999,0.17873,0.976,0 +6.687,-0.9761,-1.5205,-1.8004,0.17932,0.9761,0 +6.688,-0.9762,-1.5206,-1.8009,0.17991,0.9762,0 +6.689,-0.97631,-1.5207,-1.8014,0.1805,0.97631,0 +6.69,-0.97642,-1.5208,-1.8019,0.18109,0.97642,0 +6.691,-0.97654,-1.5208,-1.8024,0.18168,0.97654,0 +6.692,-0.97665,-1.5209,-1.803,0.18228,0.97665,0 +6.693,-0.97676,-1.521,-1.8035,0.18287,0.97676,0 +6.694,-0.97687,-1.5211,-1.804,0.18346,0.97687,0 +6.695,-0.97698,-1.5211,-1.8045,0.18405,0.97698,0 +6.696,-0.97709,-1.5212,-1.805,0.18465,0.97709,0 +6.697,-0.97721,-1.5213,-1.8055,0.18524,0.97721,0 +6.698,-0.97732,-1.5214,-1.8061,0.18583,0.97732,0 +6.699,-0.97743,-1.5214,-1.8066,0.18642,0.97743,0 +6.7,-0.97754,-1.5215,-1.8071,0.18702,0.97754,0 +6.701,-0.97765,-1.5216,-1.8076,0.18761,0.97765,0 +6.702,-0.97777,-1.5217,-1.8081,0.1882,0.97777,0 +6.703,-0.97788,-1.5217,-1.8086,0.1888,0.97788,0 +6.704,-0.97799,-1.5218,-1.8092,0.18939,0.97799,0 +6.705,-0.9781,-1.5219,-1.8097,0.18998,0.9781,0 +6.706,-0.97821,-1.522,-1.8102,0.19057,0.97821,0 +6.707,-0.97832,-1.5221,-1.8107,0.19117,0.97832,0 +6.708,-0.97844,-1.5221,-1.8112,0.19176,0.97844,0 +6.709,-0.97855,-1.5222,-1.8117,0.19235,0.97855,0 +6.71,-0.97866,-1.5223,-1.8123,0.19294,0.97866,0 +6.711,-0.97877,-1.5224,-1.8128,0.19354,0.97877,0 +6.712,-0.97888,-1.5224,-1.8133,0.19413,0.97888,0 +6.713,-0.979,-1.5225,-1.8138,0.19472,0.979,0 +6.714,-0.97911,-1.5226,-1.8143,0.19531,0.97911,0 +6.715,-0.97922,-1.5227,-1.8148,0.19591,0.97922,0 +6.716,-0.97933,-1.5227,-1.8154,0.1965,0.97933,0 +6.717,-0.97944,-1.5228,-1.8159,0.19709,0.97944,0 +6.718,-0.97956,-1.5229,-1.8164,0.19768,0.97956,0 +6.719,-0.97967,-1.523,-1.8169,0.19828,0.97967,0 +6.72,-0.97978,-1.523,-1.8174,0.19887,0.97978,0 +6.721,-0.97989,-1.5231,-1.8179,0.19946,0.97989,0 +6.722,-0.98,-1.5232,-1.8185,0.20005,0.98,0 +6.723,-0.98011,-1.5233,-1.819,0.20065,0.98011,0 +6.724,-0.98023,-1.5233,-1.8195,0.20124,0.98023,0 +6.725,-0.98034,-1.5234,-1.82,0.20183,0.98034,0 +6.726,-0.98045,-1.5235,-1.8205,0.20243,0.98045,0 +6.727,-0.98056,-1.5236,-1.821,0.20302,0.98056,0 +6.728,-0.98067,-1.5236,-1.8216,0.20361,0.98067,0 +6.729,-0.98079,-1.5237,-1.8221,0.2042,0.98079,0 +6.73,-0.9809,-1.5238,-1.8226,0.2048,0.9809,0 +6.731,-0.98101,-1.5239,-1.8231,0.20539,0.98101,0 +6.732,-0.98112,-1.524,-1.8236,0.20598,0.98112,0 +6.733,-0.98123,-1.524,-1.8241,0.20657,0.98123,0 +6.734,-0.98135,-1.5241,-1.8247,0.20717,0.98135,0 +6.735,-0.98146,-1.5242,-1.8252,0.20776,0.98146,0 +6.736,-0.98157,-1.5243,-1.8257,0.20835,0.98157,0 +6.737,-0.98168,-1.5243,-1.8262,0.20894,0.98168,0 +6.738,-0.98179,-1.5244,-1.8267,0.20954,0.98179,0 +6.739,-0.9819,-1.5245,-1.8272,0.21013,0.9819,0 +6.74,-0.98202,-1.5246,-1.8278,0.21072,0.98202,0 +6.741,-0.98213,-1.5246,-1.8283,0.21131,0.98213,0 +6.742,-0.98224,-1.5247,-1.8288,0.21191,0.98224,0 +6.743,-0.98235,-1.5248,-1.8293,0.2125,0.98235,0 +6.744,-0.98246,-1.5249,-1.8298,0.21309,0.98246,0 +6.745,-0.98258,-1.5249,-1.8303,0.21368,0.98258,0 +6.746,-0.98269,-1.525,-1.8309,0.21428,0.98269,0 +6.747,-0.9828,-1.5251,-1.8314,0.21487,0.9828,0 +6.748,-0.98291,-1.5252,-1.8319,0.21546,0.98291,0 +6.749,-0.98302,-1.5252,-1.8324,0.21606,0.98302,0 +6.75,-0.98314,-1.5253,-1.8329,0.21665,0.98314,0 +6.751,-0.98325,-1.5254,-1.8334,0.21724,0.98325,0 +6.752,-0.98336,-1.5255,-1.8339,0.21783,0.98336,0 +6.753,-0.98347,-1.5256,-1.8345,0.21843,0.98347,0 +6.754,-0.98358,-1.5256,-1.835,0.21902,0.98358,0 +6.755,-0.98369,-1.5257,-1.8355,0.21961,0.98369,0 +6.756,-0.98381,-1.5258,-1.836,0.2202,0.98381,0 +6.757,-0.98392,-1.5259,-1.8365,0.2208,0.98392,0 +6.758,-0.98403,-1.5259,-1.837,0.22139,0.98403,0 +6.759,-0.98414,-1.526,-1.8376,0.22198,0.98414,0 +6.76,-0.98425,-1.5261,-1.8381,0.22257,0.98425,0 +6.761,-0.98437,-1.5262,-1.8386,0.22317,0.98437,0 +6.762,-0.98448,-1.5262,-1.8391,0.22376,0.98448,0 +6.763,-0.9846,-1.5263,-1.8396,0.22435,0.9846,0 +6.764,-0.98473,-1.5264,-1.8402,0.22496,0.98473,0 +6.765,-0.98488,-1.5265,-1.8407,0.22556,0.98488,0 +6.766,-0.98503,-1.5265,-1.8412,0.22617,0.98503,0 +6.767,-0.9852,-1.5266,-1.8418,0.22678,0.9852,0 +6.768,-0.98539,-1.5267,-1.8423,0.2274,0.98539,0 +6.769,-0.98558,-1.5268,-1.8428,0.22802,0.98558,0 +6.77,-0.98579,-1.5269,-1.8434,0.22865,0.98579,0 +6.771,-0.986,-1.5269,-1.8439,0.22928,0.986,0 +6.772,-0.98624,-1.527,-1.8445,0.22992,0.98624,0 +6.773,-0.98647,-1.5271,-1.845,0.23056,0.98647,0 +6.774,-0.9867,-1.5272,-1.8456,0.23119,0.9867,0 +6.775,-0.98694,-1.5273,-1.8462,0.23183,0.98694,0 +6.776,-0.98717,-1.5273,-1.8467,0.23247,0.98717,0 +6.777,-0.98741,-1.5274,-1.8473,0.23311,0.98741,0 +6.778,-0.98764,-1.5275,-1.8478,0.23374,0.98764,0 +6.779,-0.98787,-1.5276,-1.8484,0.23438,0.98787,0 +6.78,-0.98811,-1.5277,-1.8489,0.23502,0.98811,0 +6.781,-0.98834,-1.5277,-1.8495,0.23565,0.98834,0 +6.782,-0.98858,-1.5278,-1.8501,0.23629,0.98858,0 +6.783,-0.98881,-1.5279,-1.8506,0.23693,0.98881,0 +6.784,-0.98904,-1.528,-1.8512,0.23757,0.98904,0 +6.785,-0.98928,-1.5281,-1.8517,0.2382,0.98928,0 +6.786,-0.98951,-1.5281,-1.8523,0.23884,0.98951,0 +6.787,-0.98975,-1.5282,-1.8528,0.23948,0.98975,0 +6.788,-0.98998,-1.5283,-1.8534,0.24012,0.98998,0 +6.789,-0.99021,-1.5284,-1.854,0.24075,0.99021,0 +6.79,-0.99045,-1.5285,-1.8545,0.24139,0.99045,0 +6.791,-0.99068,-1.5286,-1.8551,0.24203,0.99068,0 +6.792,-0.99092,-1.5286,-1.8556,0.24267,0.99092,0 +6.793,-0.99115,-1.5287,-1.8562,0.2433,0.99115,0 +6.794,-0.99139,-1.5288,-1.8567,0.24394,0.99139,0 +6.795,-0.99162,-1.5289,-1.8573,0.24458,0.99162,0 +6.796,-0.99185,-1.529,-1.8579,0.24521,0.99185,0 +6.797,-0.99209,-1.529,-1.8584,0.24585,0.99209,0 +6.798,-0.99232,-1.5291,-1.859,0.24649,0.99232,0 +6.799,-0.99256,-1.5292,-1.8595,0.24713,0.99256,0 +6.8,-0.99279,-1.5293,-1.8601,0.24776,0.99279,0 +6.801,-0.99302,-1.5294,-1.8606,0.2484,0.99302,0 +6.802,-0.99326,-1.5294,-1.8612,0.24904,0.99326,0 +6.803,-0.99349,-1.5295,-1.8617,0.24968,0.99349,0 +6.804,-0.99373,-1.5296,-1.8623,0.25031,0.99373,0 +6.805,-0.99396,-1.5297,-1.8629,0.25095,0.99396,0 +6.806,-0.99419,-1.5298,-1.8634,0.25159,0.99419,0 +6.807,-0.99443,-1.5298,-1.864,0.25223,0.99443,0 +6.808,-0.99466,-1.5299,-1.8645,0.25286,0.99466,0 +6.809,-0.9949,-1.53,-1.8651,0.2535,0.9949,0 +6.81,-0.99513,-1.5301,-1.8656,0.25414,0.99513,0 +6.811,-0.99536,-1.5302,-1.8662,0.25477,0.99536,0 +6.812,-0.9956,-1.5302,-1.8668,0.25541,0.9956,0 +6.813,-0.99583,-1.5303,-1.8673,0.25605,0.99583,0 +6.814,-0.99607,-1.5304,-1.8679,0.25669,0.99607,0 +6.815,-0.9963,-1.5305,-1.8684,0.25732,0.9963,0 +6.816,-0.99654,-1.5306,-1.869,0.25796,0.99654,0 +6.817,-0.99677,-1.5306,-1.8695,0.2586,0.99677,0 +6.818,-0.997,-1.5307,-1.8701,0.25924,0.997,0 +6.819,-0.99724,-1.5308,-1.8707,0.25987,0.99724,0 +6.82,-0.99747,-1.5309,-1.8712,0.26051,0.99747,0 +6.821,-0.99771,-1.531,-1.8718,0.26115,0.99771,0 +6.822,-0.99794,-1.531,-1.8723,0.26179,0.99794,0 +6.823,-0.99817,-1.5311,-1.8729,0.26242,0.99817,0 +6.824,-0.99841,-1.5312,-1.8734,0.26306,0.99841,0 +6.825,-0.99864,-1.5313,-1.874,0.2637,0.99864,0 +6.826,-0.99888,-1.5314,-1.8746,0.26433,0.99888,0 +6.827,-0.99911,-1.5315,-1.8751,0.26497,0.99911,0 +6.828,-0.99934,-1.5315,-1.8757,0.26561,0.99934,0 +6.829,-0.99958,-1.5316,-1.8762,0.26625,0.99958,0 +6.83,-0.99981,-1.5317,-1.8768,0.26688,0.99981,0 +6.831,-1,-1.5318,-1.8773,0.26752,1,0 +6.832,-1.0003,-1.5319,-1.8779,0.26816,1.0003,0 +6.833,-1.0005,-1.5319,-1.8785,0.2688,1.0005,0 +6.834,-1.0007,-1.532,-1.879,0.26943,1.0007,0 +6.835,-1.001,-1.5321,-1.8796,0.27007,1.001,0 +6.836,-1.0012,-1.5322,-1.8801,0.27071,1.0012,0 +6.837,-1.0015,-1.5323,-1.8807,0.27135,1.0015,0 +6.838,-1.0017,-1.5323,-1.8812,0.27198,1.0017,0 +6.839,-1.0019,-1.5324,-1.8818,0.27262,1.0019,0 +6.84,-1.0022,-1.5325,-1.8824,0.27326,1.0022,0 +6.841,-1.0024,-1.5326,-1.8829,0.27389,1.0024,0 +6.842,-1.0026,-1.5327,-1.8835,0.27453,1.0026,0 +6.843,-1.0029,-1.5327,-1.884,0.27517,1.0029,0 +6.844,-1.0031,-1.5328,-1.8846,0.27581,1.0031,0 +6.845,-1.0033,-1.5329,-1.8851,0.27644,1.0033,0 +6.846,-1.0036,-1.533,-1.8857,0.27708,1.0036,0 +6.847,-1.0038,-1.5331,-1.8862,0.27772,1.0038,0 +6.848,-1.0041,-1.5332,-1.8868,0.27837,1.0041,0 +6.849,-1.0043,-1.5333,-1.8874,0.27901,1.0043,0 +6.85,-1.0046,-1.5333,-1.8879,0.27966,1.0046,0 +6.851,-1.0048,-1.5334,-1.8885,0.28031,1.0048,0 +6.852,-1.0051,-1.5335,-1.889,0.28097,1.0051,0 +6.853,-1.0054,-1.5336,-1.8896,0.28162,1.0054,0 +6.854,-1.0057,-1.5338,-1.8901,0.28228,1.0057,0 +6.855,-1.006,-1.5339,-1.8907,0.28294,1.006,0 +6.856,-1.0062,-1.534,-1.8912,0.2836,1.0062,0 +6.857,-1.0065,-1.5341,-1.8918,0.28426,1.0065,0 +6.858,-1.0068,-1.5342,-1.8923,0.28492,1.0068,0 +6.859,-1.0071,-1.5343,-1.8929,0.28558,1.0071,0 +6.86,-1.0074,-1.5344,-1.8934,0.28624,1.0074,0 +6.861,-1.0077,-1.5345,-1.894,0.2869,1.0077,0 +6.862,-1.008,-1.5346,-1.8945,0.28756,1.008,0 +6.863,-1.0083,-1.5347,-1.8951,0.28822,1.0083,0 +6.864,-1.0086,-1.5349,-1.8956,0.28888,1.0086,0 +6.865,-1.0089,-1.535,-1.8962,0.28954,1.0089,0 +6.866,-1.0091,-1.5351,-1.8967,0.29021,1.0091,0 +6.867,-1.0094,-1.5352,-1.8973,0.29087,1.0094,0 +6.868,-1.0097,-1.5353,-1.8978,0.29153,1.0097,0 +6.869,-1.01,-1.5354,-1.8984,0.29219,1.01,0 +6.87,-1.0103,-1.5355,-1.8989,0.29285,1.0103,0 +6.871,-1.0106,-1.5356,-1.8995,0.29351,1.0106,0 +6.872,-1.0109,-1.5357,-1.9,0.29417,1.0109,0 +6.873,-1.0112,-1.5358,-1.9006,0.29483,1.0112,0 +6.874,-1.0115,-1.536,-1.9011,0.29549,1.0115,0 +6.875,-1.0118,-1.5361,-1.9017,0.29615,1.0118,0 +6.876,-1.012,-1.5362,-1.9022,0.29681,1.012,0 +6.877,-1.0123,-1.5363,-1.9028,0.29747,1.0123,0 +6.878,-1.0126,-1.5364,-1.9033,0.29813,1.0126,0 +6.879,-1.0129,-1.5365,-1.9039,0.29879,1.0129,0 +6.88,-1.0132,-1.5366,-1.9044,0.29945,1.0132,0 +6.881,-1.0135,-1.5367,-1.905,0.30011,1.0135,0 +6.882,-1.0138,-1.5368,-1.9055,0.30077,1.0138,0 +6.883,-1.0141,-1.537,-1.9061,0.30143,1.0141,0 +6.884,-1.0144,-1.5371,-1.9066,0.3021,1.0144,0 +6.885,-1.0146,-1.5372,-1.9072,0.30276,1.0146,0 +6.886,-1.0149,-1.5373,-1.9077,0.30342,1.0149,0 +6.887,-1.0152,-1.5374,-1.9083,0.30408,1.0152,0 +6.888,-1.0155,-1.5375,-1.9088,0.30474,1.0155,0 +6.889,-1.0158,-1.5376,-1.9094,0.3054,1.0158,0 +6.89,-1.0161,-1.5377,-1.9099,0.30606,1.0161,0 +6.891,-1.0164,-1.5378,-1.9105,0.30672,1.0164,0 +6.892,-1.0167,-1.5379,-1.911,0.30738,1.0167,0 +6.893,-1.017,-1.5381,-1.9116,0.30804,1.017,0 +6.894,-1.0173,-1.5382,-1.9121,0.3087,1.0173,0 +6.895,-1.0175,-1.5383,-1.9127,0.30936,1.0175,0 +6.896,-1.0178,-1.5384,-1.9132,0.31002,1.0178,0 +6.897,-1.0181,-1.5385,-1.9138,0.31068,1.0181,0 +6.898,-1.0184,-1.5386,-1.9143,0.31134,1.0184,0 +6.899,-1.0187,-1.5387,-1.9149,0.312,1.0187,0 +6.9,-1.019,-1.5388,-1.9154,0.31266,1.019,0 +6.901,-1.0193,-1.5389,-1.916,0.31332,1.0193,0 +6.902,-1.0196,-1.539,-1.9165,0.31398,1.0196,0 +6.903,-1.0199,-1.5392,-1.9171,0.31465,1.0199,0 +6.904,-1.0202,-1.5393,-1.9176,0.31531,1.0202,0 +6.905,-1.0204,-1.5394,-1.9182,0.31597,1.0204,0 +6.906,-1.0207,-1.5395,-1.9187,0.31663,1.0207,0 +6.907,-1.021,-1.5396,-1.9193,0.31729,1.021,0 +6.908,-1.0213,-1.5397,-1.9198,0.31795,1.0213,0 +6.909,-1.0216,-1.5398,-1.9204,0.31861,1.0216,0 +6.91,-1.0219,-1.5399,-1.9209,0.31927,1.0219,0 +6.911,-1.0222,-1.54,-1.9215,0.31993,1.0222,0 +6.912,-1.0225,-1.5402,-1.922,0.32059,1.0225,0 +6.913,-1.0228,-1.5403,-1.9226,0.32125,1.0228,0 +6.914,-1.0231,-1.5404,-1.9231,0.32191,1.0231,0 +6.915,-1.0233,-1.5405,-1.9237,0.32257,1.0233,0 +6.916,-1.0236,-1.5406,-1.9242,0.32323,1.0236,0 +6.917,-1.0239,-1.5407,-1.9248,0.32389,1.0239,0 +6.918,-1.0242,-1.5408,-1.9253,0.32455,1.0242,0 +6.919,-1.0245,-1.5409,-1.9259,0.32521,1.0245,0 +6.92,-1.0248,-1.541,-1.9264,0.32587,1.0248,0 +6.921,-1.0251,-1.5411,-1.927,0.32653,1.0251,0 +6.922,-1.0254,-1.5413,-1.9275,0.3272,1.0254,0 +6.923,-1.0257,-1.5414,-1.9281,0.32786,1.0257,0 +6.924,-1.0259,-1.5415,-1.9286,0.32852,1.0259,0 +6.925,-1.0262,-1.5416,-1.9292,0.32918,1.0262,0 +6.926,-1.0265,-1.5417,-1.9297,0.32984,1.0265,0 +6.927,-1.0268,-1.5418,-1.9303,0.3305,1.0268,0 +6.928,-1.0271,-1.5419,-1.9308,0.33116,1.0271,0 +6.929,-1.0274,-1.542,-1.9314,0.33182,1.0274,0 +6.93,-1.0277,-1.5421,-1.9319,0.33249,1.0277,0 +6.931,-1.028,-1.5423,-1.9325,0.33315,1.028,0 +6.932,-1.0283,-1.5424,-1.933,0.33382,1.0283,0 +6.933,-1.0286,-1.5425,-1.9336,0.3345,1.0286,0 +6.934,-1.0289,-1.5427,-1.9341,0.33517,1.0289,0 +6.935,-1.0293,-1.5428,-1.9347,0.33585,1.0293,0 +6.936,-1.0296,-1.5429,-1.9352,0.33653,1.0296,0 +6.937,-1.0299,-1.5431,-1.9357,0.33722,1.0299,0 +6.938,-1.0303,-1.5432,-1.9363,0.3379,1.0303,0 +6.939,-1.0306,-1.5434,-1.9368,0.33859,1.0306,0 +6.94,-1.031,-1.5435,-1.9373,0.33927,1.031,0 +6.941,-1.0313,-1.5437,-1.9379,0.33996,1.0313,0 +6.942,-1.0316,-1.5438,-1.9384,0.34065,1.0316,0 +6.943,-1.032,-1.544,-1.939,0.34133,1.032,0 +6.944,-1.0323,-1.5441,-1.9395,0.34202,1.0323,0 +6.945,-1.0327,-1.5443,-1.94,0.34271,1.0327,0 +6.946,-1.033,-1.5444,-1.9406,0.34339,1.033,0 +6.947,-1.0333,-1.5446,-1.9411,0.34408,1.0333,0 +6.948,-1.0337,-1.5447,-1.9416,0.34476,1.0337,0 +6.949,-1.034,-1.5449,-1.9422,0.34545,1.034,0 +6.95,-1.0344,-1.545,-1.9427,0.34614,1.0344,0 +6.951,-1.0347,-1.5452,-1.9432,0.34682,1.0347,0 +6.952,-1.0351,-1.5453,-1.9438,0.34751,1.0351,0 +6.953,-1.0354,-1.5455,-1.9443,0.3482,1.0354,0 +6.954,-1.0357,-1.5456,-1.9449,0.34888,1.0357,0 +6.955,-1.0361,-1.5458,-1.9454,0.34957,1.0361,0 +6.956,-1.0364,-1.5459,-1.9459,0.35025,1.0364,0 +6.957,-1.0368,-1.5461,-1.9465,0.35094,1.0368,0 +6.958,-1.0371,-1.5462,-1.947,0.35163,1.0371,0 +6.959,-1.0374,-1.5464,-1.9475,0.35231,1.0374,0 +6.96,-1.0378,-1.5465,-1.9481,0.353,1.0378,0 +6.961,-1.0381,-1.5467,-1.9486,0.35369,1.0381,0 +6.962,-1.0385,-1.5468,-1.9491,0.35437,1.0385,0 +6.963,-1.0388,-1.547,-1.9497,0.35506,1.0388,0 +6.964,-1.0391,-1.5471,-1.9502,0.35574,1.0391,0 +6.965,-1.0395,-1.5473,-1.9508,0.35643,1.0395,0 +6.966,-1.0398,-1.5474,-1.9513,0.35712,1.0398,0 +6.967,-1.0402,-1.5476,-1.9518,0.3578,1.0402,0 +6.968,-1.0405,-1.5477,-1.9524,0.35849,1.0405,0 +6.969,-1.0408,-1.5479,-1.9529,0.35918,1.0408,0 +6.97,-1.0412,-1.548,-1.9534,0.35986,1.0412,0 +6.971,-1.0415,-1.5482,-1.954,0.36055,1.0415,0 +6.972,-1.0419,-1.5483,-1.9545,0.36123,1.0419,0 +6.973,-1.0422,-1.5485,-1.9551,0.36192,1.0422,0 +6.974,-1.0426,-1.5486,-1.9556,0.36261,1.0426,0 +6.975,-1.0429,-1.5488,-1.9561,0.36329,1.0429,0 +6.976,-1.0432,-1.5489,-1.9567,0.36398,1.0432,0 +6.977,-1.0436,-1.5491,-1.9572,0.36467,1.0436,0 +6.978,-1.0439,-1.5492,-1.9577,0.36535,1.0439,0 +6.979,-1.0443,-1.5494,-1.9583,0.36604,1.0443,0 +6.98,-1.0446,-1.5495,-1.9588,0.36672,1.0446,0 +6.981,-1.0449,-1.5497,-1.9593,0.36741,1.0449,0 +6.982,-1.0453,-1.5498,-1.9599,0.3681,1.0453,0 +6.983,-1.0456,-1.55,-1.9604,0.36878,1.0456,0 +6.984,-1.046,-1.5501,-1.961,0.36947,1.046,0 +6.985,-1.0463,-1.5503,-1.9615,0.37016,1.0463,0 +6.986,-1.0466,-1.5504,-1.962,0.37084,1.0466,0 +6.987,-1.047,-1.5506,-1.9626,0.37153,1.047,0 +6.988,-1.0473,-1.5507,-1.9631,0.37221,1.0473,0 +6.989,-1.0477,-1.5509,-1.9636,0.3729,1.0477,0 +6.99,-1.048,-1.551,-1.9642,0.37359,1.048,0 +6.991,-1.0483,-1.5512,-1.9647,0.37427,1.0483,0 +6.992,-1.0487,-1.5513,-1.9652,0.37496,1.0487,0 +6.993,-1.049,-1.5515,-1.9658,0.37565,1.049,0 +6.994,-1.0494,-1.5516,-1.9663,0.37633,1.0494,0 +6.995,-1.0497,-1.5518,-1.9669,0.37702,1.0497,0 +6.996,-1.0501,-1.5519,-1.9674,0.3777,1.0501,0 +6.997,-1.0504,-1.5521,-1.9679,0.37839,1.0504,0 +6.998,-1.0507,-1.5522,-1.9685,0.37908,1.0507,0 +6.999,-1.0511,-1.5524,-1.969,0.37976,1.0511,0 +7,-1.0514,-1.5525,-1.9695,0.38045,1.0514,0 +7.001,-1.0518,-1.5526,-1.9701,0.38114,1.0518,0 +7.002,-1.0521,-1.5528,-1.9706,0.38182,1.0521,0 +7.003,-1.0524,-1.5529,-1.9712,0.38251,1.0524,0 +7.004,-1.0528,-1.5531,-1.9717,0.38319,1.0528,0 +7.005,-1.0531,-1.5532,-1.9722,0.38388,1.0531,0 +7.006,-1.0535,-1.5534,-1.9728,0.38457,1.0535,0 +7.007,-1.0538,-1.5535,-1.9733,0.38525,1.0538,0 +7.008,-1.0541,-1.5537,-1.9738,0.38594,1.0541,0 +7.009,-1.0545,-1.5538,-1.9744,0.38663,1.0545,0 +7.01,-1.0548,-1.554,-1.9749,0.38731,1.0548,0 +7.011,-1.0552,-1.5541,-1.9754,0.388,1.0552,0 +7.012,-1.0555,-1.5543,-1.976,0.38868,1.0555,0 +7.013,-1.0559,-1.5545,-1.9765,0.38936,1.0559,0 +7.014,-1.0562,-1.5546,-1.977,0.39003,1.0562,0 +7.015,-1.0565,-1.5548,-1.9775,0.39069,1.0565,0 +7.016,-1.0569,-1.5549,-1.978,0.39135,1.0569,0 +7.017,-1.0572,-1.5551,-1.9785,0.39201,1.0572,0 +7.018,-1.0576,-1.5553,-1.979,0.39266,1.0576,0 +7.019,-1.058,-1.5554,-1.9795,0.3933,1.058,0 +7.02,-1.0583,-1.5556,-1.9799,0.39394,1.0583,0 +7.021,-1.0587,-1.5558,-1.9804,0.39457,1.0587,0 +7.022,-1.059,-1.5559,-1.9809,0.3952,1.059,0 +7.023,-1.0594,-1.5561,-1.9813,0.39584,1.0594,0 +7.024,-1.0597,-1.5563,-1.9818,0.39647,1.0597,0 +7.025,-1.0601,-1.5564,-1.9823,0.3971,1.0601,0 +7.026,-1.0604,-1.5566,-1.9827,0.39773,1.0604,0 +7.027,-1.0608,-1.5568,-1.9832,0.39837,1.0608,0 +7.028,-1.0612,-1.557,-1.9836,0.399,1.0612,0 +7.029,-1.0615,-1.5571,-1.9841,0.39963,1.0615,0 +7.03,-1.0619,-1.5573,-1.9846,0.40027,1.0619,0 +7.031,-1.0622,-1.5575,-1.985,0.4009,1.0622,0 +7.032,-1.0626,-1.5576,-1.9855,0.40153,1.0626,0 +7.033,-1.0629,-1.5578,-1.986,0.40216,1.0629,0 +7.034,-1.0633,-1.558,-1.9864,0.4028,1.0633,0 +7.035,-1.0637,-1.5581,-1.9869,0.40343,1.0637,0 +7.036,-1.064,-1.5583,-1.9873,0.40406,1.064,0 +7.037,-1.0644,-1.5585,-1.9878,0.40469,1.0644,0 +7.038,-1.0647,-1.5587,-1.9883,0.40533,1.0647,0 +7.039,-1.0651,-1.5588,-1.9887,0.40596,1.0651,0 +7.04,-1.0654,-1.559,-1.9892,0.40659,1.0654,0 +7.041,-1.0658,-1.5592,-1.9896,0.40722,1.0658,0 +7.042,-1.0662,-1.5593,-1.9901,0.40786,1.0662,0 +7.043,-1.0665,-1.5595,-1.9906,0.40849,1.0665,0 +7.044,-1.0669,-1.5597,-1.991,0.40912,1.0669,0 +7.045,-1.0672,-1.5599,-1.9915,0.40975,1.0672,0 +7.046,-1.0676,-1.56,-1.992,0.41039,1.0676,0 +7.047,-1.0679,-1.5602,-1.9924,0.41102,1.0679,0 +7.048,-1.0683,-1.5604,-1.9929,0.41165,1.0683,0 +7.049,-1.0687,-1.5605,-1.9933,0.41229,1.0687,0 +7.05,-1.069,-1.5607,-1.9938,0.41292,1.069,0 +7.051,-1.0694,-1.5609,-1.9943,0.41355,1.0694,0 +7.052,-1.0697,-1.5611,-1.9947,0.41418,1.0697,0 +7.053,-1.0701,-1.5612,-1.9952,0.41482,1.0701,0 +7.054,-1.0704,-1.5614,-1.9956,0.41545,1.0704,0 +7.055,-1.0708,-1.5616,-1.9961,0.41608,1.0708,0 +7.056,-1.0711,-1.5617,-1.9966,0.41671,1.0711,0 +7.057,-1.0715,-1.5619,-1.997,0.41735,1.0715,0 +7.058,-1.0719,-1.5621,-1.9975,0.41798,1.0719,0 +7.059,-1.0722,-1.5622,-1.998,0.41861,1.0722,0 +7.06,-1.0726,-1.5624,-1.9984,0.41924,1.0726,0 +7.061,-1.0729,-1.5626,-1.9989,0.41988,1.0729,0 +7.062,-1.0733,-1.5628,-1.9993,0.42051,1.0733,0 +7.063,-1.0736,-1.5629,-1.9998,0.42114,1.0736,0 +7.064,-1.074,-1.5631,-2.0003,0.42178,1.074,0 +7.065,-1.0744,-1.5633,-2.0007,0.42241,1.0744,0 +7.066,-1.0747,-1.5634,-2.0012,0.42304,1.0747,0 +7.067,-1.0751,-1.5636,-2.0017,0.42367,1.0751,0 +7.068,-1.0754,-1.5638,-2.0021,0.42431,1.0754,0 +7.069,-1.0758,-1.564,-2.0026,0.42494,1.0758,0 +7.07,-1.0761,-1.5641,-2.003,0.42557,1.0761,0 +7.071,-1.0765,-1.5643,-2.0035,0.4262,1.0765,0 +7.072,-1.0769,-1.5645,-2.004,0.42684,1.0769,0 +7.073,-1.0772,-1.5646,-2.0044,0.42747,1.0772,0 +7.074,-1.0776,-1.5648,-2.0049,0.4281,1.0776,0 +7.075,-1.0779,-1.565,-2.0053,0.42873,1.0779,0 +7.076,-1.0783,-1.5652,-2.0058,0.42937,1.0783,0 +7.077,-1.0786,-1.5653,-2.0063,0.43,1.0786,0 +7.078,-1.079,-1.5655,-2.0067,0.43063,1.079,0 +7.079,-1.0794,-1.5657,-2.0072,0.43126,1.0794,0 +7.08,-1.0797,-1.5658,-2.0077,0.4319,1.0797,0 +7.081,-1.0801,-1.566,-2.0081,0.43253,1.0801,0 +7.082,-1.0804,-1.5662,-2.0086,0.43316,1.0804,0 +7.083,-1.0808,-1.5663,-2.009,0.4338,1.0808,0 +7.084,-1.0811,-1.5665,-2.0095,0.43443,1.0811,0 +7.085,-1.0815,-1.5667,-2.01,0.43506,1.0815,0 +7.086,-1.0818,-1.5669,-2.0104,0.43569,1.0818,0 +7.087,-1.0822,-1.567,-2.0109,0.43633,1.0822,0 +7.088,-1.0826,-1.5672,-2.0113,0.43696,1.0826,0 +7.089,-1.0829,-1.5674,-2.0118,0.43759,1.0829,0 +7.09,-1.0833,-1.5675,-2.0123,0.43822,1.0833,0 +7.091,-1.0836,-1.5677,-2.0127,0.43886,1.0836,0 +7.092,-1.084,-1.5679,-2.0132,0.43949,1.084,0 +7.093,-1.0843,-1.5681,-2.0137,0.44012,1.0843,0 +7.094,-1.0847,-1.5682,-2.0141,0.44075,1.0847,0 +7.095,-1.0851,-1.5684,-2.0146,0.44139,1.0851,0 +7.096,-1.0854,-1.5686,-2.015,0.44202,1.0854,0 +7.097,-1.0858,-1.5688,-2.0155,0.44264,1.0858,0 +7.098,-1.0861,-1.5689,-2.0159,0.44327,1.0861,0 +7.099,-1.0865,-1.5691,-2.0164,0.4439,1.0865,0 +7.1,-1.0869,-1.5693,-2.0168,0.44452,1.0869,0 +7.101,-1.0872,-1.5695,-2.0172,0.44514,1.0872,0 +7.102,-1.0876,-1.5697,-2.0176,0.44576,1.0876,0 +7.103,-1.088,-1.5699,-2.0181,0.44638,1.088,0 +7.104,-1.0884,-1.5701,-2.0185,0.447,1.0884,0 +7.105,-1.0887,-1.5703,-2.0189,0.44762,1.0887,0 +7.106,-1.0891,-1.5705,-2.0193,0.44823,1.0891,0 +7.107,-1.0895,-1.5707,-2.0197,0.44885,1.0895,0 +7.108,-1.0898,-1.5709,-2.0201,0.44947,1.0898,0 +7.109,-1.0902,-1.5711,-2.0206,0.45009,1.0902,0 +7.11,-1.0906,-1.5713,-2.021,0.4507,1.0906,0 +7.111,-1.091,-1.5715,-2.0214,0.45132,1.091,0 +7.112,-1.0913,-1.5717,-2.0218,0.45194,1.0913,0 +7.113,-1.0917,-1.5719,-2.0222,0.45256,1.0917,0 +7.114,-1.0921,-1.5721,-2.0226,0.45317,1.0921,0 +7.115,-1.0925,-1.5723,-2.0231,0.45379,1.0925,0 +7.116,-1.0928,-1.5725,-2.0235,0.45441,1.0928,0 +7.117,-1.0932,-1.5727,-2.0239,0.45503,1.0932,0 +7.118,-1.0936,-1.5729,-2.0243,0.45564,1.0936,0 +7.119,-1.0939,-1.5731,-2.0247,0.45626,1.0939,0 +7.12,-1.0943,-1.5733,-2.0251,0.45688,1.0943,0 +7.121,-1.0947,-1.5735,-2.0255,0.4575,1.0947,0 +7.122,-1.0951,-1.5737,-2.026,0.45811,1.0951,0 +7.123,-1.0954,-1.574,-2.0264,0.45873,1.0954,0 +7.124,-1.0958,-1.5742,-2.0268,0.45935,1.0958,0 +7.125,-1.0962,-1.5744,-2.0272,0.45997,1.0962,0 +7.126,-1.0965,-1.5746,-2.0276,0.46058,1.0965,0 +7.127,-1.0969,-1.5748,-2.028,0.4612,1.0969,0 +7.128,-1.0973,-1.575,-2.0284,0.46182,1.0973,0 +7.129,-1.0977,-1.5752,-2.0289,0.46244,1.0977,0 +7.13,-1.098,-1.5754,-2.0293,0.46305,1.098,0 +7.131,-1.0984,-1.5756,-2.0297,0.46367,1.0984,0 +7.132,-1.0988,-1.5758,-2.0301,0.46429,1.0988,0 +7.133,-1.0992,-1.576,-2.0305,0.4649,1.0992,0 +7.134,-1.0995,-1.5762,-2.0309,0.46552,1.0995,0 +7.135,-1.0999,-1.5764,-2.0314,0.46614,1.0999,0 +7.136,-1.1003,-1.5766,-2.0318,0.46676,1.1003,0 +7.137,-1.1006,-1.5768,-2.0322,0.46737,1.1006,0 +7.138,-1.101,-1.577,-2.0326,0.46799,1.101,0 +7.139,-1.1014,-1.5772,-2.033,0.46861,1.1014,0 +7.14,-1.1018,-1.5774,-2.0334,0.46923,1.1018,0 +7.141,-1.1021,-1.5776,-2.0338,0.46984,1.1021,0 +7.142,-1.1025,-1.5778,-2.0343,0.47046,1.1025,0 +7.143,-1.1029,-1.578,-2.0347,0.47108,1.1029,0 +7.144,-1.1033,-1.5782,-2.0351,0.4717,1.1033,0 +7.145,-1.1036,-1.5784,-2.0355,0.47231,1.1036,0 +7.146,-1.104,-1.5786,-2.0359,0.47293,1.104,0 +7.147,-1.1044,-1.5788,-2.0363,0.47355,1.1044,0 +7.148,-1.1047,-1.579,-2.0368,0.47417,1.1047,0 +7.149,-1.1051,-1.5792,-2.0372,0.47478,1.1051,0 +7.15,-1.1055,-1.5794,-2.0376,0.4754,1.1055,0 +7.151,-1.1059,-1.5796,-2.038,0.47602,1.1059,0 +7.152,-1.1062,-1.5798,-2.0384,0.47664,1.1062,0 +7.153,-1.1066,-1.58,-2.0388,0.47725,1.1066,0 +7.154,-1.107,-1.5802,-2.0392,0.47787,1.107,0 +7.155,-1.1074,-1.5804,-2.0397,0.47849,1.1074,0 +7.156,-1.1077,-1.5806,-2.0401,0.47911,1.1077,0 +7.157,-1.1081,-1.5808,-2.0405,0.47972,1.1081,0 +7.158,-1.1085,-1.581,-2.0409,0.48034,1.1085,0 +7.159,-1.1088,-1.5812,-2.0413,0.48096,1.1088,0 +7.16,-1.1092,-1.5814,-2.0417,0.48158,1.1092,0 +7.161,-1.1096,-1.5816,-2.0422,0.48219,1.1096,0 +7.162,-1.11,-1.5818,-2.0426,0.48281,1.11,0 +7.163,-1.1103,-1.582,-2.043,0.48343,1.1103,0 +7.164,-1.1107,-1.5822,-2.0434,0.48405,1.1107,0 +7.165,-1.1111,-1.5824,-2.0438,0.48466,1.1111,0 +7.166,-1.1114,-1.5826,-2.0442,0.48528,1.1114,0 +7.167,-1.1118,-1.5828,-2.0446,0.4859,1.1118,0 +7.168,-1.1122,-1.5831,-2.0451,0.48652,1.1122,0 +7.169,-1.1126,-1.5833,-2.0455,0.48713,1.1126,0 +7.17,-1.1129,-1.5835,-2.0459,0.48775,1.1129,0 +7.171,-1.1133,-1.5837,-2.0463,0.48837,1.1133,0 +7.172,-1.1137,-1.5839,-2.0467,0.48899,1.1137,0 +7.173,-1.1141,-1.5841,-2.0471,0.4896,1.1141,0 +7.174,-1.1144,-1.5843,-2.0475,0.49022,1.1144,0 +7.175,-1.1148,-1.5845,-2.048,0.49084,1.1148,0 +7.176,-1.1152,-1.5847,-2.0484,0.49146,1.1152,0 +7.177,-1.1155,-1.5849,-2.0488,0.49207,1.1155,0 +7.178,-1.1159,-1.5851,-2.0492,0.49269,1.1159,0 +7.179,-1.1163,-1.5853,-2.0496,0.4933,1.1163,0 +7.18,-1.1167,-1.5855,-2.05,0.49392,1.1167,0 +7.181,-1.117,-1.5857,-2.0504,0.49453,1.117,0 +7.182,-1.1174,-1.5859,-2.0508,0.49514,1.1174,0 +7.183,-1.1178,-1.5861,-2.0512,0.49574,1.1178,0 +7.184,-1.1182,-1.5864,-2.0516,0.49635,1.1182,0 +7.185,-1.1186,-1.5866,-2.0519,0.49695,1.1186,0 +7.186,-1.1189,-1.5868,-2.0523,0.49756,1.1189,0 +7.187,-1.1193,-1.5871,-2.0527,0.49816,1.1193,0 +7.188,-1.1197,-1.5873,-2.0531,0.49876,1.1197,0 +7.189,-1.1201,-1.5875,-2.0534,0.49936,1.1201,0 +7.19,-1.1205,-1.5878,-2.0538,0.49996,1.1205,0 +7.191,-1.1208,-1.588,-2.0542,0.50056,1.1208,0 +7.192,-1.1212,-1.5882,-2.0545,0.50116,1.1212,0 +7.193,-1.1216,-1.5885,-2.0549,0.50176,1.1216,0 +7.194,-1.122,-1.5887,-2.0553,0.50236,1.122,0 +7.195,-1.1224,-1.5889,-2.0556,0.50296,1.1224,0 +7.196,-1.1227,-1.5891,-2.056,0.50356,1.1227,0 +7.197,-1.1231,-1.5894,-2.0564,0.50417,1.1231,0 +7.198,-1.1235,-1.5896,-2.0567,0.50477,1.1235,0 +7.199,-1.1239,-1.5898,-2.0571,0.50537,1.1239,0 +7.2,-1.1243,-1.5901,-2.0575,0.50597,1.1243,0 +7.201,-1.1246,-1.5903,-2.0579,0.50657,1.1246,0 +7.202,-1.125,-1.5905,-2.0582,0.50717,1.125,0 +7.203,-1.1254,-1.5908,-2.0586,0.50777,1.1254,0 +7.204,-1.1258,-1.591,-2.059,0.50837,1.1258,0 +7.205,-1.1262,-1.5912,-2.0593,0.50897,1.1262,0 +7.206,-1.1265,-1.5915,-2.0597,0.50957,1.1265,0 +7.207,-1.1269,-1.5917,-2.0601,0.51017,1.1269,0 +7.208,-1.1273,-1.5919,-2.0604,0.51078,1.1273,0 +7.209,-1.1277,-1.5922,-2.0608,0.51138,1.1277,0 +7.21,-1.1281,-1.5924,-2.0612,0.51198,1.1281,0 +7.211,-1.1284,-1.5926,-2.0615,0.51258,1.1284,0 +7.212,-1.1288,-1.5929,-2.0619,0.51318,1.1288,0 +7.213,-1.1292,-1.5931,-2.0623,0.51378,1.1292,0 +7.214,-1.1296,-1.5933,-2.0626,0.51438,1.1296,0 +7.215,-1.13,-1.5936,-2.063,0.51498,1.13,0 +7.216,-1.1303,-1.5938,-2.0634,0.51558,1.1303,0 +7.217,-1.1307,-1.594,-2.0638,0.51618,1.1307,0 +7.218,-1.1311,-1.5943,-2.0641,0.51678,1.1311,0 +7.219,-1.1315,-1.5945,-2.0645,0.51738,1.1315,0 +7.22,-1.1319,-1.5947,-2.0649,0.51799,1.1319,0 +7.221,-1.1322,-1.595,-2.0652,0.51859,1.1322,0 +7.222,-1.1326,-1.5952,-2.0656,0.51919,1.1326,0 +7.223,-1.133,-1.5954,-2.066,0.51979,1.133,0 +7.224,-1.1334,-1.5956,-2.0663,0.52039,1.1334,0 +7.225,-1.1338,-1.5959,-2.0667,0.52099,1.1338,0 +7.226,-1.1341,-1.5961,-2.0671,0.52159,1.1341,0 +7.227,-1.1345,-1.5963,-2.0674,0.52219,1.1345,0 +7.228,-1.1349,-1.5966,-2.0678,0.52279,1.1349,0 +7.229,-1.1353,-1.5968,-2.0682,0.52339,1.1353,0 +7.23,-1.1357,-1.597,-2.0685,0.52399,1.1357,0 +7.231,-1.136,-1.5973,-2.0689,0.52459,1.136,0 +7.232,-1.1364,-1.5975,-2.0693,0.5252,1.1364,0 +7.233,-1.1368,-1.5977,-2.0697,0.5258,1.1368,0 +7.234,-1.1372,-1.598,-2.07,0.5264,1.1372,0 +7.235,-1.1376,-1.5982,-2.0704,0.527,1.1376,0 +7.236,-1.1379,-1.5984,-2.0708,0.5276,1.1379,0 +7.237,-1.1383,-1.5987,-2.0711,0.5282,1.1383,0 +7.238,-1.1387,-1.5989,-2.0715,0.5288,1.1387,0 +7.239,-1.1391,-1.5991,-2.0719,0.5294,1.1391,0 +7.24,-1.1395,-1.5994,-2.0722,0.53,1.1395,0 +7.241,-1.1398,-1.5996,-2.0726,0.5306,1.1398,0 +7.242,-1.1402,-1.5998,-2.073,0.5312,1.1402,0 +7.243,-1.1406,-1.6001,-2.0733,0.53181,1.1406,0 +7.244,-1.141,-1.6003,-2.0737,0.53241,1.141,0 +7.245,-1.1414,-1.6005,-2.0741,0.53301,1.1414,0 +7.246,-1.1417,-1.6008,-2.0744,0.53361,1.1417,0 +7.247,-1.1421,-1.601,-2.0748,0.53421,1.1421,0 +7.248,-1.1425,-1.6012,-2.0752,0.53481,1.1425,0 +7.249,-1.1429,-1.6015,-2.0755,0.53541,1.1429,0 +7.25,-1.1433,-1.6017,-2.0759,0.53601,1.1433,0 +7.251,-1.1436,-1.6019,-2.0763,0.53661,1.1436,0 +7.252,-1.144,-1.6022,-2.0767,0.53721,1.144,0 +7.253,-1.1444,-1.6024,-2.077,0.53781,1.1444,0 +7.254,-1.1448,-1.6026,-2.0774,0.53841,1.1448,0 +7.255,-1.1452,-1.6028,-2.0778,0.53902,1.1452,0 +7.256,-1.1455,-1.6031,-2.0781,0.53962,1.1455,0 +7.257,-1.1459,-1.6033,-2.0785,0.54022,1.1459,0 +7.258,-1.1463,-1.6035,-2.0789,0.54082,1.1463,0 +7.259,-1.1467,-1.6038,-2.0792,0.54142,1.1467,0 +7.26,-1.1471,-1.604,-2.0796,0.54202,1.1471,0 +7.261,-1.1474,-1.6042,-2.08,0.54261,1.1474,0 +7.262,-1.1478,-1.6045,-2.0803,0.54319,1.1478,0 +7.263,-1.1482,-1.6047,-2.0807,0.54377,1.1482,0 +7.264,-1.1485,-1.6049,-2.081,0.54433,1.1485,0 +7.265,-1.1489,-1.6052,-2.0813,0.54489,1.1489,0 +7.266,-1.1493,-1.6054,-2.0816,0.54543,1.1493,0 +7.267,-1.1496,-1.6056,-2.0819,0.54597,1.1496,0 +7.268,-1.1499,-1.6058,-2.0822,0.5465,1.1499,0 +7.269,-1.1503,-1.6061,-2.0825,0.54702,1.1503,0 +7.27,-1.1506,-1.6063,-2.0828,0.54753,1.1506,0 +7.271,-1.151,-1.6065,-2.0831,0.54804,1.151,0 +7.272,-1.1513,-1.6067,-2.0834,0.54855,1.1513,0 +7.273,-1.1516,-1.607,-2.0837,0.54906,1.1516,0 +7.274,-1.152,-1.6072,-2.084,0.54957,1.152,0 +7.275,-1.1523,-1.6074,-2.0843,0.55008,1.1523,0 +7.276,-1.1527,-1.6076,-2.0845,0.55059,1.1527,0 +7.277,-1.153,-1.6079,-2.0848,0.5511,1.153,0 +7.278,-1.1533,-1.6081,-2.0851,0.55161,1.1533,0 +7.279,-1.1537,-1.6083,-2.0854,0.55212,1.1537,0 +7.28,-1.154,-1.6085,-2.0857,0.55264,1.154,0 +7.281,-1.1544,-1.6088,-2.086,0.55315,1.1544,0 +7.282,-1.1547,-1.609,-2.0863,0.55366,1.1547,0 +7.283,-1.155,-1.6092,-2.0865,0.55417,1.155,0 +7.284,-1.1554,-1.6094,-2.0868,0.55468,1.1554,0 +7.285,-1.1557,-1.6097,-2.0871,0.55519,1.1557,0 +7.286,-1.156,-1.6099,-2.0874,0.5557,1.156,0 +7.287,-1.1564,-1.6101,-2.0877,0.55621,1.1564,0 +7.288,-1.1567,-1.6103,-2.088,0.55672,1.1567,0 +7.289,-1.1571,-1.6106,-2.0883,0.55723,1.1571,0 +7.29,-1.1574,-1.6108,-2.0885,0.55774,1.1574,0 +7.291,-1.1577,-1.611,-2.0888,0.55825,1.1577,0 +7.292,-1.1581,-1.6112,-2.0891,0.55877,1.1581,0 +7.293,-1.1584,-1.6115,-2.0894,0.55928,1.1584,0 +7.294,-1.1588,-1.6117,-2.0897,0.55979,1.1588,0 +7.295,-1.1591,-1.6119,-2.09,0.5603,1.1591,0 +7.296,-1.1594,-1.6121,-2.0903,0.56081,1.1594,0 +7.297,-1.1598,-1.6124,-2.0905,0.56132,1.1598,0 +7.298,-1.1601,-1.6126,-2.0908,0.56183,1.1601,0 +7.299,-1.1604,-1.6128,-2.0911,0.56234,1.1604,0 +7.3,-1.1608,-1.613,-2.0914,0.56285,1.1608,0 +7.301,-1.1611,-1.6133,-2.0917,0.56336,1.1611,0 +7.302,-1.1615,-1.6135,-2.092,0.56387,1.1615,0 +7.303,-1.1618,-1.6137,-2.0923,0.56438,1.1618,0 +7.304,-1.1621,-1.6139,-2.0925,0.5649,1.1621,0 +7.305,-1.1625,-1.6142,-2.0928,0.56541,1.1625,0 +7.306,-1.1628,-1.6144,-2.0931,0.56592,1.1628,0 +7.307,-1.1632,-1.6146,-2.0934,0.56643,1.1632,0 +7.308,-1.1635,-1.6148,-2.0937,0.56694,1.1635,0 +7.309,-1.1638,-1.6151,-2.094,0.56745,1.1638,0 +7.31,-1.1642,-1.6153,-2.0943,0.56796,1.1642,0 +7.311,-1.1645,-1.6155,-2.0945,0.56847,1.1645,0 +7.312,-1.1648,-1.6157,-2.0948,0.56898,1.1648,0 +7.313,-1.1652,-1.616,-2.0951,0.56949,1.1652,0 +7.314,-1.1655,-1.6162,-2.0954,0.57,1.1655,0 +7.315,-1.1659,-1.6164,-2.0957,0.57052,1.1659,0 +7.316,-1.1662,-1.6166,-2.096,0.57103,1.1662,0 +7.317,-1.1665,-1.6169,-2.0963,0.57154,1.1665,0 +7.318,-1.1669,-1.6171,-2.0965,0.57205,1.1669,0 +7.319,-1.1672,-1.6173,-2.0968,0.57256,1.1672,0 +7.32,-1.1676,-1.6175,-2.0971,0.57307,1.1676,0 +7.321,-1.1679,-1.6178,-2.0974,0.57358,1.1679,0 +7.322,-1.1682,-1.618,-2.0977,0.57409,1.1682,0 +7.323,-1.1686,-1.6182,-2.098,0.5746,1.1686,0 +7.324,-1.1689,-1.6184,-2.0983,0.57511,1.1689,0 +7.325,-1.1692,-1.6187,-2.0985,0.57562,1.1692,0 +7.326,-1.1696,-1.6189,-2.0988,0.57613,1.1696,0 +7.327,-1.1699,-1.6191,-2.0991,0.57665,1.1699,0 +7.328,-1.1703,-1.6193,-2.0994,0.57716,1.1703,0 +7.329,-1.1706,-1.6196,-2.0997,0.57767,1.1706,0 +7.33,-1.1709,-1.6198,-2.1,0.57818,1.1709,0 +7.331,-1.1713,-1.62,-2.1003,0.57869,1.1713,0 +7.332,-1.1716,-1.6203,-2.1005,0.5792,1.1716,0 +7.333,-1.172,-1.6205,-2.1008,0.57971,1.172,0 +7.334,-1.1723,-1.6207,-2.1011,0.58022,1.1723,0 +7.335,-1.1726,-1.6209,-2.1014,0.58073,1.1726,0 +7.336,-1.173,-1.6212,-2.1017,0.58124,1.173,0 +7.337,-1.1733,-1.6214,-2.102,0.58175,1.1733,0 +7.338,-1.1736,-1.6216,-2.1023,0.58226,1.1736,0 +7.339,-1.174,-1.6218,-2.1025,0.58278,1.174,0 +7.34,-1.1743,-1.6221,-2.1028,0.58329,1.1743,0 +7.341,-1.1747,-1.6223,-2.1031,0.5838,1.1747,0 +7.342,-1.175,-1.6225,-2.1034,0.58431,1.175,0 +7.343,-1.1753,-1.6227,-2.1037,0.58482,1.1753,0 +7.344,-1.1757,-1.623,-2.104,0.58533,1.1757,0 +7.345,-1.176,-1.6232,-2.1042,0.58583,1.176,0 +7.346,-1.1763,-1.6234,-2.1045,0.58634,1.1763,0 +7.347,-1.1767,-1.6236,-2.1048,0.58684,1.1767,0 +7.348,-1.177,-1.6239,-2.1051,0.58734,1.177,0 +7.349,-1.1773,-1.6241,-2.1053,0.58783,1.1773,0 +7.35,-1.1776,-1.6243,-2.1056,0.58833,1.1776,0 +7.351,-1.178,-1.6246,-2.1058,0.58882,1.178,0 +7.352,-1.1783,-1.6248,-2.1061,0.58931,1.1783,0 +7.353,-1.1786,-1.6251,-2.1063,0.5898,1.1786,0 +7.354,-1.1789,-1.6253,-2.1066,0.59029,1.1789,0 +7.355,-1.1792,-1.6255,-2.1068,0.59078,1.1792,0 +7.356,-1.1796,-1.6258,-2.1071,0.59127,1.1796,0 +7.357,-1.1799,-1.626,-2.1073,0.59175,1.1799,0 +7.358,-1.1802,-1.6263,-2.1076,0.59224,1.1802,0 +7.359,-1.1805,-1.6265,-2.1078,0.59273,1.1805,0 +7.36,-1.1808,-1.6267,-2.1081,0.59322,1.1808,0 +7.361,-1.1812,-1.627,-2.1083,0.59371,1.1812,0 +7.362,-1.1815,-1.6272,-2.1086,0.5942,1.1815,0 +7.363,-1.1818,-1.6275,-2.1088,0.59468,1.1818,0 +7.364,-1.1821,-1.6277,-2.1091,0.59517,1.1821,0 +7.365,-1.1824,-1.628,-2.1093,0.59566,1.1824,0 +7.366,-1.1828,-1.6282,-2.1096,0.59615,1.1828,0 +7.367,-1.1831,-1.6284,-2.1098,0.59664,1.1831,0 +7.368,-1.1834,-1.6287,-2.11,0.59713,1.1834,0 +7.369,-1.1837,-1.6289,-2.1103,0.59761,1.1837,0 +7.37,-1.184,-1.6292,-2.1105,0.5981,1.184,0 +7.371,-1.1843,-1.6294,-2.1108,0.59859,1.1843,0 +7.372,-1.1847,-1.6296,-2.111,0.59908,1.1847,0 +7.373,-1.185,-1.6299,-2.1113,0.59957,1.185,0 +7.374,-1.1853,-1.6301,-2.1115,0.60006,1.1853,0 +7.375,-1.1856,-1.6304,-2.1118,0.60054,1.1856,0 +7.376,-1.1859,-1.6306,-2.112,0.60103,1.1859,0 +7.377,-1.1863,-1.6308,-2.1123,0.60152,1.1863,0 +7.378,-1.1866,-1.6311,-2.1125,0.60201,1.1866,0 +7.379,-1.1869,-1.6313,-2.1128,0.6025,1.1869,0 +7.38,-1.1872,-1.6316,-2.113,0.60299,1.1872,0 +7.381,-1.1875,-1.6318,-2.1133,0.60347,1.1875,0 +7.382,-1.1878,-1.632,-2.1135,0.60396,1.1878,0 +7.383,-1.1882,-1.6323,-2.1138,0.60445,1.1882,0 +7.384,-1.1885,-1.6325,-2.114,0.60494,1.1885,0 +7.385,-1.1888,-1.6328,-2.1143,0.60543,1.1888,0 +7.386,-1.1891,-1.633,-2.1145,0.60592,1.1891,0 +7.387,-1.1894,-1.6332,-2.1148,0.6064,1.1894,0 +7.388,-1.1898,-1.6335,-2.115,0.60689,1.1898,0 +7.389,-1.1901,-1.6337,-2.1153,0.60738,1.1901,0 +7.39,-1.1904,-1.634,-2.1155,0.60787,1.1904,0 +7.391,-1.1907,-1.6342,-2.1157,0.60836,1.1907,0 +7.392,-1.191,-1.6344,-2.116,0.60885,1.191,0 +7.393,-1.1914,-1.6347,-2.1162,0.60933,1.1914,0 +7.394,-1.1917,-1.6349,-2.1165,0.60982,1.1917,0 +7.395,-1.192,-1.6352,-2.1167,0.61031,1.192,0 +7.396,-1.1923,-1.6354,-2.117,0.6108,1.1923,0 +7.397,-1.1926,-1.6356,-2.1172,0.61129,1.1926,0 +7.398,-1.1929,-1.6359,-2.1175,0.61178,1.1929,0 +7.399,-1.1933,-1.6361,-2.1177,0.61226,1.1933,0 +7.4,-1.1936,-1.6364,-2.118,0.61275,1.1936,0 +7.401,-1.1939,-1.6366,-2.1182,0.61324,1.1939,0 +7.402,-1.1942,-1.6368,-2.1185,0.61373,1.1942,0 +7.403,-1.1945,-1.6371,-2.1187,0.61422,1.1945,0 +7.404,-1.1949,-1.6373,-2.119,0.61471,1.1949,0 +7.405,-1.1952,-1.6376,-2.1192,0.61519,1.1952,0 +7.406,-1.1955,-1.6378,-2.1195,0.61568,1.1955,0 +7.407,-1.1958,-1.638,-2.1197,0.61617,1.1958,0 +7.408,-1.1961,-1.6383,-2.12,0.61666,1.1961,0 +7.409,-1.1965,-1.6385,-2.1202,0.61715,1.1965,0 +7.41,-1.1968,-1.6388,-2.1205,0.61764,1.1968,0 +7.411,-1.1971,-1.639,-2.1207,0.61812,1.1971,0 +7.412,-1.1974,-1.6393,-2.121,0.61861,1.1974,0 +7.413,-1.1977,-1.6395,-2.1212,0.6191,1.1977,0 +7.414,-1.198,-1.6397,-2.1214,0.61959,1.198,0 +7.415,-1.1984,-1.64,-2.1217,0.62008,1.1984,0 +7.416,-1.1987,-1.6402,-2.1219,0.62057,1.1987,0 +7.417,-1.199,-1.6405,-2.1222,0.62105,1.199,0 +7.418,-1.1993,-1.6407,-2.1224,0.62154,1.1993,0 +7.419,-1.1996,-1.6409,-2.1227,0.62203,1.1996,0 +7.42,-1.2,-1.6412,-2.1229,0.62252,1.2,0 +7.421,-1.2003,-1.6414,-2.1232,0.62301,1.2003,0 +7.422,-1.2006,-1.6417,-2.1234,0.6235,1.2006,0 +7.423,-1.2009,-1.6419,-2.1237,0.62398,1.2009,0 +7.424,-1.2012,-1.6421,-2.1239,0.62447,1.2012,0 +7.425,-1.2016,-1.6424,-2.1242,0.62496,1.2016,0 +7.426,-1.2019,-1.6426,-2.1244,0.62545,1.2019,0 +7.427,-1.2022,-1.6429,-2.1247,0.62592,1.2022,0 +7.428,-1.2025,-1.6431,-2.1249,0.62639,1.2025,0 +7.429,-1.2028,-1.6433,-2.1251,0.62685,1.2028,0 +7.43,-1.203,-1.6435,-2.1253,0.6273,1.203,0 +7.431,-1.2033,-1.6438,-2.1256,0.62773,1.2033,0 +7.432,-1.2036,-1.644,-2.1258,0.62816,1.2036,0 +7.433,-1.2038,-1.6442,-2.126,0.62858,1.2038,0 +7.434,-1.2041,-1.6444,-2.1262,0.62899,1.2041,0 +7.435,-1.2043,-1.6446,-2.1263,0.62939,1.2043,0 +7.436,-1.2046,-1.6449,-2.1265,0.62978,1.2046,0 +7.437,-1.2048,-1.6451,-2.1267,0.63017,1.2048,0 +7.438,-1.205,-1.6453,-2.1269,0.63056,1.205,0 +7.439,-1.2053,-1.6455,-2.1271,0.63095,1.2053,0 +7.44,-1.2055,-1.6457,-2.1272,0.63134,1.2055,0 +7.441,-1.2057,-1.6459,-2.1274,0.63174,1.2057,0 +7.442,-1.2059,-1.6461,-2.1276,0.63213,1.2059,0 +7.443,-1.2062,-1.6463,-2.1278,0.63252,1.2062,0 +7.444,-1.2064,-1.6465,-2.128,0.63291,1.2064,0 +7.445,-1.2066,-1.6467,-2.1281,0.6333,1.2066,0 +7.446,-1.2069,-1.647,-2.1283,0.63369,1.2069,0 +7.447,-1.2071,-1.6472,-2.1285,0.63408,1.2071,0 +7.448,-1.2073,-1.6474,-2.1287,0.63447,1.2073,0 +7.449,-1.2076,-1.6476,-2.1289,0.63487,1.2076,0 +7.45,-1.2078,-1.6478,-2.1291,0.63526,1.2078,0 +7.451,-1.208,-1.648,-2.1292,0.63565,1.208,0 +7.452,-1.2083,-1.6482,-2.1294,0.63604,1.2083,0 +7.453,-1.2085,-1.6484,-2.1296,0.63643,1.2085,0 +7.454,-1.2087,-1.6486,-2.1298,0.63682,1.2087,0 +7.455,-1.209,-1.6489,-2.13,0.63721,1.209,0 +7.456,-1.2092,-1.6491,-2.1301,0.6376,1.2092,0 +7.457,-1.2094,-1.6493,-2.1303,0.638,1.2094,0 +7.458,-1.2096,-1.6495,-2.1305,0.63839,1.2096,0 +7.459,-1.2099,-1.6497,-2.1307,0.63878,1.2099,0 +7.46,-1.2101,-1.6499,-2.1309,0.63917,1.2101,0 +7.461,-1.2103,-1.6501,-2.131,0.63956,1.2103,0 +7.462,-1.2106,-1.6503,-2.1312,0.63995,1.2106,0 +7.463,-1.2108,-1.6505,-2.1314,0.64034,1.2108,0 +7.464,-1.211,-1.6507,-2.1316,0.64073,1.211,0 +7.465,-1.2113,-1.651,-2.1318,0.64113,1.2113,0 +7.466,-1.2115,-1.6512,-2.1319,0.64152,1.2115,0 +7.467,-1.2117,-1.6514,-2.1321,0.64191,1.2117,0 +7.468,-1.212,-1.6516,-2.1323,0.6423,1.212,0 +7.469,-1.2122,-1.6518,-2.1325,0.64269,1.2122,0 +7.47,-1.2124,-1.652,-2.1327,0.64308,1.2124,0 +7.471,-1.2126,-1.6522,-2.1328,0.64347,1.2126,0 +7.472,-1.2129,-1.6524,-2.133,0.64386,1.2129,0 +7.473,-1.2131,-1.6526,-2.1332,0.64426,1.2131,0 +7.474,-1.2133,-1.6529,-2.1334,0.64465,1.2133,0 +7.475,-1.2136,-1.6531,-2.1336,0.64504,1.2136,0 +7.476,-1.2138,-1.6533,-2.1338,0.64543,1.2138,0 +7.477,-1.214,-1.6535,-2.1339,0.64582,1.214,0 +7.478,-1.2143,-1.6537,-2.1341,0.64621,1.2143,0 +7.479,-1.2145,-1.6539,-2.1343,0.6466,1.2145,0 +7.48,-1.2147,-1.6541,-2.1345,0.64699,1.2147,0 +7.481,-1.215,-1.6543,-2.1347,0.64739,1.215,0 +7.482,-1.2152,-1.6545,-2.1348,0.64778,1.2152,0 +7.483,-1.2154,-1.6547,-2.135,0.64817,1.2154,0 +7.484,-1.2157,-1.655,-2.1352,0.64856,1.2157,0 +7.485,-1.2159,-1.6552,-2.1354,0.64895,1.2159,0 +7.486,-1.2161,-1.6554,-2.1356,0.64934,1.2161,0 +7.487,-1.2163,-1.6556,-2.1357,0.64973,1.2163,0 +7.488,-1.2166,-1.6558,-2.1359,0.65012,1.2166,0 +7.489,-1.2168,-1.656,-2.1361,0.65052,1.2168,0 +7.49,-1.217,-1.6562,-2.1363,0.65091,1.217,0 +7.491,-1.2173,-1.6564,-2.1365,0.6513,1.2173,0 +7.492,-1.2175,-1.6566,-2.1366,0.65169,1.2175,0 +7.493,-1.2177,-1.6569,-2.1368,0.65208,1.2177,0 +7.494,-1.218,-1.6571,-2.137,0.65247,1.218,0 +7.495,-1.2182,-1.6573,-2.1372,0.65286,1.2182,0 +7.496,-1.2184,-1.6575,-2.1374,0.65325,1.2184,0 +7.497,-1.2187,-1.6577,-2.1375,0.65365,1.2187,0 +7.498,-1.2189,-1.6579,-2.1377,0.65404,1.2189,0 +7.499,-1.2191,-1.6581,-2.1379,0.65443,1.2191,0 +7.5,-1.2194,-1.6583,-2.1381,0.65482,1.2194,0 +7.501,-1.2196,-1.6585,-2.1383,0.65521,1.2196,0 +7.502,-1.2198,-1.6587,-2.1384,0.6556,1.2198,0 +7.503,-1.22,-1.659,-2.1386,0.65599,1.22,0 +7.504,-1.2203,-1.6592,-2.1388,0.65638,1.2203,0 +7.505,-1.2205,-1.6594,-2.139,0.65678,1.2205,0 +7.506,-1.2207,-1.6596,-2.1392,0.65717,1.2207,0 +7.507,-1.221,-1.6598,-2.1394,0.65756,1.221,0 +7.508,-1.2212,-1.66,-2.1395,0.65795,1.2212,0 +7.509,-1.2214,-1.6602,-2.1397,0.65834,1.2214,0 +7.51,-1.2217,-1.6604,-2.1399,0.65872,1.2217,0 +7.511,-1.2219,-1.6606,-2.1401,0.6591,1.2219,0 +7.512,-1.2221,-1.6608,-2.1402,0.65948,1.2221,0 +7.513,-1.2223,-1.661,-2.1404,0.65984,1.2223,0 +7.514,-1.2225,-1.6612,-2.1406,0.6602,1.2225,0 +7.515,-1.2227,-1.6614,-2.1407,0.66056,1.2227,0 +7.516,-1.2229,-1.6616,-2.1409,0.66091,1.2229,0 +7.517,-1.223,-1.6618,-2.141,0.66126,1.223,0 +7.518,-1.2232,-1.662,-2.1412,0.6616,1.2232,0 +7.519,-1.2234,-1.6622,-2.1413,0.66193,1.2234,0 +7.52,-1.2235,-1.6624,-2.1414,0.66227,1.2235,0 +7.521,-1.2237,-1.6626,-2.1416,0.6626,1.2237,0 +7.522,-1.2239,-1.6628,-2.1417,0.66294,1.2239,0 +7.523,-1.224,-1.663,-2.1419,0.66327,1.224,0 +7.524,-1.2242,-1.6632,-2.142,0.66361,1.2242,0 +7.525,-1.2244,-1.6634,-2.1422,0.66394,1.2244,0 +7.526,-1.2245,-1.6636,-2.1423,0.66428,1.2245,0 +7.527,-1.2247,-1.6638,-2.1425,0.66461,1.2247,0 +7.528,-1.2249,-1.6639,-2.1426,0.66495,1.2249,0 +7.529,-1.225,-1.6641,-2.1427,0.66529,1.225,0 +7.53,-1.2252,-1.6643,-2.1429,0.66562,1.2252,0 +7.531,-1.2254,-1.6645,-2.143,0.66596,1.2254,0 +7.532,-1.2255,-1.6647,-2.1432,0.66629,1.2255,0 +7.533,-1.2257,-1.6649,-2.1433,0.66663,1.2257,0 +7.534,-1.2259,-1.6651,-2.1435,0.66696,1.2259,0 +7.535,-1.226,-1.6653,-2.1436,0.6673,1.226,0 +7.536,-1.2262,-1.6655,-2.1437,0.66763,1.2262,0 +7.537,-1.2264,-1.6657,-2.1439,0.66797,1.2264,0 +7.538,-1.2265,-1.6659,-2.144,0.6683,1.2265,0 +7.539,-1.2267,-1.6661,-2.1442,0.66864,1.2267,0 +7.54,-1.2269,-1.6663,-2.1443,0.66897,1.2269,0 +7.541,-1.227,-1.6664,-2.1445,0.66931,1.227,0 +7.542,-1.2272,-1.6666,-2.1446,0.66964,1.2272,0 +7.543,-1.2274,-1.6668,-2.1447,0.66998,1.2274,0 +7.544,-1.2275,-1.667,-2.1449,0.67032,1.2275,0 +7.545,-1.2277,-1.6672,-2.145,0.67065,1.2277,0 +7.546,-1.2279,-1.6674,-2.1452,0.67099,1.2279,0 +7.547,-1.228,-1.6676,-2.1453,0.67132,1.228,0 +7.548,-1.2282,-1.6678,-2.1455,0.67166,1.2282,0 +7.549,-1.2284,-1.668,-2.1456,0.67199,1.2284,0 +7.55,-1.2285,-1.6682,-2.1457,0.67233,1.2285,0 +7.551,-1.2287,-1.6684,-2.1459,0.67266,1.2287,0 +7.552,-1.2289,-1.6686,-2.146,0.673,1.2289,0 +7.553,-1.229,-1.6688,-2.1462,0.67333,1.229,0 +7.554,-1.2292,-1.6689,-2.1463,0.67367,1.2292,0 +7.555,-1.2294,-1.6691,-2.1465,0.674,1.2294,0 +7.556,-1.2295,-1.6693,-2.1466,0.67434,1.2295,0 +7.557,-1.2297,-1.6695,-2.1467,0.67467,1.2297,0 +7.558,-1.2299,-1.6697,-2.1469,0.67501,1.2299,0 +7.559,-1.23,-1.6699,-2.147,0.67535,1.23,0 +7.56,-1.2302,-1.6701,-2.1472,0.67568,1.2302,0 +7.561,-1.2304,-1.6703,-2.1473,0.67602,1.2304,0 +7.562,-1.2305,-1.6705,-2.1475,0.67635,1.2305,0 +7.563,-1.2307,-1.6707,-2.1476,0.67669,1.2307,0 +7.564,-1.2309,-1.6709,-2.1477,0.67702,1.2309,0 +7.565,-1.231,-1.6711,-2.1479,0.67736,1.231,0 +7.566,-1.2312,-1.6713,-2.148,0.67769,1.2312,0 +7.567,-1.2314,-1.6714,-2.1482,0.67803,1.2314,0 +7.568,-1.2315,-1.6716,-2.1483,0.67836,1.2315,0 +7.569,-1.2317,-1.6718,-2.1485,0.6787,1.2317,0 +7.57,-1.2318,-1.672,-2.1486,0.67903,1.2318,0 +7.571,-1.232,-1.6722,-2.1488,0.67937,1.232,0 +7.572,-1.2322,-1.6724,-2.1489,0.6797,1.2322,0 +7.573,-1.2323,-1.6726,-2.149,0.68004,1.2323,0 +7.574,-1.2325,-1.6728,-2.1492,0.68038,1.2325,0 +7.575,-1.2327,-1.673,-2.1493,0.68071,1.2327,0 +7.576,-1.2328,-1.6732,-2.1495,0.68105,1.2328,0 +7.577,-1.233,-1.6734,-2.1496,0.68138,1.233,0 +7.578,-1.2332,-1.6736,-2.1498,0.68172,1.2332,0 +7.579,-1.2333,-1.6737,-2.1499,0.68205,1.2333,0 +7.58,-1.2335,-1.6739,-2.15,0.68239,1.2335,0 +7.581,-1.2337,-1.6741,-2.1502,0.68272,1.2337,0 +7.582,-1.2338,-1.6743,-2.1503,0.68306,1.2338,0 +7.583,-1.234,-1.6745,-2.1505,0.68339,1.234,0 +7.584,-1.2342,-1.6747,-2.1506,0.68373,1.2342,0 +7.585,-1.2343,-1.6749,-2.1508,0.68406,1.2343,0 +7.586,-1.2345,-1.6751,-2.1509,0.6844,1.2345,0 +7.587,-1.2347,-1.6753,-2.151,0.68473,1.2347,0 +7.588,-1.2348,-1.6755,-2.1512,0.68507,1.2348,0 +7.589,-1.235,-1.6757,-2.1513,0.68541,1.235,0 +7.59,-1.2352,-1.6759,-2.1515,0.68574,1.2352,0 +7.591,-1.2353,-1.6761,-2.1516,0.68608,1.2353,0 +7.592,-1.2355,-1.6762,-2.1518,0.68641,1.2355,0 +7.593,-1.2357,-1.6764,-2.1519,0.68674,1.2357,0 +7.594,-1.2358,-1.6766,-2.152,0.68707,1.2358,0 +7.595,-1.2359,-1.6768,-2.1522,0.6874,1.2359,0 +7.596,-1.2361,-1.677,-2.1523,0.68772,1.2361,0 +7.597,-1.2362,-1.6772,-2.1524,0.68804,1.2362,0 +7.598,-1.2363,-1.6774,-2.1526,0.68836,1.2363,0 +7.599,-1.2364,-1.6776,-2.1527,0.68867,1.2364,0 +7.6,-1.2365,-1.6778,-2.1528,0.68899,1.2365,0 +7.601,-1.2365,-1.6779,-2.1529,0.6893,1.2365,0 +7.602,-1.2366,-1.6781,-2.1531,0.6896,1.2366,0 +7.603,-1.2367,-1.6783,-2.1532,0.68991,1.2367,0 +7.604,-1.2367,-1.6785,-2.1533,0.69022,1.2367,0 +7.605,-1.2368,-1.6787,-2.1534,0.69053,1.2368,0 +7.606,-1.2369,-1.6789,-2.1536,0.69083,1.2369,0 +7.607,-1.2369,-1.6791,-2.1537,0.69114,1.2369,0 +7.608,-1.237,-1.6792,-2.1538,0.69145,1.237,0 +7.609,-1.2371,-1.6794,-2.1539,0.69176,1.2371,0 +7.61,-1.2371,-1.6796,-2.154,0.69206,1.2371,0 +7.611,-1.2372,-1.6798,-2.1542,0.69237,1.2372,0 +7.612,-1.2373,-1.68,-2.1543,0.69268,1.2373,0 +7.613,-1.2373,-1.6802,-2.1544,0.69299,1.2373,0 +7.614,-1.2374,-1.6804,-2.1545,0.69329,1.2374,0 +7.615,-1.2375,-1.6805,-2.1547,0.6936,1.2375,0 +7.616,-1.2375,-1.6807,-2.1548,0.69391,1.2375,0 +7.617,-1.2376,-1.6809,-2.1549,0.69422,1.2376,0 +7.618,-1.2377,-1.6811,-2.155,0.69452,1.2377,0 +7.619,-1.2377,-1.6813,-2.1551,0.69483,1.2377,0 +7.62,-1.2378,-1.6815,-2.1553,0.69514,1.2378,0 +7.621,-1.2379,-1.6817,-2.1554,0.69545,1.2379,0 +7.622,-1.2379,-1.6818,-2.1555,0.69575,1.2379,0 +7.623,-1.238,-1.682,-2.1556,0.69606,1.238,0 +7.624,-1.2381,-1.6822,-2.1558,0.69637,1.2381,0 +7.625,-1.2381,-1.6824,-2.1559,0.69668,1.2381,0 +7.626,-1.2382,-1.6826,-2.156,0.69698,1.2382,0 +7.627,-1.2383,-1.6828,-2.1561,0.69729,1.2383,0 +7.628,-1.2383,-1.683,-2.1562,0.6976,1.2383,0 +7.629,-1.2384,-1.6831,-2.1564,0.69791,1.2384,0 +7.63,-1.2385,-1.6833,-2.1565,0.69821,1.2385,0 +7.631,-1.2385,-1.6835,-2.1566,0.69852,1.2385,0 +7.632,-1.2386,-1.6837,-2.1567,0.69883,1.2386,0 +7.633,-1.2387,-1.6839,-2.1569,0.69914,1.2387,0 +7.634,-1.2387,-1.6841,-2.157,0.69944,1.2387,0 +7.635,-1.2388,-1.6842,-2.1571,0.69975,1.2388,0 +7.636,-1.2389,-1.6844,-2.1572,0.70006,1.2389,0 +7.637,-1.2389,-1.6846,-2.1573,0.70037,1.2389,0 +7.638,-1.239,-1.6848,-2.1575,0.70067,1.239,0 +7.639,-1.2391,-1.685,-2.1576,0.70098,1.2391,0 +7.64,-1.2391,-1.6852,-2.1577,0.70129,1.2391,0 +7.641,-1.2392,-1.6854,-2.1578,0.7016,1.2392,0 +7.642,-1.2393,-1.6855,-2.158,0.7019,1.2393,0 +7.643,-1.2393,-1.6857,-2.1581,0.70221,1.2393,0 +7.644,-1.2394,-1.6859,-2.1582,0.70252,1.2394,0 +7.645,-1.2395,-1.6861,-2.1583,0.70283,1.2395,0 +7.646,-1.2395,-1.6863,-2.1584,0.70314,1.2395,0 +7.647,-1.2396,-1.6865,-2.1586,0.70344,1.2396,0 +7.648,-1.2397,-1.6867,-2.1587,0.70375,1.2397,0 +7.649,-1.2397,-1.6868,-2.1588,0.70406,1.2397,0 +7.65,-1.2398,-1.687,-2.1589,0.70437,1.2398,0 +7.651,-1.2399,-1.6872,-2.159,0.70467,1.2399,0 +7.652,-1.2399,-1.6874,-2.1592,0.70498,1.2399,0 +7.653,-1.24,-1.6876,-2.1593,0.70529,1.24,0 +7.654,-1.2401,-1.6878,-2.1594,0.7056,1.2401,0 +7.655,-1.2401,-1.688,-2.1595,0.7059,1.2401,0 +7.656,-1.2402,-1.6881,-2.1597,0.70621,1.2402,0 +7.657,-1.2403,-1.6883,-2.1598,0.70652,1.2403,0 +7.658,-1.2403,-1.6885,-2.1599,0.70683,1.2403,0 +7.659,-1.2404,-1.6887,-2.16,0.70713,1.2404,0 +7.66,-1.2405,-1.6889,-2.1601,0.70744,1.2405,0 +7.661,-1.2405,-1.6891,-2.1603,0.70775,1.2405,0 +7.662,-1.2406,-1.6893,-2.1604,0.70806,1.2406,0 +7.663,-1.2407,-1.6894,-2.1605,0.70836,1.2407,0 +7.664,-1.2407,-1.6896,-2.1606,0.70867,1.2407,0 +7.665,-1.2408,-1.6898,-2.1608,0.70898,1.2408,0 +7.666,-1.2409,-1.69,-2.1609,0.70929,1.2409,0 +7.667,-1.2409,-1.6902,-2.161,0.70959,1.2409,0 +7.668,-1.241,-1.6904,-2.1611,0.7099,1.241,0 +7.669,-1.2411,-1.6906,-2.1612,0.71021,1.2411,0 +7.67,-1.2411,-1.6907,-2.1614,0.71052,1.2411,0 +7.671,-1.2412,-1.6909,-2.1615,0.71082,1.2412,0 +7.672,-1.2413,-1.6911,-2.1616,0.71113,1.2413,0 +7.673,-1.2413,-1.6913,-2.1617,0.71144,1.2413,0 +7.674,-1.2414,-1.6915,-2.1619,0.71175,1.2414,0 +7.675,-1.2415,-1.6917,-2.162,0.71205,1.2415,0 +7.676,-1.2415,-1.6918,-2.1621,0.71234,1.2415,0 +7.677,-1.2415,-1.692,-2.1622,0.71261,1.2415,0 +7.678,-1.2415,-1.6922,-2.1623,0.71288,1.2415,0 +7.679,-1.2415,-1.6923,-2.1624,0.71313,1.2415,0 +7.68,-1.2414,-1.6925,-2.1625,0.71336,1.2414,0 +7.681,-1.2413,-1.6926,-2.1626,0.71359,1.2413,0 +7.682,-1.2412,-1.6927,-2.1627,0.7138,1.2412,0 +7.683,-1.2411,-1.6929,-2.1627,0.714,1.2411,0 +7.684,-1.241,-1.693,-2.1628,0.71418,1.241,0 +7.685,-1.2408,-1.6931,-2.1629,0.71436,1.2408,0 +7.686,-1.2407,-1.6932,-2.1629,0.71453,1.2407,0 +7.687,-1.2405,-1.6933,-2.163,0.71471,1.2405,0 +7.688,-1.2403,-1.6934,-2.163,0.71488,1.2403,0 +7.689,-1.2402,-1.6935,-2.1631,0.71506,1.2402,0 +7.69,-1.24,-1.6937,-2.1632,0.71523,1.24,0 +7.691,-1.2399,-1.6938,-2.1632,0.71541,1.2399,0 +7.692,-1.2397,-1.6939,-2.1633,0.71559,1.2397,0 +7.693,-1.2395,-1.694,-2.1634,0.71576,1.2395,0 +7.694,-1.2394,-1.6941,-2.1634,0.71594,1.2394,0 +7.695,-1.2392,-1.6942,-2.1635,0.71611,1.2392,0 +7.696,-1.2391,-1.6943,-2.1635,0.71629,1.2391,0 +7.697,-1.2389,-1.6944,-2.1636,0.71646,1.2389,0 +7.698,-1.2388,-1.6946,-2.1637,0.71664,1.2388,0 +7.699,-1.2386,-1.6947,-2.1637,0.71682,1.2386,0 +7.7,-1.2384,-1.6948,-2.1638,0.71699,1.2384,0 +7.701,-1.2383,-1.6949,-2.1639,0.71717,1.2383,0 +7.702,-1.2381,-1.695,-2.1639,0.71734,1.2381,0 +7.703,-1.238,-1.6951,-2.164,0.71752,1.238,0 +7.704,-1.2378,-1.6952,-2.1641,0.7177,1.2378,0 +7.705,-1.2376,-1.6953,-2.1641,0.71787,1.2376,0 +7.706,-1.2375,-1.6955,-2.1642,0.71805,1.2375,0 +7.707,-1.2373,-1.6956,-2.1642,0.71822,1.2373,0 +7.708,-1.2372,-1.6957,-2.1643,0.7184,1.2372,0 +7.709,-1.237,-1.6958,-2.1644,0.71857,1.237,0 +7.71,-1.2369,-1.6959,-2.1644,0.71875,1.2369,0 +7.711,-1.2367,-1.696,-2.1645,0.71893,1.2367,0 +7.712,-1.2365,-1.6961,-2.1646,0.7191,1.2365,0 +7.713,-1.2364,-1.6962,-2.1646,0.71928,1.2364,0 +7.714,-1.2362,-1.6964,-2.1647,0.71945,1.2362,0 +7.715,-1.2361,-1.6965,-2.1647,0.71963,1.2361,0 +7.716,-1.2359,-1.6966,-2.1648,0.7198,1.2359,0 +7.717,-1.2357,-1.6967,-2.1649,0.71998,1.2357,0 +7.718,-1.2356,-1.6968,-2.1649,0.72016,1.2356,0 +7.719,-1.2354,-1.6969,-2.165,0.72033,1.2354,0 +7.72,-1.2353,-1.697,-2.1651,0.72051,1.2353,0 +7.721,-1.2351,-1.6972,-2.1651,0.72068,1.2351,0 +7.722,-1.235,-1.6973,-2.1652,0.72086,1.235,0 +7.723,-1.2348,-1.6974,-2.1653,0.72103,1.2348,0 +7.724,-1.2346,-1.6975,-2.1653,0.72121,1.2346,0 +7.725,-1.2345,-1.6976,-2.1654,0.72139,1.2345,0 +7.726,-1.2343,-1.6977,-2.1654,0.72156,1.2343,0 +7.727,-1.2342,-1.6978,-2.1655,0.72174,1.2342,0 +7.728,-1.234,-1.6979,-2.1656,0.72191,1.234,0 +7.729,-1.2338,-1.6981,-2.1656,0.72209,1.2338,0 +7.73,-1.2337,-1.6982,-2.1657,0.72226,1.2337,0 +7.731,-1.2335,-1.6983,-2.1658,0.72244,1.2335,0 +7.732,-1.2334,-1.6984,-2.1658,0.72262,1.2334,0 +7.733,-1.2332,-1.6985,-2.1659,0.72279,1.2332,0 +7.734,-1.2331,-1.6986,-2.1659,0.72297,1.2331,0 +7.735,-1.2329,-1.6987,-2.166,0.72314,1.2329,0 +7.736,-1.2327,-1.6988,-2.1661,0.72332,1.2327,0 +7.737,-1.2326,-1.699,-2.1661,0.72349,1.2326,0 +7.738,-1.2324,-1.6991,-2.1662,0.72367,1.2324,0 +7.739,-1.2323,-1.6992,-2.1663,0.72385,1.2323,0 +7.74,-1.2321,-1.6993,-2.1663,0.72402,1.2321,0 +7.741,-1.2319,-1.6994,-2.1664,0.7242,1.2319,0 +7.742,-1.2318,-1.6995,-2.1664,0.72437,1.2318,0 +7.743,-1.2316,-1.6996,-2.1665,0.72455,1.2316,0 +7.744,-1.2315,-1.6997,-2.1666,0.72472,1.2315,0 +7.745,-1.2313,-1.6999,-2.1666,0.7249,1.2313,0 +7.746,-1.2312,-1.7,-2.1667,0.72508,1.2312,0 +7.747,-1.231,-1.7001,-2.1668,0.72525,1.231,0 +7.748,-1.2308,-1.7002,-2.1668,0.72543,1.2308,0 +7.749,-1.2307,-1.7003,-2.1669,0.7256,1.2307,0 +7.75,-1.2305,-1.7004,-2.167,0.72578,1.2305,0 +7.751,-1.2304,-1.7005,-2.167,0.72595,1.2304,0 +7.752,-1.2302,-1.7006,-2.1671,0.72613,1.2302,0 +7.753,-1.23,-1.7008,-2.1671,0.72631,1.23,0 +7.754,-1.2299,-1.7009,-2.1672,0.72648,1.2299,0 +7.755,-1.2297,-1.701,-2.1673,0.72666,1.2297,0 +7.756,-1.2296,-1.7011,-2.1673,0.72683,1.2296,0 +7.757,-1.2294,-1.7012,-2.1674,0.72701,1.2294,0 +7.758,-1.2293,-1.7013,-2.1675,0.72718,1.2293,0 +7.759,-1.2291,-1.7014,-2.1675,0.72735,1.2291,0 +7.76,-1.2289,-1.7015,-2.1676,0.72752,1.2289,0 +7.761,-1.2287,-1.7016,-2.1676,0.72768,1.2287,0 +7.762,-1.2285,-1.7017,-2.1677,0.72783,1.2285,0 +7.763,-1.2283,-1.7018,-2.1677,0.72798,1.2283,0 +7.764,-1.2281,-1.7019,-2.1678,0.72813,1.2281,0 +7.765,-1.2278,-1.702,-2.1678,0.72827,1.2278,0 +7.766,-1.2276,-1.7021,-2.1679,0.72841,1.2276,0 +7.767,-1.2273,-1.7022,-2.1679,0.72855,1.2273,0 +7.768,-1.2271,-1.7023,-2.1679,0.72868,1.2271,0 +7.769,-1.2268,-1.7024,-2.168,0.72881,1.2268,0 +7.77,-1.2266,-1.7025,-2.168,0.72894,1.2266,0 +7.771,-1.2263,-1.7026,-2.1681,0.72907,1.2263,0 +7.772,-1.2261,-1.7027,-2.1681,0.7292,1.2261,0 +7.773,-1.2258,-1.7028,-2.1681,0.72933,1.2258,0 +7.774,-1.2256,-1.7029,-2.1682,0.72946,1.2256,0 +7.775,-1.2253,-1.703,-2.1682,0.72959,1.2253,0 +7.776,-1.225,-1.7031,-2.1683,0.72972,1.225,0 +7.777,-1.2248,-1.7032,-2.1683,0.72985,1.2248,0 +7.778,-1.2245,-1.7032,-2.1683,0.72998,1.2245,0 +7.779,-1.2243,-1.7033,-2.1684,0.73011,1.2243,0 +7.78,-1.224,-1.7034,-2.1684,0.73025,1.224,0 +7.781,-1.2238,-1.7035,-2.1684,0.73038,1.2238,0 +7.782,-1.2235,-1.7036,-2.1685,0.73051,1.2235,0 +7.783,-1.2232,-1.7037,-2.1685,0.73064,1.2232,0 +7.784,-1.223,-1.7038,-2.1686,0.73077,1.223,0 +7.785,-1.2227,-1.7039,-2.1686,0.7309,1.2227,0 +7.786,-1.2225,-1.704,-2.1686,0.73103,1.2225,0 +7.787,-1.2222,-1.7041,-2.1687,0.73116,1.2222,0 +7.788,-1.222,-1.7042,-2.1687,0.73129,1.222,0 +7.789,-1.2217,-1.7043,-2.1688,0.73142,1.2217,0 +7.79,-1.2214,-1.7044,-2.1688,0.73155,1.2214,0 +7.791,-1.2212,-1.7044,-2.1688,0.73168,1.2212,0 +7.792,-1.2209,-1.7045,-2.1689,0.73181,1.2209,0 +7.793,-1.2207,-1.7046,-2.1689,0.73195,1.2207,0 +7.794,-1.2204,-1.7047,-2.1689,0.73208,1.2204,0 +7.795,-1.2202,-1.7048,-2.169,0.73221,1.2202,0 +7.796,-1.2199,-1.7049,-2.169,0.73234,1.2199,0 +7.797,-1.2197,-1.705,-2.1691,0.73247,1.2197,0 +7.798,-1.2194,-1.7051,-2.1691,0.7326,1.2194,0 +7.799,-1.2191,-1.7052,-2.1691,0.73273,1.2191,0 +7.8,-1.2189,-1.7053,-2.1692,0.73286,1.2189,0 +7.801,-1.2186,-1.7054,-2.1692,0.73299,1.2186,0 +7.802,-1.2184,-1.7055,-2.1693,0.73312,1.2184,0 +7.803,-1.2181,-1.7056,-2.1693,0.73325,1.2181,0 +7.804,-1.2179,-1.7056,-2.1693,0.73338,1.2179,0 +7.805,-1.2176,-1.7057,-2.1694,0.73351,1.2176,0 +7.806,-1.2173,-1.7058,-2.1694,0.73365,1.2173,0 +7.807,-1.2171,-1.7059,-2.1694,0.73378,1.2171,0 +7.808,-1.2168,-1.706,-2.1695,0.73391,1.2168,0 +7.809,-1.2166,-1.7061,-2.1695,0.73404,1.2166,0 +7.81,-1.2163,-1.7062,-2.1696,0.73417,1.2163,0 +7.811,-1.2161,-1.7063,-2.1696,0.7343,1.2161,0 +7.812,-1.2158,-1.7064,-2.1696,0.73443,1.2158,0 +7.813,-1.2156,-1.7065,-2.1697,0.73456,1.2156,0 +7.814,-1.2153,-1.7066,-2.1697,0.73469,1.2153,0 +7.815,-1.215,-1.7067,-2.1698,0.73482,1.215,0 +7.816,-1.2148,-1.7068,-2.1698,0.73495,1.2148,0 +7.817,-1.2145,-1.7068,-2.1698,0.73508,1.2145,0 +7.818,-1.2143,-1.7069,-2.1699,0.73521,1.2143,0 +7.819,-1.214,-1.707,-2.1699,0.73535,1.214,0 +7.82,-1.2138,-1.7071,-2.1699,0.73548,1.2138,0 +7.821,-1.2135,-1.7072,-2.17,0.73561,1.2135,0 +7.822,-1.2132,-1.7073,-2.17,0.73574,1.2132,0 +7.823,-1.213,-1.7074,-2.1701,0.73587,1.213,0 +7.824,-1.2127,-1.7075,-2.1701,0.736,1.2127,0 +7.825,-1.2125,-1.7076,-2.1701,0.73613,1.2125,0 +7.826,-1.2122,-1.7077,-2.1702,0.73626,1.2122,0 +7.827,-1.212,-1.7078,-2.1702,0.73639,1.212,0 +7.828,-1.2117,-1.7079,-2.1703,0.73652,1.2117,0 +7.829,-1.2114,-1.708,-2.1703,0.73665,1.2114,0 +7.83,-1.2112,-1.708,-2.1703,0.73678,1.2112,0 +7.831,-1.2109,-1.7081,-2.1704,0.73691,1.2109,0 +7.832,-1.2107,-1.7082,-2.1704,0.73705,1.2107,0 +7.833,-1.2104,-1.7083,-2.1704,0.73718,1.2104,0 +7.834,-1.2102,-1.7084,-2.1705,0.73731,1.2102,0 +7.835,-1.2099,-1.7085,-2.1705,0.73744,1.2099,0 +7.836,-1.2097,-1.7086,-2.1706,0.73757,1.2097,0 +7.837,-1.2094,-1.7087,-2.1706,0.7377,1.2094,0 +7.838,-1.2091,-1.7088,-2.1706,0.73783,1.2091,0 +7.839,-1.2089,-1.7089,-2.1707,0.73796,1.2089,0 +7.84,-1.2086,-1.709,-2.1707,0.73809,1.2086,0 +7.841,-1.2084,-1.7091,-2.1708,0.73822,1.2084,0 +7.842,-1.2081,-1.7092,-2.1708,0.73834,1.2081,0 +7.843,-1.2078,-1.7092,-2.1708,0.73846,1.2078,0 +7.844,-1.2075,-1.7093,-2.1708,0.73858,1.2075,0 +7.845,-1.2072,-1.7094,-2.1709,0.73869,1.2072,0 +7.846,-1.2069,-1.7095,-2.1709,0.73879,1.2069,0 +7.847,-1.2065,-1.7096,-2.1709,0.73889,1.2065,0 +7.848,-1.2062,-1.7097,-2.1709,0.73899,1.2062,0 +7.849,-1.2058,-1.7097,-2.1709,0.73908,1.2058,0 +7.85,-1.2055,-1.7098,-2.1709,0.73917,1.2055,0 +7.851,-1.2051,-1.7099,-2.1709,0.73925,1.2051,0 +7.852,-1.2047,-1.71,-2.171,0.73933,1.2047,0 +7.853,-1.2043,-1.7101,-2.171,0.73942,1.2043,0 +7.854,-1.204,-1.7101,-2.171,0.7395,1.204,0 +7.855,-1.2036,-1.7102,-2.171,0.73959,1.2036,0 +7.856,-1.2032,-1.7103,-2.171,0.73967,1.2032,0 +7.857,-1.2028,-1.7104,-2.171,0.73975,1.2028,0 +7.858,-1.2025,-1.7104,-2.171,0.73984,1.2025,0 +7.859,-1.2021,-1.7105,-2.171,0.73992,1.2021,0 +7.86,-1.2017,-1.7106,-2.171,0.74001,1.2017,0 +7.861,-1.2013,-1.7107,-2.171,0.74009,1.2013,0 +7.862,-1.201,-1.7108,-2.171,0.74017,1.201,0 +7.863,-1.2006,-1.7108,-2.171,0.74026,1.2006,0 +7.864,-1.2002,-1.7109,-2.171,0.74034,1.2002,0 +7.865,-1.1998,-1.711,-2.171,0.74043,1.1998,0 +7.866,-1.1994,-1.7111,-2.171,0.74051,1.1994,0 +7.867,-1.1991,-1.7111,-2.171,0.74059,1.1991,0 +7.868,-1.1987,-1.7112,-2.1711,0.74068,1.1987,0 +7.869,-1.1983,-1.7113,-2.1711,0.74076,1.1983,0 +7.87,-1.1979,-1.7114,-2.1711,0.74085,1.1979,0 +7.871,-1.1976,-1.7114,-2.1711,0.74093,1.1976,0 +7.872,-1.1972,-1.7115,-2.1711,0.74101,1.1972,0 +7.873,-1.1968,-1.7116,-2.1711,0.7411,1.1968,0 +7.874,-1.1964,-1.7117,-2.1711,0.74118,1.1964,0 +7.875,-1.1961,-1.7118,-2.1711,0.74127,1.1961,0 +7.876,-1.1957,-1.7118,-2.1711,0.74135,1.1957,0 +7.877,-1.1953,-1.7119,-2.1711,0.74143,1.1953,0 +7.878,-1.1949,-1.712,-2.1711,0.74152,1.1949,0 +7.879,-1.1946,-1.7121,-2.1711,0.7416,1.1946,0 +7.88,-1.1942,-1.7121,-2.1711,0.74169,1.1942,0 +7.881,-1.1938,-1.7122,-2.1711,0.74177,1.1938,0 +7.882,-1.1934,-1.7123,-2.1711,0.74185,1.1934,0 +7.883,-1.1931,-1.7124,-2.1712,0.74194,1.1931,0 +7.884,-1.1927,-1.7125,-2.1712,0.74202,1.1927,0 +7.885,-1.1923,-1.7125,-2.1712,0.74211,1.1923,0 +7.886,-1.1919,-1.7126,-2.1712,0.74219,1.1919,0 +7.887,-1.1915,-1.7127,-2.1712,0.74227,1.1915,0 +7.888,-1.1912,-1.7128,-2.1712,0.74236,1.1912,0 +7.889,-1.1908,-1.7128,-2.1712,0.74244,1.1908,0 +7.89,-1.1904,-1.7129,-2.1712,0.74253,1.1904,0 +7.891,-1.19,-1.713,-2.1712,0.74261,1.19,0 +7.892,-1.1897,-1.7131,-2.1712,0.74269,1.1897,0 +7.893,-1.1893,-1.7132,-2.1712,0.74278,1.1893,0 +7.894,-1.1889,-1.7132,-2.1712,0.74286,1.1889,0 +7.895,-1.1885,-1.7133,-2.1712,0.74295,1.1885,0 +7.896,-1.1882,-1.7134,-2.1712,0.74303,1.1882,0 +7.897,-1.1878,-1.7135,-2.1712,0.74311,1.1878,0 +7.898,-1.1874,-1.7135,-2.1712,0.7432,1.1874,0 +7.899,-1.187,-1.7136,-2.1713,0.74328,1.187,0 +7.9,-1.1867,-1.7137,-2.1713,0.74336,1.1867,0 +7.901,-1.1863,-1.7138,-2.1713,0.74345,1.1863,0 +7.902,-1.1859,-1.7139,-2.1713,0.74353,1.1859,0 +7.903,-1.1855,-1.7139,-2.1713,0.74362,1.1855,0 +7.904,-1.1852,-1.714,-2.1713,0.7437,1.1852,0 +7.905,-1.1848,-1.7141,-2.1713,0.74378,1.1848,0 +7.906,-1.1844,-1.7142,-2.1713,0.74387,1.1844,0 +7.907,-1.184,-1.7142,-2.1713,0.74395,1.184,0 +7.908,-1.1836,-1.7143,-2.1713,0.74404,1.1836,0 +7.909,-1.1833,-1.7144,-2.1713,0.74412,1.1833,0 +7.91,-1.1829,-1.7145,-2.1713,0.7442,1.1829,0 +7.911,-1.1825,-1.7145,-2.1713,0.74429,1.1825,0 +7.912,-1.1821,-1.7146,-2.1713,0.74437,1.1821,0 +7.913,-1.1818,-1.7147,-2.1713,0.74446,1.1818,0 +7.914,-1.1814,-1.7148,-2.1714,0.74454,1.1814,0 +7.915,-1.181,-1.7149,-2.1714,0.74462,1.181,0 +7.916,-1.1806,-1.7149,-2.1714,0.74471,1.1806,0 +7.917,-1.1803,-1.715,-2.1714,0.74479,1.1803,0 +7.918,-1.1799,-1.7151,-2.1714,0.74488,1.1799,0 +7.919,-1.1795,-1.7152,-2.1714,0.74496,1.1795,0 +7.92,-1.1791,-1.7152,-2.1714,0.74504,1.1791,0 +7.921,-1.1788,-1.7153,-2.1714,0.74513,1.1788,0 +7.922,-1.1784,-1.7154,-2.1714,0.74521,1.1784,0 +7.923,-1.178,-1.7155,-2.1714,0.7453,1.178,0 +7.924,-1.1776,-1.7156,-2.1714,0.74538,1.1776,0 +7.925,-1.1772,-1.7156,-2.1714,0.74546,1.1772,0 +7.926,-1.1769,-1.7157,-2.1714,0.74555,1.1769,0 +7.927,-1.1765,-1.7158,-2.1714,0.74563,1.1765,0 +7.928,-1.1761,-1.7159,-2.1714,0.74571,1.1761,0 +7.929,-1.1757,-1.716,-2.1714,0.74579,1.1757,0 +7.93,-1.1753,-1.7161,-2.1714,0.74588,1.1753,0 +7.931,-1.1749,-1.7161,-2.1714,0.74596,1.1749,0 +7.932,-1.1745,-1.7162,-2.1714,0.74604,1.1745,0 +7.933,-1.1741,-1.7163,-2.1714,0.74612,1.1741,0 +7.934,-1.1737,-1.7164,-2.1714,0.7462,1.1737,0 +7.935,-1.1733,-1.7165,-2.1714,0.74628,1.1733,0 +7.936,-1.1729,-1.7166,-2.1714,0.74636,1.1729,0 +7.937,-1.1725,-1.7167,-2.1714,0.74644,1.1725,0 +7.938,-1.1721,-1.7168,-2.1713,0.74652,1.1721,0 +7.939,-1.1717,-1.7169,-2.1713,0.74661,1.1717,0 +7.94,-1.1713,-1.717,-2.1713,0.74669,1.1713,0 +7.941,-1.1709,-1.7171,-2.1713,0.74677,1.1709,0 +7.942,-1.1705,-1.7171,-2.1713,0.74685,1.1705,0 +7.943,-1.1701,-1.7172,-2.1713,0.74693,1.1701,0 +7.944,-1.1697,-1.7173,-2.1713,0.74701,1.1697,0 +7.945,-1.1693,-1.7174,-2.1713,0.74709,1.1693,0 +7.946,-1.1689,-1.7175,-2.1713,0.74717,1.1689,0 +7.947,-1.1685,-1.7176,-2.1712,0.74725,1.1685,0 +7.948,-1.1681,-1.7177,-2.1712,0.74733,1.1681,0 +7.949,-1.1677,-1.7178,-2.1712,0.74741,1.1677,0 +7.95,-1.1673,-1.7179,-2.1712,0.74749,1.1673,0 +7.951,-1.1669,-1.718,-2.1712,0.74758,1.1669,0 +7.952,-1.1665,-1.7181,-2.1712,0.74766,1.1665,0 +7.953,-1.1661,-1.7181,-2.1712,0.74774,1.1661,0 +7.954,-1.1657,-1.7182,-2.1712,0.74782,1.1657,0 +7.955,-1.1653,-1.7183,-2.1712,0.7479,1.1653,0 +7.956,-1.1649,-1.7184,-2.1712,0.74798,1.1649,0 +7.957,-1.1645,-1.7185,-2.1711,0.74806,1.1645,0 +7.958,-1.1641,-1.7186,-2.1711,0.74814,1.1641,0 +7.959,-1.1637,-1.7187,-2.1711,0.74822,1.1637,0 +7.96,-1.1633,-1.7188,-2.1711,0.7483,1.1633,0 +7.961,-1.1629,-1.7189,-2.1711,0.74838,1.1629,0 +7.962,-1.1625,-1.719,-2.1711,0.74846,1.1625,0 +7.963,-1.162,-1.719,-2.1711,0.74855,1.162,0 +7.964,-1.1616,-1.7191,-2.1711,0.74863,1.1616,0 +7.965,-1.1612,-1.7192,-2.1711,0.74871,1.1612,0 +7.966,-1.1608,-1.7193,-2.1711,0.74879,1.1608,0 +7.967,-1.1604,-1.7194,-2.171,0.74887,1.1604,0 +7.968,-1.16,-1.7195,-2.171,0.74895,1.16,0 +7.969,-1.1596,-1.7196,-2.171,0.74903,1.1596,0 +7.97,-1.1592,-1.7197,-2.171,0.74911,1.1592,0 +7.971,-1.1588,-1.7198,-2.171,0.74919,1.1588,0 +7.972,-1.1584,-1.7199,-2.171,0.74927,1.1584,0 +7.973,-1.158,-1.72,-2.171,0.74935,1.158,0 +7.974,-1.1576,-1.72,-2.171,0.74943,1.1576,0 +7.975,-1.1572,-1.7201,-2.171,0.74952,1.1572,0 +7.976,-1.1568,-1.7202,-2.171,0.7496,1.1568,0 +7.977,-1.1564,-1.7203,-2.1709,0.74968,1.1564,0 +7.978,-1.156,-1.7204,-2.1709,0.74976,1.156,0 +7.979,-1.1556,-1.7205,-2.1709,0.74984,1.1556,0 +7.98,-1.1552,-1.7206,-2.1709,0.74992,1.1552,0 +7.981,-1.1548,-1.7207,-2.1709,0.75,1.1548,0 +7.982,-1.1544,-1.7208,-2.1709,0.75008,1.1544,0 +7.983,-1.154,-1.7209,-2.1709,0.75016,1.154,0 +7.984,-1.1536,-1.721,-2.1709,0.75024,1.1536,0 +7.985,-1.1532,-1.721,-2.1709,0.75032,1.1532,0 +7.986,-1.1528,-1.7211,-2.1709,0.7504,1.1528,0 +7.987,-1.1524,-1.7212,-2.1708,0.75049,1.1524,0 +7.988,-1.152,-1.7213,-2.1708,0.75057,1.152,0 +7.989,-1.1516,-1.7214,-2.1708,0.75065,1.1516,0 +7.99,-1.1512,-1.7215,-2.1708,0.75073,1.1512,0 +7.991,-1.1508,-1.7216,-2.1708,0.75081,1.1508,0 +7.992,-1.1504,-1.7217,-2.1708,0.75089,1.1504,0 +7.993,-1.15,-1.7218,-2.1708,0.75097,1.15,0 +7.994,-1.1496,-1.7219,-2.1708,0.75105,1.1496,0 +7.995,-1.1492,-1.722,-2.1708,0.75113,1.1492,0 +7.996,-1.1488,-1.722,-2.1708,0.75121,1.1488,0 +7.997,-1.1484,-1.7221,-2.1707,0.75129,1.1484,0 +7.998,-1.148,-1.7222,-2.1707,0.75137,1.148,0 +7.999,-1.1476,-1.7223,-2.1707,0.75146,1.1476,0 +8,-1.1472,-1.7224,-2.1707,0.75154,1.1472,0 +8.001,-1.1468,-1.7225,-2.1707,0.75162,1.1468,0 +8.002,-1.1464,-1.7226,-2.1707,0.7517,1.1464,0 +8.003,-1.146,-1.7227,-2.1707,0.75178,1.146,0 +8.004,-1.1456,-1.7228,-2.1707,0.75186,1.1456,0 +8.005,-1.1452,-1.7229,-2.1707,0.75194,1.1452,0 +8.006,-1.1448,-1.723,-2.1707,0.75202,1.1448,0 +8.007,-1.1444,-1.7231,-2.1706,0.7521,1.1444,0 +8.008,-1.144,-1.7231,-2.1706,0.75219,1.144,0 +8.009,-1.1435,-1.7232,-2.1706,0.75227,1.1435,0 +8.01,-1.1431,-1.7233,-2.1706,0.75235,1.1431,0 +8.011,-1.1427,-1.7234,-2.1706,0.75244,1.1427,0 +8.012,-1.1423,-1.7235,-2.1706,0.75253,1.1423,0 +8.013,-1.1419,-1.7237,-2.1706,0.75262,1.1419,0 +8.014,-1.1415,-1.7238,-2.1705,0.7527,1.1415,0 +8.015,-1.1411,-1.7239,-2.1705,0.75279,1.1411,0 +8.016,-1.1407,-1.724,-2.1705,0.75289,1.1407,0 +8.017,-1.1403,-1.7241,-2.1705,0.75298,1.1403,0 +8.018,-1.1399,-1.7242,-2.1704,0.75307,1.1399,0 +8.019,-1.1395,-1.7243,-2.1704,0.75316,1.1395,0 +8.02,-1.1391,-1.7244,-2.1704,0.75325,1.1391,0 +8.021,-1.1386,-1.7246,-2.1704,0.75334,1.1386,0 +8.022,-1.1382,-1.7247,-2.1704,0.75344,1.1382,0 +8.023,-1.1378,-1.7248,-2.1703,0.75353,1.1378,0 +8.024,-1.1374,-1.7249,-2.1703,0.75362,1.1374,0 +8.025,-1.137,-1.725,-2.1703,0.75371,1.137,0 +8.026,-1.1366,-1.7251,-2.1703,0.7538,1.1366,0 +8.027,-1.1362,-1.7252,-2.1702,0.7539,1.1362,0 +8.028,-1.1358,-1.7254,-2.1702,0.75399,1.1358,0 +8.029,-1.1354,-1.7255,-2.1702,0.75408,1.1354,0 +8.03,-1.135,-1.7256,-2.1702,0.75417,1.135,0 +8.031,-1.1345,-1.7257,-2.1702,0.75426,1.1345,0 +8.032,-1.1341,-1.7258,-2.1701,0.75435,1.1341,0 +8.033,-1.1337,-1.7259,-2.1701,0.75445,1.1337,0 +8.034,-1.1333,-1.726,-2.1701,0.75454,1.1333,0 +8.035,-1.1329,-1.7262,-2.1701,0.75463,1.1329,0 +8.036,-1.1325,-1.7263,-2.17,0.75472,1.1325,0 +8.037,-1.1321,-1.7264,-2.17,0.75481,1.1321,0 +8.038,-1.1317,-1.7265,-2.17,0.7549,1.1317,0 +8.039,-1.1313,-1.7266,-2.17,0.755,1.1313,0 +8.04,-1.1309,-1.7267,-2.17,0.75509,1.1309,0 +8.041,-1.1304,-1.7268,-2.1699,0.75518,1.1304,0 +8.042,-1.13,-1.727,-2.1699,0.75527,1.13,0 +8.043,-1.1296,-1.7271,-2.1699,0.75536,1.1296,0 +8.044,-1.1292,-1.7272,-2.1699,0.75546,1.1292,0 +8.045,-1.1288,-1.7273,-2.1698,0.75555,1.1288,0 +8.046,-1.1284,-1.7274,-2.1698,0.75564,1.1284,0 +8.047,-1.128,-1.7275,-2.1698,0.75573,1.128,0 +8.048,-1.1276,-1.7276,-2.1698,0.75582,1.1276,0 +8.049,-1.1272,-1.7278,-2.1698,0.75591,1.1272,0 +8.05,-1.1268,-1.7279,-2.1697,0.75601,1.1268,0 +8.051,-1.1263,-1.728,-2.1697,0.7561,1.1263,0 +8.052,-1.1259,-1.7281,-2.1697,0.75619,1.1259,0 +8.053,-1.1255,-1.7282,-2.1697,0.75628,1.1255,0 +8.054,-1.1251,-1.7283,-2.1696,0.75637,1.1251,0 +8.055,-1.1247,-1.7284,-2.1696,0.75646,1.1247,0 +8.056,-1.1243,-1.7286,-2.1696,0.75656,1.1243,0 +8.057,-1.1239,-1.7287,-2.1696,0.75665,1.1239,0 +8.058,-1.1235,-1.7288,-2.1696,0.75674,1.1235,0 +8.059,-1.1231,-1.7289,-2.1695,0.75683,1.1231,0 +8.06,-1.1227,-1.729,-2.1695,0.75692,1.1227,0 +8.061,-1.1222,-1.7291,-2.1695,0.75702,1.1222,0 +8.062,-1.1218,-1.7292,-2.1695,0.75711,1.1218,0 +8.063,-1.1214,-1.7293,-2.1694,0.7572,1.1214,0 +8.064,-1.121,-1.7295,-2.1694,0.75729,1.121,0 +8.065,-1.1206,-1.7296,-2.1694,0.75738,1.1206,0 +8.066,-1.1202,-1.7297,-2.1694,0.75747,1.1202,0 +8.067,-1.1198,-1.7298,-2.1694,0.75757,1.1198,0 +8.068,-1.1194,-1.7299,-2.1693,0.75766,1.1194,0 +8.069,-1.119,-1.73,-2.1693,0.75775,1.119,0 +8.07,-1.1186,-1.7301,-2.1693,0.75784,1.1186,0 +8.071,-1.1181,-1.7303,-2.1693,0.75793,1.1181,0 +8.072,-1.1177,-1.7304,-2.1692,0.75803,1.1177,0 +8.073,-1.1173,-1.7305,-2.1692,0.75812,1.1173,0 +8.074,-1.1169,-1.7306,-2.1692,0.75821,1.1169,0 +8.075,-1.1165,-1.7307,-2.1692,0.7583,1.1165,0 +8.076,-1.1161,-1.7308,-2.1692,0.75839,1.1161,0 +8.077,-1.1157,-1.7309,-2.1691,0.75848,1.1157,0 +8.078,-1.1153,-1.7311,-2.1691,0.75858,1.1153,0 +8.079,-1.1149,-1.7312,-2.1691,0.75867,1.1149,0 +8.08,-1.1145,-1.7313,-2.1691,0.75876,1.1145,0 +8.081,-1.114,-1.7314,-2.169,0.75885,1.114,0 +8.082,-1.1136,-1.7315,-2.169,0.75894,1.1136,0 +8.083,-1.1132,-1.7316,-2.169,0.75903,1.1132,0 +8.084,-1.1128,-1.7317,-2.169,0.75913,1.1128,0 +8.085,-1.1124,-1.7319,-2.169,0.75922,1.1124,0 +8.086,-1.112,-1.732,-2.1689,0.75931,1.112,0 +8.087,-1.1116,-1.7321,-2.1689,0.7594,1.1116,0 +8.088,-1.1112,-1.7322,-2.1689,0.75949,1.1112,0 +8.089,-1.1108,-1.7323,-2.1689,0.75959,1.1108,0 +8.09,-1.1104,-1.7324,-2.1688,0.75968,1.1104,0 +8.091,-1.1099,-1.7325,-2.1688,0.75976,1.1099,0 +8.092,-1.1095,-1.7327,-2.1688,0.75985,1.1095,0 +8.093,-1.1091,-1.7328,-2.1688,0.75994,1.1091,0 +8.094,-1.1087,-1.7329,-2.1687,0.76002,1.1087,0 +8.095,-1.1083,-1.733,-2.1687,0.7601,1.1083,0 +8.096,-1.1079,-1.7331,-2.1686,0.76018,1.1079,0 +8.097,-1.1075,-1.7332,-2.1686,0.76026,1.1075,0 +8.098,-1.1071,-1.7334,-2.1686,0.76033,1.1071,0 +8.099,-1.1067,-1.7335,-2.1685,0.76041,1.1067,0 +8.1,-1.1063,-1.7336,-2.1685,0.76048,1.1063,0 +8.101,-1.1059,-1.7337,-2.1684,0.76055,1.1059,0 +8.102,-1.1055,-1.7338,-2.1684,0.76062,1.1055,0 +8.103,-1.105,-1.7339,-2.1683,0.7607,1.105,0 +8.104,-1.1046,-1.7341,-2.1683,0.76077,1.1046,0 +8.105,-1.1042,-1.7342,-2.1683,0.76084,1.1042,0 +8.106,-1.1038,-1.7343,-2.1682,0.76092,1.1038,0 +8.107,-1.1034,-1.7344,-2.1682,0.76099,1.1034,0 +8.108,-1.103,-1.7345,-2.1681,0.76106,1.103,0 +8.109,-1.1026,-1.7347,-2.1681,0.76113,1.1026,0 +8.11,-1.1022,-1.7348,-2.168,0.76121,1.1022,0 +8.111,-1.1018,-1.7349,-2.168,0.76128,1.1018,0 +8.112,-1.1014,-1.735,-2.1679,0.76135,1.1014,0 +8.113,-1.101,-1.7351,-2.1679,0.76143,1.101,0 +8.114,-1.1006,-1.7352,-2.1678,0.7615,1.1006,0 +8.115,-1.1001,-1.7354,-2.1678,0.76157,1.1001,0 +8.116,-1.0997,-1.7355,-2.1678,0.76164,1.0997,0 +8.117,-1.0993,-1.7356,-2.1677,0.76172,1.0993,0 +8.118,-1.0989,-1.7357,-2.1677,0.76179,1.0989,0 +8.119,-1.0985,-1.7358,-2.1676,0.76186,1.0985,0 +8.12,-1.0981,-1.736,-2.1676,0.76194,1.0981,0 +8.121,-1.0977,-1.7361,-2.1675,0.76201,1.0977,0 +8.122,-1.0973,-1.7362,-2.1675,0.76208,1.0973,0 +8.123,-1.0969,-1.7363,-2.1674,0.76215,1.0969,0 +8.124,-1.0965,-1.7364,-2.1674,0.76223,1.0965,0 +8.125,-1.0961,-1.7365,-2.1673,0.7623,1.0961,0 +8.126,-1.0957,-1.7367,-2.1673,0.76237,1.0957,0 +8.127,-1.0952,-1.7368,-2.1673,0.76245,1.0952,0 +8.128,-1.0948,-1.7369,-2.1672,0.76252,1.0948,0 +8.129,-1.0944,-1.737,-2.1672,0.76259,1.0944,0 +8.13,-1.094,-1.7371,-2.1671,0.76266,1.094,0 +8.131,-1.0936,-1.7373,-2.1671,0.76274,1.0936,0 +8.132,-1.0932,-1.7374,-2.167,0.76281,1.0932,0 +8.133,-1.0928,-1.7375,-2.167,0.76288,1.0928,0 +8.134,-1.0924,-1.7376,-2.1669,0.76296,1.0924,0 +8.135,-1.092,-1.7377,-2.1669,0.76303,1.092,0 +8.136,-1.0916,-1.7378,-2.1669,0.7631,1.0916,0 +8.137,-1.0912,-1.738,-2.1668,0.76317,1.0912,0 +8.138,-1.0907,-1.7381,-2.1668,0.76325,1.0907,0 +8.139,-1.0903,-1.7382,-2.1667,0.76332,1.0903,0 +8.14,-1.0899,-1.7383,-2.1667,0.76339,1.0899,0 +8.141,-1.0895,-1.7384,-2.1666,0.76347,1.0895,0 +8.142,-1.0891,-1.7385,-2.1666,0.76354,1.0891,0 +8.143,-1.0887,-1.7387,-2.1665,0.76361,1.0887,0 +8.144,-1.0883,-1.7388,-2.1665,0.76368,1.0883,0 +8.145,-1.0879,-1.7389,-2.1664,0.76376,1.0879,0 +8.146,-1.0875,-1.739,-2.1664,0.76383,1.0875,0 +8.147,-1.0871,-1.7391,-2.1664,0.7639,1.0871,0 +8.148,-1.0867,-1.7393,-2.1663,0.76398,1.0867,0 +8.149,-1.0863,-1.7394,-2.1663,0.76405,1.0863,0 +8.15,-1.0858,-1.7395,-2.1662,0.76412,1.0858,0 +8.151,-1.0854,-1.7396,-2.1662,0.76419,1.0854,0 +8.152,-1.085,-1.7397,-2.1661,0.76427,1.085,0 +8.153,-1.0846,-1.7398,-2.1661,0.76434,1.0846,0 +8.154,-1.0842,-1.74,-2.166,0.76441,1.0842,0 +8.155,-1.0838,-1.7401,-2.166,0.76449,1.0838,0 +8.156,-1.0834,-1.7402,-2.166,0.76456,1.0834,0 +8.157,-1.083,-1.7403,-2.1659,0.76463,1.083,0 +8.158,-1.0826,-1.7404,-2.1659,0.7647,1.0826,0 +8.159,-1.0822,-1.7406,-2.1658,0.76478,1.0822,0 +8.16,-1.0818,-1.7407,-2.1658,0.76485,1.0818,0 +8.161,-1.0814,-1.7408,-2.1657,0.76492,1.0814,0 +8.162,-1.0809,-1.7409,-2.1657,0.765,1.0809,0 +8.163,-1.0805,-1.741,-2.1656,0.76507,1.0805,0 +8.164,-1.0801,-1.7411,-2.1656,0.76514,1.0801,0 +8.165,-1.0797,-1.7413,-2.1655,0.76521,1.0797,0 +8.166,-1.0793,-1.7414,-2.1655,0.76529,1.0793,0 +8.167,-1.0789,-1.7415,-2.1655,0.76536,1.0789,0 +8.168,-1.0785,-1.7416,-2.1654,0.76543,1.0785,0 +8.169,-1.0781,-1.7417,-2.1654,0.76551,1.0781,0 +8.17,-1.0777,-1.7418,-2.1653,0.76558,1.0777,0 +8.171,-1.0773,-1.742,-2.1653,0.76565,1.0773,0 +8.172,-1.0769,-1.7421,-2.1652,0.76572,1.0769,0 +8.173,-1.0765,-1.7422,-2.1652,0.7658,1.0765,0 +8.174,-1.0761,-1.7423,-2.1651,0.76587,1.0761,0 +8.175,-1.0756,-1.7424,-2.1651,0.76594,1.0756,0 +8.176,-1.0752,-1.7426,-2.165,0.76601,1.0752,0 +8.177,-1.0748,-1.7427,-2.165,0.76608,1.0748,0 +8.178,-1.0744,-1.7428,-2.1649,0.76615,1.0744,0 +8.179,-1.074,-1.7429,-2.1649,0.76622,1.074,0 +8.18,-1.0736,-1.7431,-2.1648,0.76629,1.0736,0 +8.181,-1.0732,-1.7432,-2.1648,0.76636,1.0732,0 +8.182,-1.0728,-1.7433,-2.1647,0.76643,1.0728,0 +8.183,-1.0724,-1.7435,-2.1646,0.7665,1.0724,0 +8.184,-1.072,-1.7436,-2.1646,0.76657,1.072,0 +8.185,-1.0716,-1.7437,-2.1645,0.76663,1.0716,0 +8.186,-1.0712,-1.7438,-2.1645,0.7667,1.0712,0 +8.187,-1.0708,-1.744,-2.1644,0.76677,1.0708,0 +8.188,-1.0704,-1.7441,-2.1643,0.76684,1.0704,0 +8.189,-1.07,-1.7442,-2.1643,0.76691,1.07,0 +8.19,-1.0697,-1.7444,-2.1642,0.76698,1.0697,0 +8.191,-1.0693,-1.7445,-2.1641,0.76705,1.0693,0 +8.192,-1.0689,-1.7446,-2.1641,0.76711,1.0689,0 +8.193,-1.0685,-1.7448,-2.164,0.76718,1.0685,0 +8.194,-1.0681,-1.7449,-2.164,0.76725,1.0681,0 +8.195,-1.0677,-1.745,-2.1639,0.76732,1.0677,0 +8.196,-1.0673,-1.7451,-2.1638,0.76739,1.0673,0 +8.197,-1.0669,-1.7453,-2.1638,0.76746,1.0669,0 +8.198,-1.0665,-1.7454,-2.1637,0.76752,1.0665,0 +8.199,-1.0661,-1.7455,-2.1637,0.76759,1.0661,0 +8.2,-1.0657,-1.7457,-2.1636,0.76766,1.0657,0 +8.201,-1.0653,-1.7458,-2.1635,0.76773,1.0653,0 +8.202,-1.0649,-1.7459,-2.1635,0.7678,1.0649,0 +8.203,-1.0645,-1.7461,-2.1634,0.76787,1.0645,0 +8.204,-1.0641,-1.7462,-2.1633,0.76793,1.0641,0 +8.205,-1.0637,-1.7463,-2.1633,0.768,1.0637,0 +8.206,-1.0633,-1.7464,-2.1632,0.76807,1.0633,0 +8.207,-1.0629,-1.7466,-2.1632,0.76814,1.0629,0 +8.208,-1.0625,-1.7467,-2.1631,0.76821,1.0625,0 +8.209,-1.0621,-1.7468,-2.163,0.76828,1.0621,0 +8.21,-1.0617,-1.747,-2.163,0.76834,1.0617,0 +8.211,-1.0613,-1.7471,-2.1629,0.76841,1.0613,0 +8.212,-1.0609,-1.7472,-2.1629,0.76848,1.0609,0 +8.213,-1.0605,-1.7474,-2.1628,0.76855,1.0605,0 +8.214,-1.0601,-1.7475,-2.1627,0.76862,1.0601,0 +8.215,-1.0597,-1.7476,-2.1627,0.76869,1.0597,0 +8.216,-1.0593,-1.7477,-2.1626,0.76875,1.0593,0 +8.217,-1.0589,-1.7479,-2.1625,0.76882,1.0589,0 +8.218,-1.0585,-1.748,-2.1625,0.76889,1.0585,0 +8.219,-1.0581,-1.7481,-2.1624,0.76896,1.0581,0 +8.22,-1.0577,-1.7483,-2.1624,0.76903,1.0577,0 +8.221,-1.0573,-1.7484,-2.1623,0.7691,1.0573,0 +8.222,-1.0569,-1.7485,-2.1622,0.76916,1.0569,0 +8.223,-1.0565,-1.7486,-2.1622,0.76923,1.0565,0 +8.224,-1.0561,-1.7488,-2.1621,0.7693,1.0561,0 +8.225,-1.0557,-1.7489,-2.1621,0.76937,1.0557,0 +8.226,-1.0553,-1.749,-2.162,0.76944,1.0553,0 +8.227,-1.0549,-1.7492,-2.1619,0.76951,1.0549,0 +8.228,-1.0545,-1.7493,-2.1619,0.76957,1.0545,0 +8.229,-1.0541,-1.7494,-2.1618,0.76964,1.0541,0 +8.23,-1.0537,-1.7496,-2.1617,0.76971,1.0537,0 +8.231,-1.0533,-1.7497,-2.1617,0.76978,1.0533,0 +8.232,-1.0529,-1.7498,-2.1616,0.76985,1.0529,0 +8.233,-1.0525,-1.7499,-2.1616,0.76992,1.0525,0 +8.234,-1.0521,-1.7501,-2.1615,0.76999,1.0521,0 +8.235,-1.0517,-1.7502,-2.1614,0.77005,1.0517,0 +8.236,-1.0513,-1.7503,-2.1614,0.77012,1.0513,0 +8.237,-1.0509,-1.7505,-2.1613,0.77019,1.0509,0 +8.238,-1.0505,-1.7506,-2.1613,0.77026,1.0505,0 +8.239,-1.0501,-1.7507,-2.1612,0.77033,1.0501,0 +8.24,-1.0497,-1.7509,-2.1611,0.7704,1.0497,0 +8.241,-1.0494,-1.751,-2.1611,0.77046,1.0494,0 +8.242,-1.049,-1.7511,-2.161,0.77053,1.049,0 +8.243,-1.0486,-1.7512,-2.1609,0.7706,1.0486,0 +8.244,-1.0482,-1.7514,-2.1609,0.77067,1.0482,0 +8.245,-1.0478,-1.7515,-2.1608,0.77074,1.0478,0 +8.246,-1.0474,-1.7516,-2.1608,0.77081,1.0474,0 +8.247,-1.047,-1.7518,-2.1607,0.77087,1.047,0 +8.248,-1.0466,-1.7519,-2.1606,0.77094,1.0466,0 +8.249,-1.0462,-1.752,-2.1606,0.77101,1.0462,0 +8.25,-1.0458,-1.7522,-2.1605,0.77108,1.0458,0 +8.251,-1.0454,-1.7523,-2.1605,0.77115,1.0454,0 +8.252,-1.045,-1.7524,-2.1604,0.77122,1.045,0 +8.253,-1.0446,-1.7525,-2.1603,0.77128,1.0446,0 +8.254,-1.0442,-1.7527,-2.1603,0.77135,1.0442,0 +8.255,-1.0438,-1.7528,-2.1602,0.77142,1.0438,0 +8.256,-1.0434,-1.7529,-2.1601,0.77149,1.0434,0 +8.257,-1.043,-1.7531,-2.1601,0.77155,1.043,0 +8.258,-1.0426,-1.7532,-2.16,0.77162,1.0426,0 +8.259,-1.0422,-1.7533,-2.1599,0.77168,1.0422,0 +8.26,-1.0418,-1.7535,-2.1599,0.77174,1.0418,0 +8.261,-1.0414,-1.7536,-2.1598,0.77179,1.0414,0 +8.262,-1.041,-1.7537,-2.1597,0.77185,1.041,0 +8.263,-1.0406,-1.7538,-2.1596,0.7719,1.0406,0 +8.264,-1.0402,-1.754,-2.1596,0.77195,1.0402,0 +8.265,-1.0399,-1.7541,-2.1595,0.772,1.0399,0 +8.266,-1.0395,-1.7542,-2.1594,0.77205,1.0395,0 +8.267,-1.0391,-1.7544,-2.1593,0.7721,1.0391,0 +8.268,-1.0387,-1.7545,-2.1592,0.77215,1.0387,0 +8.269,-1.0383,-1.7546,-2.1592,0.7722,1.0383,0 +8.27,-1.0379,-1.7548,-2.1591,0.77225,1.0379,0 +8.271,-1.0375,-1.7549,-2.159,0.7723,1.0375,0 +8.272,-1.0371,-1.755,-2.1589,0.77235,1.0371,0 +8.273,-1.0368,-1.7552,-2.1588,0.77239,1.0368,0 +8.274,-1.0364,-1.7553,-2.1587,0.77244,1.0364,0 +8.275,-1.036,-1.7554,-2.1587,0.77249,1.036,0 +8.276,-1.0356,-1.7556,-2.1586,0.77254,1.0356,0 +8.277,-1.0352,-1.7557,-2.1585,0.77259,1.0352,0 +8.278,-1.0348,-1.7558,-2.1584,0.77264,1.0348,0 +8.279,-1.0344,-1.756,-2.1583,0.77269,1.0344,0 +8.28,-1.034,-1.7561,-2.1582,0.77274,1.034,0 +8.281,-1.0337,-1.7562,-2.1582,0.77279,1.0337,0 +8.282,-1.0333,-1.7563,-2.1581,0.77284,1.0333,0 +8.283,-1.0329,-1.7565,-2.158,0.77288,1.0329,0 +8.284,-1.0325,-1.7566,-2.1579,0.77293,1.0325,0 +8.285,-1.0321,-1.7567,-2.1578,0.77298,1.0321,0 +8.286,-1.0317,-1.7569,-2.1578,0.77303,1.0317,0 +8.287,-1.0313,-1.757,-2.1577,0.77308,1.0313,0 +8.288,-1.031,-1.7571,-2.1576,0.77313,1.031,0 +8.289,-1.0306,-1.7573,-2.1575,0.77318,1.0306,0 +8.29,-1.0302,-1.7574,-2.1574,0.77323,1.0302,0 +8.291,-1.0298,-1.7575,-2.1573,0.77328,1.0298,0 +8.292,-1.0294,-1.7577,-2.1573,0.77333,1.0294,0 +8.293,-1.029,-1.7578,-2.1572,0.77337,1.029,0 +8.294,-1.0286,-1.7579,-2.1571,0.77342,1.0286,0 +8.295,-1.0282,-1.7581,-2.157,0.77347,1.0282,0 +8.296,-1.0279,-1.7582,-2.1569,0.77352,1.0279,0 +8.297,-1.0275,-1.7583,-2.1568,0.77357,1.0275,0 +8.298,-1.0271,-1.7584,-2.1568,0.77362,1.0271,0 +8.299,-1.0267,-1.7586,-2.1567,0.77367,1.0267,0 +8.3,-1.0263,-1.7587,-2.1566,0.77372,1.0263,0 +8.301,-1.0259,-1.7588,-2.1565,0.77377,1.0259,0 +8.302,-1.0255,-1.759,-2.1564,0.77382,1.0255,0 +8.303,-1.0251,-1.7591,-2.1564,0.77386,1.0251,0 +8.304,-1.0248,-1.7592,-2.1563,0.77391,1.0248,0 +8.305,-1.0244,-1.7594,-2.1562,0.77396,1.0244,0 +8.306,-1.024,-1.7595,-2.1561,0.77401,1.024,0 +8.307,-1.0236,-1.7596,-2.156,0.77406,1.0236,0 +8.308,-1.0232,-1.7598,-2.1559,0.77411,1.0232,0 +8.309,-1.0228,-1.7599,-2.1559,0.77416,1.0228,0 +8.31,-1.0224,-1.76,-2.1558,0.77421,1.0224,0 +8.311,-1.022,-1.7602,-2.1557,0.77426,1.022,0 +8.312,-1.0217,-1.7603,-2.1556,0.77431,1.0217,0 +8.313,-1.0213,-1.7604,-2.1555,0.77435,1.0213,0 +8.314,-1.0209,-1.7606,-2.1554,0.7744,1.0209,0 +8.315,-1.0205,-1.7607,-2.1554,0.77445,1.0205,0 +8.316,-1.0201,-1.7608,-2.1553,0.7745,1.0201,0 +8.317,-1.0197,-1.7609,-2.1552,0.77455,1.0197,0 +8.318,-1.0193,-1.7611,-2.1551,0.7746,1.0193,0 +8.319,-1.0189,-1.7612,-2.155,0.77465,1.0189,0 +8.32,-1.0186,-1.7613,-2.1549,0.7747,1.0186,0 +8.321,-1.0182,-1.7615,-2.1549,0.77475,1.0182,0 +8.322,-1.0178,-1.7616,-2.1548,0.7748,1.0178,0 +8.323,-1.0174,-1.7617,-2.1547,0.77485,1.0174,0 +8.324,-1.017,-1.7619,-2.1546,0.77489,1.017,0 +8.325,-1.0166,-1.762,-2.1545,0.77494,1.0166,0 +8.326,-1.0162,-1.7621,-2.1545,0.77499,1.0162,0 +8.327,-1.0159,-1.7623,-2.1544,0.77504,1.0159,0 +8.328,-1.0155,-1.7624,-2.1543,0.77509,1.0155,0 +8.329,-1.0151,-1.7625,-2.1542,0.77514,1.0151,0 +8.33,-1.0147,-1.7627,-2.1541,0.77519,1.0147,0 +8.331,-1.0143,-1.7628,-2.154,0.77524,1.0143,0 +8.332,-1.0139,-1.7629,-2.154,0.77529,1.0139,0 +8.333,-1.0135,-1.7631,-2.1539,0.77534,1.0135,0 +8.334,-1.0131,-1.7632,-2.1538,0.77538,1.0131,0 +8.335,-1.0128,-1.7633,-2.1537,0.77543,1.0128,0 +8.336,-1.0124,-1.7634,-2.1536,0.77548,1.0124,0 +8.337,-1.012,-1.7636,-2.1535,0.77553,1.012,0 +8.338,-1.0116,-1.7637,-2.1535,0.77558,1.0116,0 +8.339,-1.0112,-1.7638,-2.1534,0.77563,1.0112,0 +8.34,-1.0108,-1.764,-2.1533,0.77568,1.0108,0 +8.341,-1.0104,-1.7641,-2.1532,0.77572,1.0104,0 +8.342,-1.0101,-1.7642,-2.1531,0.77577,1.0101,0 +8.343,-1.0097,-1.7644,-2.153,0.77582,1.0097,0 +8.344,-1.0093,-1.7645,-2.1529,0.77586,1.0093,0 +8.345,-1.0089,-1.7647,-2.1528,0.77591,1.0089,0 +8.346,-1.0085,-1.7648,-2.1527,0.77595,1.0085,0 +8.347,-1.0082,-1.7649,-2.1527,0.776,1.0082,0 +8.348,-1.0078,-1.7651,-2.1526,0.77604,1.0078,0 +8.349,-1.0074,-1.7652,-2.1525,0.77609,1.0074,0 +8.35,-1.007,-1.7654,-2.1524,0.77613,1.007,0 +8.351,-1.0067,-1.7655,-2.1523,0.77617,1.0067,0 +8.352,-1.0063,-1.7656,-2.1522,0.77622,1.0063,0 +8.353,-1.0059,-1.7658,-2.1521,0.77626,1.0059,0 +8.354,-1.0055,-1.7659,-2.152,0.77631,1.0055,0 +8.355,-1.0052,-1.7661,-2.1519,0.77635,1.0052,0 +8.356,-1.0048,-1.7662,-2.1518,0.77639,1.0048,0 +8.357,-1.0044,-1.7664,-2.1517,0.77644,1.0044,0 +8.358,-1.004,-1.7665,-2.1516,0.77648,1.004,0 +8.359,-1.0037,-1.7666,-2.1515,0.77652,1.0037,0 +8.36,-1.0033,-1.7668,-2.1514,0.77657,1.0033,0 +8.361,-1.0029,-1.7669,-2.1513,0.77661,1.0029,0 +8.362,-1.0025,-1.7671,-2.1512,0.77666,1.0025,0 +8.363,-1.0021,-1.7672,-2.1511,0.7767,1.0021,0 +8.364,-1.0018,-1.7674,-2.151,0.77674,1.0018,0 +8.365,-1.0014,-1.7675,-2.1509,0.77679,1.0014,0 +8.366,-1.001,-1.7676,-2.1508,0.77683,1.001,0 +8.367,-1.0006,-1.7678,-2.1507,0.77688,1.0006,0 +8.368,-1.0003,-1.7679,-2.1506,0.77692,1.0003,0 +8.369,-0.99989,-1.7681,-2.1505,0.77696,0.99989,0 +8.37,-0.99952,-1.7682,-2.1504,0.77701,0.99952,0 +8.371,-0.99914,-1.7684,-2.1503,0.77705,0.99914,0 +8.372,-0.99877,-1.7685,-2.1502,0.77709,0.99877,0 +8.373,-0.99839,-1.7686,-2.1501,0.77714,0.99839,0 +8.374,-0.99801,-1.7688,-2.15,0.77718,0.99801,0 +8.375,-0.99764,-1.7689,-2.1499,0.77723,0.99764,0 +8.376,-0.99726,-1.7691,-2.1498,0.77727,0.99726,0 +8.377,-0.99689,-1.7692,-2.1497,0.77731,0.99689,0 +8.378,-0.99651,-1.7693,-2.1496,0.77736,0.99651,0 +8.379,-0.99614,-1.7695,-2.1495,0.7774,0.99614,0 +8.38,-0.99576,-1.7696,-2.1494,0.77745,0.99576,0 +8.381,-0.99538,-1.7698,-2.1493,0.77749,0.99538,0 +8.382,-0.99501,-1.7699,-2.1492,0.77753,0.99501,0 +8.383,-0.99463,-1.7701,-2.1491,0.77758,0.99463,0 +8.384,-0.99426,-1.7702,-2.149,0.77762,0.99426,0 +8.385,-0.99388,-1.7703,-2.1489,0.77766,0.99388,0 +8.386,-0.99351,-1.7705,-2.1488,0.77771,0.99351,0 +8.387,-0.99313,-1.7706,-2.1487,0.77775,0.99313,0 +8.388,-0.99275,-1.7708,-2.1486,0.7778,0.99275,0 +8.389,-0.99238,-1.7709,-2.1485,0.77784,0.99238,0 +8.39,-0.992,-1.7711,-2.1484,0.77788,0.992,0 +8.391,-0.99163,-1.7712,-2.1483,0.77793,0.99163,0 +8.392,-0.99125,-1.7713,-2.1482,0.77797,0.99125,0 +8.393,-0.99088,-1.7715,-2.1481,0.77801,0.99088,0 +8.394,-0.9905,-1.7716,-2.148,0.77806,0.9905,0 +8.395,-0.99012,-1.7718,-2.1479,0.7781,0.99012,0 +8.396,-0.98975,-1.7719,-2.1478,0.77815,0.98975,0 +8.397,-0.98937,-1.772,-2.1477,0.77819,0.98937,0 +8.398,-0.989,-1.7722,-2.1476,0.77823,0.989,0 +8.399,-0.98862,-1.7723,-2.1475,0.77828,0.98862,0 +8.4,-0.98825,-1.7725,-2.1474,0.77832,0.98825,0 +8.401,-0.98787,-1.7726,-2.1473,0.77837,0.98787,0 +8.402,-0.98749,-1.7728,-2.1472,0.77841,0.98749,0 +8.403,-0.98712,-1.7729,-2.1471,0.77845,0.98712,0 +8.404,-0.98674,-1.773,-2.147,0.7785,0.98674,0 +8.405,-0.98637,-1.7732,-2.1469,0.77854,0.98637,0 +8.406,-0.98599,-1.7733,-2.1469,0.77858,0.98599,0 +8.407,-0.98562,-1.7735,-2.1468,0.77863,0.98562,0 +8.408,-0.98524,-1.7736,-2.1467,0.77867,0.98524,0 +8.409,-0.98486,-1.7738,-2.1466,0.77872,0.98486,0 +8.41,-0.98449,-1.7739,-2.1465,0.77876,0.98449,0 +8.411,-0.98411,-1.774,-2.1464,0.7788,0.98411,0 +8.412,-0.98374,-1.7742,-2.1463,0.77885,0.98374,0 +8.413,-0.98336,-1.7743,-2.1462,0.77889,0.98336,0 +8.414,-0.98299,-1.7745,-2.1461,0.77894,0.98299,0 +8.415,-0.98261,-1.7746,-2.146,0.77898,0.98261,0 +8.416,-0.98223,-1.7747,-2.1459,0.77902,0.98223,0 +8.417,-0.98186,-1.7749,-2.1458,0.77907,0.98186,0 +8.418,-0.98148,-1.775,-2.1457,0.77911,0.98148,0 +8.419,-0.98111,-1.7752,-2.1456,0.77915,0.98111,0 +8.42,-0.98073,-1.7753,-2.1455,0.7792,0.98073,0 +8.421,-0.98035,-1.7755,-2.1454,0.77924,0.98035,0 +8.422,-0.97998,-1.7756,-2.1453,0.77928,0.97998,0 +8.423,-0.97961,-1.7757,-2.1452,0.77932,0.97961,0 +8.424,-0.97924,-1.7759,-2.1451,0.77936,0.97924,0 +8.425,-0.97888,-1.776,-2.145,0.7794,0.97888,0 +8.426,-0.97851,-1.7762,-2.1449,0.77943,0.97851,0 +8.427,-0.97815,-1.7763,-2.1448,0.77947,0.97815,0 +8.428,-0.97779,-1.7764,-2.1446,0.7795,0.97779,0 +8.429,-0.97744,-1.7766,-2.1445,0.77953,0.97744,0 +8.43,-0.97708,-1.7767,-2.1444,0.77956,0.97708,0 +8.431,-0.97673,-1.7769,-2.1443,0.77958,0.97673,0 +8.432,-0.97638,-1.777,-2.1442,0.77961,0.97638,0 +8.433,-0.97603,-1.7771,-2.1441,0.77963,0.97603,0 +8.434,-0.97568,-1.7773,-2.144,0.77966,0.97568,0 +8.435,-0.97533,-1.7774,-2.1439,0.77968,0.97533,0 +8.436,-0.97498,-1.7776,-2.1437,0.77971,0.97498,0 +8.437,-0.97463,-1.7777,-2.1436,0.77973,0.97463,0 +8.438,-0.97428,-1.7778,-2.1435,0.77976,0.97428,0 +8.439,-0.97393,-1.778,-2.1434,0.77978,0.97393,0 +8.44,-0.97358,-1.7781,-2.1433,0.77981,0.97358,0 +8.441,-0.97323,-1.7782,-2.1432,0.77984,0.97323,0 +8.442,-0.97288,-1.7784,-2.1431,0.77986,0.97288,0 +8.443,-0.97253,-1.7785,-2.143,0.77989,0.97253,0 +8.444,-0.97218,-1.7787,-2.1428,0.77991,0.97218,0 +8.445,-0.97183,-1.7788,-2.1427,0.77994,0.97183,0 +8.446,-0.97148,-1.7789,-2.1426,0.77996,0.97148,0 +8.447,-0.97113,-1.7791,-2.1425,0.77999,0.97113,0 +8.448,-0.97078,-1.7792,-2.1424,0.78001,0.97078,0 +8.449,-0.97043,-1.7794,-2.1423,0.78004,0.97043,0 +8.45,-0.97008,-1.7795,-2.1422,0.78006,0.97008,0 +8.451,-0.96972,-1.7796,-2.1421,0.78009,0.96972,0 +8.452,-0.96937,-1.7798,-2.1419,0.78011,0.96937,0 +8.453,-0.96902,-1.7799,-2.1418,0.78014,0.96902,0 +8.454,-0.96867,-1.78,-2.1417,0.78017,0.96867,0 +8.455,-0.96832,-1.7802,-2.1416,0.78019,0.96832,0 +8.456,-0.96797,-1.7803,-2.1415,0.78022,0.96797,0 +8.457,-0.96762,-1.7805,-2.1414,0.78024,0.96762,0 +8.458,-0.96727,-1.7806,-2.1413,0.78027,0.96727,0 +8.459,-0.96692,-1.7807,-2.1411,0.78029,0.96692,0 +8.46,-0.96657,-1.7809,-2.141,0.78032,0.96657,0 +8.461,-0.96622,-1.781,-2.1409,0.78034,0.96622,0 +8.462,-0.96587,-1.7812,-2.1408,0.78037,0.96587,0 +8.463,-0.96552,-1.7813,-2.1407,0.78039,0.96552,0 +8.464,-0.96517,-1.7814,-2.1406,0.78042,0.96517,0 +8.465,-0.96482,-1.7816,-2.1405,0.78044,0.96482,0 +8.466,-0.96447,-1.7817,-2.1404,0.78047,0.96447,0 +8.467,-0.96412,-1.7818,-2.1402,0.7805,0.96412,0 +8.468,-0.96377,-1.782,-2.1401,0.78052,0.96377,0 +8.469,-0.96342,-1.7821,-2.14,0.78055,0.96342,0 +8.47,-0.96307,-1.7823,-2.1399,0.78057,0.96307,0 +8.471,-0.96272,-1.7824,-2.1398,0.7806,0.96272,0 +8.472,-0.96237,-1.7825,-2.1397,0.78062,0.96237,0 +8.473,-0.96201,-1.7827,-2.1396,0.78065,0.96201,0 +8.474,-0.96166,-1.7828,-2.1395,0.78067,0.96166,0 +8.475,-0.96131,-1.783,-2.1393,0.7807,0.96131,0 +8.476,-0.96096,-1.7831,-2.1392,0.78072,0.96096,0 +8.477,-0.96061,-1.7832,-2.1391,0.78075,0.96061,0 +8.478,-0.96026,-1.7834,-2.139,0.78077,0.96026,0 +8.479,-0.95991,-1.7835,-2.1389,0.7808,0.95991,0 +8.48,-0.95956,-1.7836,-2.1388,0.78083,0.95956,0 +8.481,-0.95921,-1.7838,-2.1387,0.78085,0.95921,0 +8.482,-0.95886,-1.7839,-2.1385,0.78088,0.95886,0 +8.483,-0.95851,-1.7841,-2.1384,0.7809,0.95851,0 +8.484,-0.95816,-1.7842,-2.1383,0.78093,0.95816,0 +8.485,-0.95781,-1.7843,-2.1382,0.78095,0.95781,0 +8.486,-0.95746,-1.7845,-2.1381,0.78098,0.95746,0 +8.487,-0.95711,-1.7846,-2.138,0.781,0.95711,0 +8.488,-0.95676,-1.7848,-2.1379,0.78103,0.95676,0 +8.489,-0.95641,-1.7849,-2.1378,0.78105,0.95641,0 +8.49,-0.95606,-1.785,-2.1376,0.78108,0.95606,0 +8.491,-0.95571,-1.7852,-2.1375,0.78111,0.95571,0 +8.492,-0.95536,-1.7853,-2.1374,0.78113,0.95536,0 +8.493,-0.95501,-1.7854,-2.1373,0.78116,0.95501,0 +8.494,-0.95466,-1.7856,-2.1372,0.78118,0.95466,0 +8.495,-0.9543,-1.7857,-2.1371,0.78121,0.9543,0 +8.496,-0.95395,-1.7859,-2.137,0.78123,0.95395,0 +8.497,-0.9536,-1.786,-2.1369,0.78126,0.9536,0 +8.498,-0.95325,-1.7861,-2.1367,0.78128,0.95325,0 +8.499,-0.9529,-1.7863,-2.1366,0.78131,0.9529,0 +8.5,-0.95255,-1.7864,-2.1365,0.78133,0.95255,0 +8.501,-0.9522,-1.7866,-2.1364,0.78136,0.9522,0 +8.502,-0.95185,-1.7867,-2.1363,0.78138,0.95185,0 +8.503,-0.9515,-1.7868,-2.1362,0.78141,0.9515,0 +8.504,-0.95115,-1.787,-2.1361,0.78144,0.95115,0 +8.505,-0.9508,-1.7871,-2.1359,0.78146,0.9508,0 +8.506,-0.95045,-1.7872,-2.1358,0.78148,0.95045,0 +8.507,-0.95011,-1.7874,-2.1357,0.7815,0.95011,0 +8.508,-0.94977,-1.7875,-2.1356,0.78152,0.94977,0 +8.509,-0.94942,-1.7877,-2.1355,0.78154,0.94942,0 +8.51,-0.94908,-1.7878,-2.1353,0.78155,0.94908,0 +8.511,-0.94875,-1.7879,-2.1352,0.78156,0.94875,0 +8.512,-0.94841,-1.7881,-2.1351,0.78157,0.94841,0 +8.513,-0.94808,-1.7882,-2.135,0.78158,0.94808,0 +8.514,-0.94774,-1.7883,-2.1348,0.78159,0.94774,0 +8.515,-0.94741,-1.7885,-2.1347,0.78159,0.94741,0 +8.516,-0.94708,-1.7886,-2.1346,0.7816,0.94708,0 +8.517,-0.94674,-1.7887,-2.1345,0.78161,0.94674,0 +8.518,-0.94641,-1.7889,-2.1343,0.78162,0.94641,0 +8.519,-0.94608,-1.789,-2.1342,0.78162,0.94608,0 +8.52,-0.94575,-1.7892,-2.1341,0.78163,0.94575,0 +8.521,-0.94541,-1.7893,-2.1339,0.78164,0.94541,0 +8.522,-0.94508,-1.7894,-2.1338,0.78164,0.94508,0 +8.523,-0.94475,-1.7896,-2.1337,0.78165,0.94475,0 +8.524,-0.94441,-1.7897,-2.1336,0.78166,0.94441,0 +8.525,-0.94408,-1.7898,-2.1334,0.78166,0.94408,0 +8.526,-0.94375,-1.79,-2.1333,0.78167,0.94375,0 +8.527,-0.94342,-1.7901,-2.1332,0.78168,0.94342,0 +8.528,-0.94308,-1.7902,-2.133,0.78168,0.94308,0 +8.529,-0.94275,-1.7904,-2.1329,0.78169,0.94275,0 +8.53,-0.94242,-1.7905,-2.1328,0.7817,0.94242,0 +8.531,-0.94208,-1.7906,-2.1327,0.7817,0.94208,0 +8.532,-0.94175,-1.7908,-2.1325,0.78171,0.94175,0 +8.533,-0.94142,-1.7909,-2.1324,0.78172,0.94142,0 +8.534,-0.94109,-1.791,-2.1323,0.78172,0.94109,0 +8.535,-0.94075,-1.7912,-2.1321,0.78173,0.94075,0 +8.536,-0.94042,-1.7913,-2.132,0.78174,0.94042,0 +8.537,-0.94009,-1.7915,-2.1319,0.78175,0.94009,0 +8.538,-0.93976,-1.7916,-2.1318,0.78175,0.93976,0 +8.539,-0.93942,-1.7917,-2.1316,0.78176,0.93942,0 +8.54,-0.93909,-1.7919,-2.1315,0.78177,0.93909,0 +8.541,-0.93876,-1.792,-2.1314,0.78177,0.93876,0 +8.542,-0.93842,-1.7921,-2.1312,0.78178,0.93842,0 +8.543,-0.93809,-1.7923,-2.1311,0.78179,0.93809,0 +8.544,-0.93776,-1.7924,-2.131,0.78179,0.93776,0 +8.545,-0.93743,-1.7925,-2.1309,0.7818,0.93743,0 +8.546,-0.93709,-1.7927,-2.1307,0.78181,0.93709,0 +8.547,-0.93676,-1.7928,-2.1306,0.78181,0.93676,0 +8.548,-0.93643,-1.7929,-2.1305,0.78182,0.93643,0 +8.549,-0.93609,-1.7931,-2.1303,0.78183,0.93609,0 +8.55,-0.93576,-1.7932,-2.1302,0.78183,0.93576,0 +8.551,-0.93543,-1.7934,-2.1301,0.78184,0.93543,0 +8.552,-0.9351,-1.7935,-2.13,0.78185,0.9351,0 +8.553,-0.93476,-1.7936,-2.1298,0.78185,0.93476,0 +8.554,-0.93443,-1.7938,-2.1297,0.78186,0.93443,0 +8.555,-0.9341,-1.7939,-2.1296,0.78187,0.9341,0 +8.556,-0.93376,-1.794,-2.1294,0.78187,0.93376,0 +8.557,-0.93343,-1.7942,-2.1293,0.78188,0.93343,0 +8.558,-0.9331,-1.7943,-2.1292,0.78189,0.9331,0 +8.559,-0.93277,-1.7944,-2.1291,0.7819,0.93277,0 +8.56,-0.93243,-1.7946,-2.1289,0.7819,0.93243,0 +8.561,-0.9321,-1.7947,-2.1288,0.78191,0.9321,0 +8.562,-0.93177,-1.7948,-2.1287,0.78192,0.93177,0 +8.563,-0.93144,-1.795,-2.1285,0.78192,0.93144,0 +8.564,-0.9311,-1.7951,-2.1284,0.78193,0.9311,0 +8.565,-0.93077,-1.7952,-2.1283,0.78194,0.93077,0 +8.566,-0.93044,-1.7954,-2.1282,0.78194,0.93044,0 +8.567,-0.9301,-1.7955,-2.128,0.78195,0.9301,0 +8.568,-0.92977,-1.7957,-2.1279,0.78196,0.92977,0 +8.569,-0.92944,-1.7958,-2.1278,0.78196,0.92944,0 +8.57,-0.92911,-1.7959,-2.1276,0.78197,0.92911,0 +8.571,-0.92877,-1.7961,-2.1275,0.78198,0.92877,0 +8.572,-0.92844,-1.7962,-2.1274,0.78198,0.92844,0 +8.573,-0.92811,-1.7963,-2.1272,0.78199,0.92811,0 +8.574,-0.92777,-1.7965,-2.1271,0.782,0.92777,0 +8.575,-0.92744,-1.7966,-2.127,0.782,0.92744,0 +8.576,-0.92711,-1.7967,-2.1269,0.78201,0.92711,0 +8.577,-0.92678,-1.7969,-2.1267,0.78202,0.92678,0 +8.578,-0.92644,-1.797,-2.1266,0.78202,0.92644,0 +8.579,-0.92611,-1.7971,-2.1265,0.78203,0.92611,0 +8.58,-0.92578,-1.7973,-2.1263,0.78204,0.92578,0 +8.581,-0.92544,-1.7974,-2.1262,0.78205,0.92544,0 +8.582,-0.92511,-1.7976,-2.1261,0.78205,0.92511,0 +8.583,-0.92478,-1.7977,-2.126,0.78206,0.92478,0 +8.584,-0.92445,-1.7978,-2.1258,0.78207,0.92445,0 +8.585,-0.92411,-1.798,-2.1257,0.78207,0.92411,0 +8.586,-0.92378,-1.7981,-2.1256,0.78208,0.92378,0 +8.587,-0.92345,-1.7982,-2.1254,0.78209,0.92345,0 +8.588,-0.92312,-1.7984,-2.1253,0.78209,0.92312,0 +8.589,-0.92281,-1.7985,-2.1252,0.7821,0.92281,0 +8.59,-0.9225,-1.7986,-2.1251,0.7821,0.9225,0 +8.591,-0.9222,-1.7987,-2.125,0.7821,0.9222,0 +8.592,-0.92191,-1.7989,-2.1248,0.78211,0.92191,0 +8.593,-0.92162,-1.799,-2.1247,0.78211,0.92162,0 +8.594,-0.92134,-1.7991,-2.1246,0.78211,0.92134,0 +8.595,-0.92108,-1.7992,-2.1245,0.78211,0.92108,0 +8.596,-0.92082,-1.7993,-2.1244,0.7821,0.92082,0 +8.597,-0.92056,-1.7994,-2.1243,0.7821,0.92056,0 +8.598,-0.92031,-1.7995,-2.1241,0.7821,0.92031,0 +8.599,-0.92006,-1.7997,-2.124,0.78209,0.92006,0 +8.6,-0.91981,-1.7998,-2.1239,0.78209,0.91981,0 +8.601,-0.91956,-1.7999,-2.1238,0.78209,0.91956,0 +8.602,-0.9193,-1.8,-2.1237,0.78209,0.9193,0 +8.603,-0.91905,-1.8001,-2.1236,0.78208,0.91905,0 +8.604,-0.9188,-1.8002,-2.1235,0.78208,0.9188,0 +8.605,-0.91855,-1.8003,-2.1234,0.78208,0.91855,0 +8.606,-0.9183,-1.8004,-2.1233,0.78207,0.9183,0 +8.607,-0.91804,-1.8005,-2.1231,0.78207,0.91804,0 +8.608,-0.91779,-1.8006,-2.123,0.78207,0.91779,0 +8.609,-0.91754,-1.8007,-2.1229,0.78206,0.91754,0 +8.61,-0.91729,-1.8008,-2.1228,0.78206,0.91729,0 +8.611,-0.91704,-1.8009,-2.1227,0.78206,0.91704,0 +8.612,-0.91678,-1.8011,-2.1226,0.78206,0.91678,0 +8.613,-0.91653,-1.8012,-2.1225,0.78205,0.91653,0 +8.614,-0.91628,-1.8013,-2.1224,0.78205,0.91628,0 +8.615,-0.91603,-1.8014,-2.1223,0.78205,0.91603,0 +8.616,-0.91577,-1.8015,-2.1221,0.78204,0.91577,0 +8.617,-0.91552,-1.8016,-2.122,0.78204,0.91552,0 +8.618,-0.91527,-1.8017,-2.1219,0.78204,0.91527,0 +8.619,-0.91502,-1.8018,-2.1218,0.78204,0.91502,0 +8.62,-0.91477,-1.8019,-2.1217,0.78203,0.91477,0 +8.621,-0.91451,-1.802,-2.1216,0.78203,0.91451,0 +8.622,-0.91426,-1.8021,-2.1215,0.78203,0.91426,0 +8.623,-0.91401,-1.8022,-2.1214,0.78202,0.91401,0 +8.624,-0.91376,-1.8024,-2.1213,0.78202,0.91376,0 +8.625,-0.91351,-1.8025,-2.1211,0.78202,0.91351,0 +8.626,-0.91325,-1.8026,-2.121,0.78201,0.91325,0 +8.627,-0.913,-1.8027,-2.1209,0.78201,0.913,0 +8.628,-0.91275,-1.8028,-2.1208,0.78201,0.91275,0 +8.629,-0.9125,-1.8029,-2.1207,0.78201,0.9125,0 +8.63,-0.91225,-1.803,-2.1206,0.782,0.91225,0 +8.631,-0.91199,-1.8031,-2.1205,0.782,0.91199,0 +8.632,-0.91174,-1.8032,-2.1204,0.782,0.91174,0 +8.633,-0.91149,-1.8033,-2.1203,0.78199,0.91149,0 +8.634,-0.91124,-1.8034,-2.1202,0.78199,0.91124,0 +8.635,-0.91099,-1.8035,-2.12,0.78199,0.91099,0 +8.636,-0.91073,-1.8036,-2.1199,0.78199,0.91073,0 +8.637,-0.91048,-1.8038,-2.1198,0.78198,0.91048,0 +8.638,-0.91023,-1.8039,-2.1197,0.78198,0.91023,0 +8.639,-0.90998,-1.804,-2.1196,0.78198,0.90998,0 +8.64,-0.90972,-1.8041,-2.1195,0.78197,0.90972,0 +8.641,-0.90947,-1.8042,-2.1194,0.78197,0.90947,0 +8.642,-0.90922,-1.8043,-2.1193,0.78197,0.90922,0 +8.643,-0.90897,-1.8044,-2.1192,0.78196,0.90897,0 +8.644,-0.90872,-1.8045,-2.119,0.78196,0.90872,0 +8.645,-0.90846,-1.8046,-2.1189,0.78196,0.90846,0 +8.646,-0.90821,-1.8047,-2.1188,0.78196,0.90821,0 +8.647,-0.90796,-1.8048,-2.1187,0.78195,0.90796,0 +8.648,-0.90771,-1.8049,-2.1186,0.78195,0.90771,0 +8.649,-0.90746,-1.8051,-2.1185,0.78195,0.90746,0 +8.65,-0.9072,-1.8052,-2.1184,0.78194,0.9072,0 +8.651,-0.90695,-1.8053,-2.1183,0.78194,0.90695,0 +8.652,-0.9067,-1.8054,-2.1182,0.78194,0.9067,0 +8.653,-0.90645,-1.8055,-2.118,0.78194,0.90645,0 +8.654,-0.9062,-1.8056,-2.1179,0.78193,0.9062,0 +8.655,-0.90594,-1.8057,-2.1178,0.78193,0.90594,0 +8.656,-0.90569,-1.8058,-2.1177,0.78193,0.90569,0 +8.657,-0.90544,-1.8059,-2.1176,0.78192,0.90544,0 +8.658,-0.90519,-1.806,-2.1175,0.78192,0.90519,0 +8.659,-0.90494,-1.8061,-2.1174,0.78192,0.90494,0 +8.66,-0.90468,-1.8062,-2.1173,0.78191,0.90468,0 +8.661,-0.90443,-1.8064,-2.1172,0.78191,0.90443,0 +8.662,-0.90418,-1.8065,-2.117,0.78191,0.90418,0 +8.663,-0.90393,-1.8066,-2.1169,0.78191,0.90393,0 +8.664,-0.90367,-1.8067,-2.1168,0.7819,0.90367,0 +8.665,-0.90342,-1.8068,-2.1167,0.7819,0.90342,0 +8.666,-0.90317,-1.8069,-2.1166,0.7819,0.90317,0 +8.667,-0.90292,-1.807,-2.1165,0.78189,0.90292,0 +8.668,-0.90267,-1.8071,-2.1164,0.78189,0.90267,0 +8.669,-0.90241,-1.8072,-2.1163,0.78189,0.90241,0 +8.67,-0.90216,-1.8073,-2.1162,0.78188,0.90216,0 +8.671,-0.90191,-1.8074,-2.116,0.78188,0.90191,0 +8.672,-0.90167,-1.8075,-2.1159,0.78188,0.90167,0 +8.673,-0.90142,-1.8076,-2.1158,0.78188,0.90142,0 +8.674,-0.90118,-1.8078,-2.1157,0.78187,0.90118,0 +8.675,-0.90094,-1.8079,-2.1156,0.78187,0.90094,0 +8.676,-0.9007,-1.808,-2.1155,0.78187,0.9007,0 +8.677,-0.90047,-1.8081,-2.1154,0.78186,0.90047,0 +8.678,-0.90024,-1.8082,-2.1153,0.78186,0.90024,0 +8.679,-0.90001,-1.8083,-2.1152,0.78186,0.90001,0 +8.68,-0.89978,-1.8084,-2.1151,0.78185,0.89978,0 +8.681,-0.89955,-1.8085,-2.1149,0.78185,0.89955,0 +8.682,-0.89933,-1.8086,-2.1148,0.78185,0.89933,0 +8.683,-0.8991,-1.8087,-2.1147,0.78184,0.8991,0 +8.684,-0.89887,-1.8088,-2.1146,0.78184,0.89887,0 +8.685,-0.89865,-1.8089,-2.1145,0.78184,0.89865,0 +8.686,-0.89842,-1.809,-2.1144,0.78183,0.89842,0 +8.687,-0.89819,-1.8091,-2.1143,0.78183,0.89819,0 +8.688,-0.89797,-1.8092,-2.1142,0.78183,0.89797,0 +8.689,-0.89774,-1.8093,-2.1141,0.78182,0.89774,0 +8.69,-0.89751,-1.8094,-2.114,0.78182,0.89751,0 +8.691,-0.89729,-1.8095,-2.1139,0.78182,0.89729,0 +8.692,-0.89706,-1.8097,-2.1138,0.78181,0.89706,0 +8.693,-0.89683,-1.8098,-2.1136,0.78181,0.89683,0 +8.694,-0.89661,-1.8099,-2.1135,0.78181,0.89661,0 +8.695,-0.89638,-1.81,-2.1134,0.7818,0.89638,0 +8.696,-0.89615,-1.8101,-2.1133,0.7818,0.89615,0 +8.697,-0.89593,-1.8102,-2.1132,0.7818,0.89593,0 +8.698,-0.8957,-1.8103,-2.1131,0.78179,0.8957,0 +8.699,-0.89547,-1.8104,-2.113,0.78179,0.89547,0 +8.7,-0.89524,-1.8105,-2.1129,0.78179,0.89524,0 +8.701,-0.89502,-1.8106,-2.1128,0.78178,0.89502,0 +8.702,-0.89479,-1.8107,-2.1127,0.78178,0.89479,0 +8.703,-0.89456,-1.8108,-2.1126,0.78178,0.89456,0 +8.704,-0.89434,-1.8109,-2.1124,0.78177,0.89434,0 +8.705,-0.89411,-1.811,-2.1123,0.78177,0.89411,0 +8.706,-0.89388,-1.8111,-2.1122,0.78177,0.89388,0 +8.707,-0.89366,-1.8112,-2.1121,0.78176,0.89366,0 +8.708,-0.89343,-1.8113,-2.112,0.78176,0.89343,0 +8.709,-0.8932,-1.8114,-2.1119,0.78176,0.8932,0 +8.71,-0.89298,-1.8116,-2.1118,0.78175,0.89298,0 +8.711,-0.89275,-1.8117,-2.1117,0.78175,0.89275,0 +8.712,-0.89252,-1.8118,-2.1116,0.78174,0.89252,0 +8.713,-0.8923,-1.8119,-2.1115,0.78174,0.8923,0 +8.714,-0.89207,-1.812,-2.1114,0.78174,0.89207,0 +8.715,-0.89184,-1.8121,-2.1112,0.78173,0.89184,0 +8.716,-0.89162,-1.8122,-2.1111,0.78173,0.89162,0 +8.717,-0.89139,-1.8123,-2.111,0.78173,0.89139,0 +8.718,-0.89116,-1.8124,-2.1109,0.78172,0.89116,0 +8.719,-0.89094,-1.8125,-2.1108,0.78172,0.89094,0 +8.72,-0.89071,-1.8126,-2.1107,0.78172,0.89071,0 +8.721,-0.89048,-1.8127,-2.1106,0.78171,0.89048,0 +8.722,-0.89025,-1.8128,-2.1105,0.78171,0.89025,0 +8.723,-0.89003,-1.8129,-2.1104,0.78171,0.89003,0 +8.724,-0.8898,-1.813,-2.1103,0.7817,0.8898,0 +8.725,-0.88957,-1.8131,-2.1102,0.7817,0.88957,0 +8.726,-0.88935,-1.8132,-2.1101,0.7817,0.88935,0 +8.727,-0.88912,-1.8133,-2.1099,0.78169,0.88912,0 +8.728,-0.88889,-1.8134,-2.1098,0.78169,0.88889,0 +8.729,-0.88867,-1.8136,-2.1097,0.78169,0.88867,0 +8.73,-0.88844,-1.8137,-2.1096,0.78168,0.88844,0 +8.731,-0.88821,-1.8138,-2.1095,0.78168,0.88821,0 +8.732,-0.88799,-1.8139,-2.1094,0.78168,0.88799,0 +8.733,-0.88776,-1.814,-2.1093,0.78167,0.88776,0 +8.734,-0.88753,-1.8141,-2.1092,0.78167,0.88753,0 +8.735,-0.88731,-1.8142,-2.1091,0.78167,0.88731,0 +8.736,-0.88708,-1.8143,-2.109,0.78166,0.88708,0 +8.737,-0.88685,-1.8144,-2.1089,0.78166,0.88685,0 +8.738,-0.88663,-1.8145,-2.1087,0.78166,0.88663,0 +8.739,-0.8864,-1.8146,-2.1086,0.78165,0.8864,0 +8.74,-0.88617,-1.8147,-2.1085,0.78165,0.88617,0 +8.741,-0.88594,-1.8148,-2.1084,0.78165,0.88594,0 +8.742,-0.88572,-1.8149,-2.1083,0.78164,0.88572,0 +8.743,-0.88549,-1.815,-2.1082,0.78164,0.88549,0 +8.744,-0.88526,-1.8151,-2.1081,0.78164,0.88526,0 +8.745,-0.88504,-1.8152,-2.108,0.78163,0.88504,0 +8.746,-0.88481,-1.8153,-2.1079,0.78163,0.88481,0 +8.747,-0.88458,-1.8155,-2.1078,0.78163,0.88458,0 +8.748,-0.88436,-1.8156,-2.1077,0.78162,0.88436,0 +8.749,-0.88413,-1.8157,-2.1076,0.78162,0.88413,0 +8.75,-0.8839,-1.8158,-2.1074,0.78162,0.8839,0 +8.751,-0.88368,-1.8159,-2.1073,0.78161,0.88368,0 +8.752,-0.88345,-1.816,-2.1072,0.78161,0.88345,0 +8.753,-0.88322,-1.8161,-2.1071,0.78161,0.88322,0 +8.754,-0.883,-1.8162,-2.107,0.7816,0.883,0 +8.755,-0.88279,-1.8163,-2.1069,0.7816,0.88279,0 +8.756,-0.88257,-1.8164,-2.1068,0.7816,0.88257,0 +8.757,-0.88237,-1.8165,-2.1067,0.7816,0.88237,0 +8.758,-0.88216,-1.8166,-2.1066,0.7816,0.88216,0 +8.759,-0.88197,-1.8167,-2.1065,0.78159,0.88197,0 +8.76,-0.88177,-1.8168,-2.1064,0.78159,0.88177,0 +8.761,-0.88159,-1.8169,-2.1063,0.78159,0.88159,0 +8.762,-0.8814,-1.817,-2.1062,0.78159,0.8814,0 +8.763,-0.88123,-1.8171,-2.1061,0.7816,0.88123,0 +8.764,-0.88105,-1.8171,-2.106,0.7816,0.88105,0 +8.765,-0.88087,-1.8172,-2.1059,0.7816,0.88087,0 +8.766,-0.88069,-1.8173,-2.1059,0.7816,0.88069,0 +8.767,-0.88051,-1.8174,-2.1058,0.7816,0.88051,0 +8.768,-0.88033,-1.8175,-2.1057,0.7816,0.88033,0 +8.769,-0.88015,-1.8176,-2.1056,0.7816,0.88015,0 +8.77,-0.87997,-1.8177,-2.1055,0.7816,0.87997,0 +8.771,-0.8798,-1.8178,-2.1054,0.7816,0.8798,0 +8.772,-0.87962,-1.8179,-2.1053,0.7816,0.87962,0 +8.773,-0.87944,-1.818,-2.1052,0.7816,0.87944,0 +8.774,-0.87926,-1.8181,-2.1051,0.7816,0.87926,0 +8.775,-0.87908,-1.8182,-2.105,0.7816,0.87908,0 +8.776,-0.8789,-1.8182,-2.105,0.7816,0.8789,0 +8.777,-0.87872,-1.8183,-2.1049,0.7816,0.87872,0 +8.778,-0.87855,-1.8184,-2.1048,0.7816,0.87855,0 +8.779,-0.87837,-1.8185,-2.1047,0.7816,0.87837,0 +8.78,-0.87819,-1.8186,-2.1046,0.78161,0.87819,0 +8.781,-0.87801,-1.8187,-2.1045,0.78161,0.87801,0 +8.782,-0.87783,-1.8188,-2.1044,0.78161,0.87783,0 +8.783,-0.87765,-1.8189,-2.1043,0.78161,0.87765,0 +8.784,-0.87747,-1.819,-2.1042,0.78161,0.87747,0 +8.785,-0.87729,-1.8191,-2.1041,0.78161,0.87729,0 +8.786,-0.87712,-1.8192,-2.104,0.78161,0.87712,0 +8.787,-0.87694,-1.8192,-2.104,0.78161,0.87694,0 +8.788,-0.87676,-1.8193,-2.1039,0.78161,0.87676,0 +8.789,-0.87658,-1.8194,-2.1038,0.78161,0.87658,0 +8.79,-0.8764,-1.8195,-2.1037,0.78161,0.8764,0 +8.791,-0.87622,-1.8196,-2.1036,0.78161,0.87622,0 +8.792,-0.87604,-1.8197,-2.1035,0.78161,0.87604,0 +8.793,-0.87587,-1.8198,-2.1034,0.78161,0.87587,0 +8.794,-0.87569,-1.8199,-2.1033,0.78161,0.87569,0 +8.795,-0.87551,-1.82,-2.1032,0.78161,0.87551,0 +8.796,-0.87533,-1.8201,-2.1031,0.78162,0.87533,0 +8.797,-0.87515,-1.8202,-2.103,0.78162,0.87515,0 +8.798,-0.87497,-1.8203,-2.103,0.78162,0.87497,0 +8.799,-0.87479,-1.8203,-2.1029,0.78162,0.87479,0 +8.8,-0.87462,-1.8204,-2.1028,0.78162,0.87462,0 +8.801,-0.87444,-1.8205,-2.1027,0.78162,0.87444,0 +8.802,-0.87426,-1.8206,-2.1026,0.78162,0.87426,0 +8.803,-0.87408,-1.8207,-2.1025,0.78162,0.87408,0 +8.804,-0.8739,-1.8208,-2.1024,0.78162,0.8739,0 +8.805,-0.87372,-1.8209,-2.1023,0.78162,0.87372,0 +8.806,-0.87354,-1.821,-2.1022,0.78162,0.87354,0 +8.807,-0.87336,-1.8211,-2.1021,0.78162,0.87336,0 +8.808,-0.87319,-1.8212,-2.1021,0.78162,0.87319,0 +8.809,-0.87301,-1.8213,-2.102,0.78162,0.87301,0 +8.81,-0.87283,-1.8213,-2.1019,0.78162,0.87283,0 +8.811,-0.87265,-1.8214,-2.1018,0.78162,0.87265,0 +8.812,-0.87247,-1.8215,-2.1017,0.78162,0.87247,0 +8.813,-0.87229,-1.8216,-2.1016,0.78163,0.87229,0 +8.814,-0.87211,-1.8217,-2.1015,0.78163,0.87211,0 +8.815,-0.87194,-1.8218,-2.1014,0.78163,0.87194,0 +8.816,-0.87176,-1.8219,-2.1013,0.78163,0.87176,0 +8.817,-0.87158,-1.822,-2.1012,0.78163,0.87158,0 +8.818,-0.8714,-1.8221,-2.1011,0.78163,0.8714,0 +8.819,-0.87122,-1.8222,-2.1011,0.78163,0.87122,0 +8.82,-0.87104,-1.8223,-2.101,0.78163,0.87104,0 +8.821,-0.87086,-1.8224,-2.1009,0.78163,0.87086,0 +8.822,-0.87069,-1.8224,-2.1008,0.78163,0.87069,0 +8.823,-0.87051,-1.8225,-2.1007,0.78163,0.87051,0 +8.824,-0.87033,-1.8226,-2.1006,0.78163,0.87033,0 +8.825,-0.87015,-1.8227,-2.1005,0.78163,0.87015,0 +8.826,-0.86997,-1.8228,-2.1004,0.78163,0.86997,0 +8.827,-0.86979,-1.8229,-2.1003,0.78163,0.86979,0 +8.828,-0.86961,-1.823,-2.1002,0.78163,0.86961,0 +8.829,-0.86943,-1.8231,-2.1001,0.78164,0.86943,0 +8.83,-0.86926,-1.8232,-2.1001,0.78164,0.86926,0 +8.831,-0.86908,-1.8233,-2.1,0.78164,0.86908,0 +8.832,-0.8689,-1.8234,-2.0999,0.78164,0.8689,0 +8.833,-0.86872,-1.8234,-2.0998,0.78164,0.86872,0 +8.834,-0.86854,-1.8235,-2.0997,0.78164,0.86854,0 +8.835,-0.86836,-1.8236,-2.0996,0.78164,0.86836,0 +8.836,-0.86818,-1.8237,-2.0995,0.78164,0.86818,0 +8.837,-0.86801,-1.8238,-2.0994,0.78164,0.86801,0 +8.838,-0.86783,-1.8239,-2.0993,0.78165,0.86783,0 +8.839,-0.86766,-1.824,-2.0992,0.78165,0.86766,0 +8.84,-0.86749,-1.8241,-2.0992,0.78166,0.86749,0 +8.841,-0.86733,-1.8242,-2.0991,0.78167,0.86733,0 +8.842,-0.86716,-1.8243,-2.099,0.78168,0.86716,0 +8.843,-0.867,-1.8244,-2.0989,0.78169,0.867,0 +8.844,-0.86684,-1.8245,-2.0988,0.7817,0.86684,0 +8.845,-0.86668,-1.8246,-2.0987,0.78171,0.86668,0 +8.846,-0.86652,-1.8247,-2.0987,0.78173,0.86652,0 +8.847,-0.86636,-1.8248,-2.0986,0.78174,0.86636,0 +8.848,-0.86621,-1.8248,-2.0985,0.78176,0.86621,0 +8.849,-0.86605,-1.8249,-2.0984,0.78178,0.86605,0 +8.85,-0.86589,-1.825,-2.0983,0.78179,0.86589,0 +8.851,-0.86573,-1.8251,-2.0983,0.78181,0.86573,0 +8.852,-0.86558,-1.8252,-2.0982,0.78182,0.86558,0 +8.853,-0.86542,-1.8253,-2.0981,0.78184,0.86542,0 +8.854,-0.86526,-1.8254,-2.098,0.78185,0.86526,0 +8.855,-0.86511,-1.8255,-2.0979,0.78187,0.86511,0 +8.856,-0.86495,-1.8256,-2.0979,0.78188,0.86495,0 +8.857,-0.86479,-1.8257,-2.0978,0.7819,0.86479,0 +8.858,-0.86464,-1.8258,-2.0977,0.78191,0.86464,0 +8.859,-0.86448,-1.8259,-2.0976,0.78193,0.86448,0 +8.86,-0.86432,-1.826,-2.0976,0.78195,0.86432,0 +8.861,-0.86416,-1.8261,-2.0975,0.78196,0.86416,0 +8.862,-0.86401,-1.8262,-2.0974,0.78198,0.86401,0 +8.863,-0.86385,-1.8263,-2.0973,0.78199,0.86385,0 +8.864,-0.86369,-1.8264,-2.0972,0.78201,0.86369,0 +8.865,-0.86354,-1.8265,-2.0972,0.78202,0.86354,0 +8.866,-0.86338,-1.8266,-2.0971,0.78204,0.86338,0 +8.867,-0.86322,-1.8267,-2.097,0.78205,0.86322,0 +8.868,-0.86306,-1.8267,-2.0969,0.78207,0.86306,0 +8.869,-0.86291,-1.8268,-2.0968,0.78208,0.86291,0 +8.87,-0.86275,-1.8269,-2.0968,0.7821,0.86275,0 +8.871,-0.86259,-1.827,-2.0967,0.78211,0.86259,0 +8.872,-0.86244,-1.8271,-2.0966,0.78213,0.86244,0 +8.873,-0.86228,-1.8272,-2.0965,0.78215,0.86228,0 +8.874,-0.86212,-1.8273,-2.0964,0.78216,0.86212,0 +8.875,-0.86197,-1.8274,-2.0964,0.78218,0.86197,0 +8.876,-0.86181,-1.8275,-2.0963,0.78219,0.86181,0 +8.877,-0.86165,-1.8276,-2.0962,0.78221,0.86165,0 +8.878,-0.86149,-1.8277,-2.0961,0.78222,0.86149,0 +8.879,-0.86134,-1.8278,-2.096,0.78224,0.86134,0 +8.88,-0.86118,-1.8279,-2.096,0.78225,0.86118,0 +8.881,-0.86102,-1.828,-2.0959,0.78227,0.86102,0 +8.882,-0.86087,-1.8281,-2.0958,0.78228,0.86087,0 +8.883,-0.86071,-1.8282,-2.0957,0.7823,0.86071,0 +8.884,-0.86055,-1.8283,-2.0956,0.78232,0.86055,0 +8.885,-0.86039,-1.8284,-2.0956,0.78233,0.86039,0 +8.886,-0.86024,-1.8285,-2.0955,0.78235,0.86024,0 +8.887,-0.86008,-1.8286,-2.0954,0.78236,0.86008,0 +8.888,-0.85992,-1.8286,-2.0953,0.78238,0.85992,0 +8.889,-0.85977,-1.8287,-2.0952,0.78239,0.85977,0 +8.89,-0.85961,-1.8288,-2.0952,0.78241,0.85961,0 +8.891,-0.85945,-1.8289,-2.0951,0.78242,0.85945,0 +8.892,-0.85929,-1.829,-2.095,0.78244,0.85929,0 +8.893,-0.85914,-1.8291,-2.0949,0.78245,0.85914,0 +8.894,-0.85898,-1.8292,-2.0948,0.78247,0.85898,0 +8.895,-0.85882,-1.8293,-2.0948,0.78248,0.85882,0 +8.896,-0.85867,-1.8294,-2.0947,0.7825,0.85867,0 +8.897,-0.85851,-1.8295,-2.0946,0.78252,0.85851,0 +8.898,-0.85835,-1.8296,-2.0945,0.78253,0.85835,0 +8.899,-0.8582,-1.8297,-2.0944,0.78255,0.8582,0 +8.9,-0.85804,-1.8298,-2.0944,0.78256,0.85804,0 +8.901,-0.85788,-1.8299,-2.0943,0.78258,0.85788,0 +8.902,-0.85772,-1.83,-2.0942,0.78259,0.85772,0 +8.903,-0.85757,-1.8301,-2.0941,0.78261,0.85757,0 +8.904,-0.85741,-1.8302,-2.094,0.78262,0.85741,0 +8.905,-0.85725,-1.8303,-2.094,0.78264,0.85725,0 +8.906,-0.8571,-1.8304,-2.0939,0.78265,0.8571,0 +8.907,-0.85694,-1.8305,-2.0938,0.78267,0.85694,0 +8.908,-0.85678,-1.8306,-2.0937,0.78269,0.85678,0 +8.909,-0.85662,-1.8306,-2.0936,0.7827,0.85662,0 +8.91,-0.85647,-1.8307,-2.0936,0.78272,0.85647,0 +8.911,-0.85631,-1.8308,-2.0935,0.78273,0.85631,0 +8.912,-0.85615,-1.8309,-2.0934,0.78275,0.85615,0 +8.913,-0.856,-1.831,-2.0933,0.78276,0.856,0 +8.914,-0.85584,-1.8311,-2.0932,0.78278,0.85584,0 +8.915,-0.85568,-1.8312,-2.0932,0.78279,0.85568,0 +8.916,-0.85553,-1.8313,-2.0931,0.78281,0.85553,0 +8.917,-0.85537,-1.8314,-2.093,0.78282,0.85537,0 +8.918,-0.85521,-1.8315,-2.0929,0.78284,0.85521,0 +8.919,-0.85505,-1.8316,-2.0929,0.78285,0.85505,0 +8.92,-0.8549,-1.8317,-2.0928,0.78287,0.8549,0 +8.921,-0.85474,-1.8318,-2.0927,0.78288,0.85474,0 +8.922,-0.85458,-1.8319,-2.0926,0.78289,0.85458,0 +8.923,-0.85443,-1.832,-2.0925,0.7829,0.85443,0 +8.924,-0.85427,-1.8321,-2.0924,0.78291,0.85427,0 +8.925,-0.85412,-1.8322,-2.0924,0.78291,0.85412,0 +8.926,-0.85396,-1.8322,-2.0923,0.78292,0.85396,0 +8.927,-0.85381,-1.8323,-2.0922,0.78292,0.85381,0 +8.928,-0.85365,-1.8324,-2.0921,0.78292,0.85365,0 +8.929,-0.8535,-1.8325,-2.092,0.78292,0.8535,0 +8.93,-0.85335,-1.8326,-2.0919,0.78292,0.85335,0 +8.931,-0.85319,-1.8327,-2.0918,0.78292,0.85319,0 +8.932,-0.85304,-1.8328,-2.0917,0.78292,0.85304,0 +8.933,-0.85288,-1.8329,-2.0917,0.78292,0.85288,0 +8.934,-0.85273,-1.8329,-2.0916,0.78292,0.85273,0 +8.935,-0.85258,-1.833,-2.0915,0.78292,0.85258,0 +8.936,-0.85242,-1.8331,-2.0914,0.78292,0.85242,0 +8.937,-0.85227,-1.8332,-2.0913,0.78292,0.85227,0 +8.938,-0.85211,-1.8333,-2.0912,0.78292,0.85211,0 +8.939,-0.85196,-1.8334,-2.0911,0.78292,0.85196,0 +8.94,-0.8518,-1.8335,-2.091,0.78292,0.8518,0 +8.941,-0.85165,-1.8336,-2.091,0.78292,0.85165,0 +8.942,-0.8515,-1.8336,-2.0909,0.78292,0.8515,0 +8.943,-0.85134,-1.8337,-2.0908,0.78292,0.85134,0 +8.944,-0.85119,-1.8338,-2.0907,0.78292,0.85119,0 +8.945,-0.85103,-1.8339,-2.0906,0.78292,0.85103,0 +8.946,-0.85088,-1.834,-2.0905,0.78292,0.85088,0 +8.947,-0.85073,-1.8341,-2.0904,0.78292,0.85073,0 +8.948,-0.85057,-1.8342,-2.0903,0.78292,0.85057,0 +8.949,-0.85042,-1.8343,-2.0903,0.78292,0.85042,0 +8.95,-0.85026,-1.8343,-2.0902,0.78292,0.85026,0 +8.951,-0.85011,-1.8344,-2.0901,0.78292,0.85011,0 +8.952,-0.84995,-1.8345,-2.09,0.78292,0.84995,0 +8.953,-0.8498,-1.8346,-2.0899,0.78292,0.8498,0 +8.954,-0.84965,-1.8347,-2.0898,0.78292,0.84965,0 +8.955,-0.84949,-1.8348,-2.0897,0.78292,0.84949,0 +8.956,-0.84934,-1.8349,-2.0896,0.78292,0.84934,0 +8.957,-0.84918,-1.835,-2.0896,0.78292,0.84918,0 +8.958,-0.84903,-1.835,-2.0895,0.78292,0.84903,0 +8.959,-0.84888,-1.8351,-2.0894,0.78292,0.84888,0 +8.96,-0.84872,-1.8352,-2.0893,0.78292,0.84872,0 +8.961,-0.84857,-1.8353,-2.0892,0.78292,0.84857,0 +8.962,-0.84841,-1.8354,-2.0891,0.78292,0.84841,0 +8.963,-0.84826,-1.8355,-2.089,0.78292,0.84826,0 +8.964,-0.8481,-1.8356,-2.0889,0.78292,0.8481,0 +8.965,-0.84795,-1.8357,-2.0889,0.78292,0.84795,0 +8.966,-0.8478,-1.8357,-2.0888,0.78292,0.8478,0 +8.967,-0.84764,-1.8358,-2.0887,0.78292,0.84764,0 +8.968,-0.84749,-1.8359,-2.0886,0.78292,0.84749,0 +8.969,-0.84733,-1.836,-2.0885,0.78292,0.84733,0 +8.97,-0.84718,-1.8361,-2.0884,0.78292,0.84718,0 +8.971,-0.84703,-1.8362,-2.0883,0.78292,0.84703,0 +8.972,-0.84687,-1.8363,-2.0882,0.78292,0.84687,0 +8.973,-0.84672,-1.8364,-2.0882,0.78292,0.84672,0 +8.974,-0.84656,-1.8364,-2.0881,0.78292,0.84656,0 +8.975,-0.84641,-1.8365,-2.088,0.78292,0.84641,0 +8.976,-0.84625,-1.8366,-2.0879,0.78292,0.84625,0 +8.977,-0.8461,-1.8367,-2.0878,0.78292,0.8461,0 +8.978,-0.84595,-1.8368,-2.0877,0.78292,0.84595,0 +8.979,-0.84579,-1.8369,-2.0876,0.78292,0.84579,0 +8.98,-0.84564,-1.837,-2.0875,0.78292,0.84564,0 +8.981,-0.84548,-1.8371,-2.0875,0.78292,0.84548,0 +8.982,-0.84533,-1.8371,-2.0874,0.78292,0.84533,0 +8.983,-0.84518,-1.8372,-2.0873,0.78292,0.84518,0 +8.984,-0.84502,-1.8373,-2.0872,0.78292,0.84502,0 +8.985,-0.84487,-1.8374,-2.0871,0.78292,0.84487,0 +8.986,-0.84471,-1.8375,-2.087,0.78292,0.84471,0 +8.987,-0.84456,-1.8376,-2.0869,0.78292,0.84456,0 +8.988,-0.8444,-1.8377,-2.0868,0.78292,0.8444,0 +8.989,-0.84425,-1.8378,-2.0868,0.78292,0.84425,0 +8.99,-0.8441,-1.8378,-2.0867,0.78292,0.8441,0 +8.991,-0.84394,-1.8379,-2.0866,0.78292,0.84394,0 +8.992,-0.84379,-1.838,-2.0865,0.78292,0.84379,0 +8.993,-0.84363,-1.8381,-2.0864,0.78292,0.84363,0 +8.994,-0.84348,-1.8382,-2.0863,0.78292,0.84348,0 +8.995,-0.84333,-1.8383,-2.0862,0.78292,0.84333,0 +8.996,-0.84317,-1.8384,-2.0861,0.78292,0.84317,0 +8.997,-0.84302,-1.8385,-2.0861,0.78292,0.84302,0 +8.998,-0.84286,-1.8385,-2.086,0.78292,0.84286,0 +8.999,-0.84271,-1.8386,-2.0859,0.78292,0.84271,0 +9,-0.84255,-1.8387,-2.0858,0.78292,0.84255,0 +9.001,-0.8424,-1.8388,-2.0857,0.78292,0.8424,0 +9.002,-0.84225,-1.8389,-2.0856,0.78292,0.84225,0 +9.003,-0.84209,-1.839,-2.0855,0.78292,0.84209,0 +9.004,-0.84194,-1.8391,-2.0854,0.78292,0.84194,0 +9.005,-0.84179,-1.8392,-2.0854,0.78292,0.84179,0 +9.006,-0.84163,-1.8392,-2.0853,0.78292,0.84163,0 +9.007,-0.84148,-1.8393,-2.0852,0.78292,0.84148,0 +9.008,-0.84133,-1.8394,-2.0851,0.78292,0.84133,0 +9.009,-0.84118,-1.8395,-2.085,0.78292,0.84118,0 +9.01,-0.84102,-1.8396,-2.0849,0.78292,0.84102,0 +9.011,-0.84087,-1.8397,-2.0848,0.78292,0.84087,0 +9.012,-0.84072,-1.8398,-2.0847,0.78292,0.84072,0 +9.013,-0.84057,-1.8399,-2.0846,0.78291,0.84057,0 +9.014,-0.84042,-1.84,-2.0845,0.78291,0.84042,0 +9.015,-0.84027,-1.84,-2.0845,0.78291,0.84027,0 +9.016,-0.84012,-1.8401,-2.0844,0.78291,0.84012,0 +9.017,-0.83997,-1.8402,-2.0843,0.78291,0.83997,0 +9.018,-0.83981,-1.8403,-2.0842,0.78291,0.83981,0 +9.019,-0.83966,-1.8404,-2.0841,0.78291,0.83966,0 +9.02,-0.83951,-1.8405,-2.084,0.7829,0.83951,0 +9.021,-0.83936,-1.8406,-2.0839,0.7829,0.83936,0 +9.022,-0.83921,-1.8407,-2.0838,0.7829,0.83921,0 +9.023,-0.83906,-1.8408,-2.0837,0.7829,0.83906,0 +9.024,-0.83891,-1.8408,-2.0836,0.7829,0.83891,0 +9.025,-0.83876,-1.8409,-2.0835,0.7829,0.83876,0 +9.026,-0.8386,-1.841,-2.0835,0.78289,0.8386,0 +9.027,-0.83845,-1.8411,-2.0834,0.78289,0.83845,0 +9.028,-0.8383,-1.8412,-2.0833,0.78289,0.8383,0 +9.029,-0.83815,-1.8413,-2.0832,0.78289,0.83815,0 +9.03,-0.838,-1.8414,-2.0831,0.78289,0.838,0 +9.031,-0.83785,-1.8415,-2.083,0.78289,0.83785,0 +9.032,-0.8377,-1.8416,-2.0829,0.78288,0.8377,0 +9.033,-0.83755,-1.8417,-2.0828,0.78288,0.83755,0 +9.034,-0.83739,-1.8417,-2.0827,0.78288,0.83739,0 +9.035,-0.83724,-1.8418,-2.0826,0.78288,0.83724,0 +9.036,-0.83709,-1.8419,-2.0826,0.78288,0.83709,0 +9.037,-0.83694,-1.842,-2.0825,0.78288,0.83694,0 +9.038,-0.83679,-1.8421,-2.0824,0.78288,0.83679,0 +9.039,-0.83664,-1.8422,-2.0823,0.78287,0.83664,0 +9.04,-0.83649,-1.8423,-2.0822,0.78287,0.83649,0 +9.041,-0.83634,-1.8424,-2.0821,0.78287,0.83634,0 +9.042,-0.83618,-1.8425,-2.082,0.78287,0.83618,0 +9.043,-0.83603,-1.8425,-2.0819,0.78287,0.83603,0 +9.044,-0.83588,-1.8426,-2.0818,0.78287,0.83588,0 +9.045,-0.83573,-1.8427,-2.0817,0.78286,0.83573,0 +9.046,-0.83558,-1.8428,-2.0816,0.78286,0.83558,0 +9.047,-0.83543,-1.8429,-2.0816,0.78286,0.83543,0 +9.048,-0.83528,-1.843,-2.0815,0.78286,0.83528,0 +9.049,-0.83513,-1.8431,-2.0814,0.78286,0.83513,0 +9.05,-0.83497,-1.8432,-2.0813,0.78286,0.83497,0 +9.051,-0.83482,-1.8433,-2.0812,0.78285,0.83482,0 +9.052,-0.83467,-1.8433,-2.0811,0.78285,0.83467,0 +9.053,-0.83452,-1.8434,-2.081,0.78285,0.83452,0 +9.054,-0.83437,-1.8435,-2.0809,0.78285,0.83437,0 +9.055,-0.83422,-1.8436,-2.0808,0.78285,0.83422,0 +9.056,-0.83407,-1.8437,-2.0807,0.78285,0.83407,0 +9.057,-0.83392,-1.8438,-2.0806,0.78285,0.83392,0 +9.058,-0.83376,-1.8439,-2.0806,0.78284,0.83376,0 +9.059,-0.83361,-1.844,-2.0805,0.78284,0.83361,0 +9.06,-0.83346,-1.8441,-2.0804,0.78284,0.83346,0 +9.061,-0.83331,-1.8442,-2.0803,0.78284,0.83331,0 +9.062,-0.83316,-1.8442,-2.0802,0.78284,0.83316,0 +9.063,-0.83301,-1.8443,-2.0801,0.78284,0.83301,0 +9.064,-0.83286,-1.8444,-2.08,0.78283,0.83286,0 +9.065,-0.83271,-1.8445,-2.0799,0.78283,0.83271,0 +9.066,-0.83255,-1.8446,-2.0798,0.78283,0.83255,0 +9.067,-0.8324,-1.8447,-2.0797,0.78283,0.8324,0 +9.068,-0.83225,-1.8448,-2.0796,0.78283,0.83225,0 +9.069,-0.8321,-1.8449,-2.0796,0.78283,0.8321,0 +9.07,-0.83195,-1.845,-2.0795,0.78282,0.83195,0 +9.071,-0.8318,-1.845,-2.0794,0.78282,0.8318,0 +9.072,-0.83165,-1.8451,-2.0793,0.78282,0.83165,0 +9.073,-0.83149,-1.8452,-2.0792,0.78282,0.83149,0 +9.074,-0.83134,-1.8453,-2.0791,0.78282,0.83134,0 +9.075,-0.83119,-1.8454,-2.079,0.78282,0.83119,0 +9.076,-0.83104,-1.8455,-2.0789,0.78282,0.83104,0 +9.077,-0.83089,-1.8456,-2.0788,0.78281,0.83089,0 +9.078,-0.83074,-1.8457,-2.0787,0.78281,0.83074,0 +9.079,-0.83059,-1.8458,-2.0786,0.78281,0.83059,0 +9.08,-0.83044,-1.8458,-2.0786,0.78281,0.83044,0 +9.081,-0.83028,-1.8459,-2.0785,0.78281,0.83028,0 +9.082,-0.83013,-1.846,-2.0784,0.78281,0.83013,0 +9.083,-0.82998,-1.8461,-2.0783,0.7828,0.82998,0 +9.084,-0.82983,-1.8462,-2.0782,0.7828,0.82983,0 +9.085,-0.82968,-1.8463,-2.0781,0.7828,0.82968,0 +9.086,-0.82953,-1.8464,-2.078,0.7828,0.82953,0 +9.087,-0.82938,-1.8465,-2.0779,0.7828,0.82938,0 +9.088,-0.82923,-1.8466,-2.0778,0.78281,0.82923,0 +9.089,-0.82908,-1.8467,-2.0777,0.78281,0.82908,0 +9.09,-0.82894,-1.8468,-2.0777,0.78282,0.82894,0 +9.091,-0.82879,-1.8468,-2.0776,0.78282,0.82879,0 +9.092,-0.82865,-1.8469,-2.0775,0.78283,0.82865,0 +9.093,-0.8285,-1.847,-2.0774,0.78284,0.8285,0 +9.094,-0.82836,-1.8471,-2.0773,0.78285,0.82836,0 +9.095,-0.82822,-1.8472,-2.0772,0.78286,0.82822,0 +9.096,-0.82807,-1.8473,-2.0771,0.78287,0.82807,0 +9.097,-0.82793,-1.8474,-2.077,0.78288,0.82793,0 +9.098,-0.82779,-1.8475,-2.077,0.7829,0.82779,0 +9.099,-0.82765,-1.8476,-2.0769,0.78291,0.82765,0 +9.1,-0.8275,-1.8477,-2.0768,0.78292,0.8275,0 +9.101,-0.82736,-1.8478,-2.0767,0.78293,0.82736,0 +9.102,-0.82722,-1.8479,-2.0766,0.78294,0.82722,0 +9.103,-0.82708,-1.848,-2.0765,0.78295,0.82708,0 +9.104,-0.82693,-1.8481,-2.0764,0.78296,0.82693,0 +9.105,-0.82679,-1.8482,-2.0764,0.78297,0.82679,0 +9.106,-0.82665,-1.8483,-2.0763,0.78299,0.82665,0 +9.107,-0.8265,-1.8484,-2.0762,0.783,0.8265,0 +9.108,-0.82636,-1.8485,-2.0761,0.78301,0.82636,0 +9.109,-0.82622,-1.8486,-2.076,0.78302,0.82622,0 +9.11,-0.82608,-1.8487,-2.0759,0.78303,0.82608,0 +9.111,-0.82593,-1.8488,-2.0758,0.78304,0.82593,0 +9.112,-0.82579,-1.8489,-2.0758,0.78305,0.82579,0 +9.113,-0.82565,-1.849,-2.0757,0.78307,0.82565,0 +9.114,-0.82551,-1.8491,-2.0756,0.78308,0.82551,0 +9.115,-0.82536,-1.8492,-2.0755,0.78309,0.82536,0 +9.116,-0.82522,-1.8493,-2.0754,0.7831,0.82522,0 +9.117,-0.82508,-1.8494,-2.0753,0.78311,0.82508,0 +9.118,-0.82493,-1.8495,-2.0752,0.78312,0.82493,0 +9.119,-0.82479,-1.8496,-2.0752,0.78313,0.82479,0 +9.12,-0.82465,-1.8497,-2.0751,0.78315,0.82465,0 +9.121,-0.82451,-1.8498,-2.075,0.78316,0.82451,0 +9.122,-0.82436,-1.8499,-2.0749,0.78317,0.82436,0 +9.123,-0.82422,-1.85,-2.0748,0.78318,0.82422,0 +9.124,-0.82408,-1.8501,-2.0747,0.78319,0.82408,0 +9.125,-0.82394,-1.8502,-2.0746,0.7832,0.82394,0 +9.126,-0.82379,-1.8503,-2.0746,0.78321,0.82379,0 +9.127,-0.82365,-1.8503,-2.0745,0.78323,0.82365,0 +9.128,-0.82351,-1.8504,-2.0744,0.78324,0.82351,0 +9.129,-0.82336,-1.8505,-2.0743,0.78325,0.82336,0 +9.13,-0.82322,-1.8506,-2.0742,0.78326,0.82322,0 +9.131,-0.82308,-1.8507,-2.0741,0.78327,0.82308,0 +9.132,-0.82294,-1.8508,-2.074,0.78328,0.82294,0 +9.133,-0.82279,-1.8509,-2.074,0.78329,0.82279,0 +9.134,-0.82265,-1.851,-2.0739,0.7833,0.82265,0 +9.135,-0.82251,-1.8511,-2.0738,0.78332,0.82251,0 +9.136,-0.82237,-1.8512,-2.0737,0.78333,0.82237,0 +9.137,-0.82222,-1.8513,-2.0736,0.78334,0.82222,0 +9.138,-0.82208,-1.8514,-2.0735,0.78335,0.82208,0 +9.139,-0.82194,-1.8515,-2.0734,0.78336,0.82194,0 +9.14,-0.82179,-1.8516,-2.0734,0.78337,0.82179,0 +9.141,-0.82165,-1.8517,-2.0733,0.78338,0.82165,0 +9.142,-0.82151,-1.8518,-2.0732,0.7834,0.82151,0 +9.143,-0.82137,-1.8519,-2.0731,0.78341,0.82137,0 +9.144,-0.82122,-1.852,-2.073,0.78342,0.82122,0 +9.145,-0.82108,-1.8521,-2.0729,0.78343,0.82108,0 +9.146,-0.82094,-1.8522,-2.0728,0.78344,0.82094,0 +9.147,-0.8208,-1.8523,-2.0728,0.78345,0.8208,0 +9.148,-0.82065,-1.8524,-2.0727,0.78346,0.82065,0 +9.149,-0.82051,-1.8525,-2.0726,0.78348,0.82051,0 +9.15,-0.82037,-1.8526,-2.0725,0.78349,0.82037,0 +9.151,-0.82022,-1.8527,-2.0724,0.7835,0.82022,0 +9.152,-0.82008,-1.8528,-2.0723,0.78351,0.82008,0 +9.153,-0.81994,-1.8529,-2.0722,0.78352,0.81994,0 +9.154,-0.8198,-1.853,-2.0721,0.78353,0.8198,0 +9.155,-0.81965,-1.8531,-2.0721,0.78354,0.81965,0 +9.156,-0.81951,-1.8532,-2.072,0.78355,0.81951,0 +9.157,-0.81937,-1.8533,-2.0719,0.78357,0.81937,0 +9.158,-0.81923,-1.8534,-2.0718,0.78358,0.81923,0 +9.159,-0.81908,-1.8535,-2.0717,0.78359,0.81908,0 +9.16,-0.81894,-1.8536,-2.0716,0.7836,0.81894,0 +9.161,-0.8188,-1.8537,-2.0715,0.78361,0.8188,0 +9.162,-0.81865,-1.8538,-2.0715,0.78362,0.81865,0 +9.163,-0.81851,-1.8539,-2.0714,0.78363,0.81851,0 +9.164,-0.81837,-1.8539,-2.0713,0.78365,0.81837,0 +9.165,-0.81823,-1.854,-2.0712,0.78366,0.81823,0 +9.166,-0.81808,-1.8541,-2.0711,0.78367,0.81808,0 +9.167,-0.81794,-1.8542,-2.071,0.78368,0.81794,0 +9.168,-0.8178,-1.8543,-2.0709,0.78369,0.8178,0 +9.169,-0.81766,-1.8544,-2.0709,0.7837,0.81766,0 +9.17,-0.81752,-1.8545,-2.0708,0.78371,0.81752,0 +9.171,-0.81738,-1.8546,-2.0707,0.78372,0.81738,0 +9.172,-0.81724,-1.8547,-2.0706,0.78374,0.81724,0 +9.173,-0.8171,-1.8548,-2.0705,0.78375,0.8171,0 +9.174,-0.81696,-1.8549,-2.0704,0.78376,0.81696,0 +9.175,-0.81682,-1.855,-2.0703,0.78377,0.81682,0 +9.176,-0.81669,-1.8551,-2.0703,0.78378,0.81669,0 +9.177,-0.81655,-1.8552,-2.0702,0.78379,0.81655,0 +9.178,-0.81642,-1.8553,-2.0701,0.7838,0.81642,0 +9.179,-0.81628,-1.8554,-2.07,0.78381,0.81628,0 +9.18,-0.81615,-1.8555,-2.0699,0.78382,0.81615,0 +9.181,-0.81602,-1.8556,-2.0698,0.78383,0.81602,0 +9.182,-0.81588,-1.8557,-2.0698,0.78385,0.81588,0 +9.183,-0.81575,-1.8558,-2.0697,0.78386,0.81575,0 +9.184,-0.81561,-1.8559,-2.0696,0.78387,0.81561,0 +9.185,-0.81548,-1.856,-2.0695,0.78388,0.81548,0 +9.186,-0.81534,-1.8561,-2.0694,0.78389,0.81534,0 +9.187,-0.81521,-1.8562,-2.0693,0.7839,0.81521,0 +9.188,-0.81507,-1.8563,-2.0692,0.78391,0.81507,0 +9.189,-0.81494,-1.8564,-2.0692,0.78392,0.81494,0 +9.19,-0.8148,-1.8565,-2.0691,0.78393,0.8148,0 +9.191,-0.81467,-1.8565,-2.069,0.78394,0.81467,0 +9.192,-0.81454,-1.8566,-2.0689,0.78395,0.81454,0 +9.193,-0.8144,-1.8567,-2.0688,0.78397,0.8144,0 +9.194,-0.81427,-1.8568,-2.0687,0.78398,0.81427,0 +9.195,-0.81413,-1.8569,-2.0686,0.78399,0.81413,0 +9.196,-0.814,-1.857,-2.0686,0.784,0.814,0 +9.197,-0.81386,-1.8571,-2.0685,0.78401,0.81386,0 +9.198,-0.81373,-1.8572,-2.0684,0.78402,0.81373,0 +9.199,-0.81359,-1.8573,-2.0683,0.78403,0.81359,0 +9.2,-0.81346,-1.8574,-2.0682,0.78404,0.81346,0 +9.201,-0.81333,-1.8575,-2.0681,0.78405,0.81333,0 +9.202,-0.81319,-1.8576,-2.0681,0.78406,0.81319,0 +9.203,-0.81306,-1.8577,-2.068,0.78407,0.81306,0 +9.204,-0.81292,-1.8578,-2.0679,0.78408,0.81292,0 +9.205,-0.81279,-1.8579,-2.0678,0.7841,0.81279,0 +9.206,-0.81265,-1.858,-2.0677,0.78411,0.81265,0 +9.207,-0.81252,-1.8581,-2.0676,0.78412,0.81252,0 +9.208,-0.81238,-1.8582,-2.0675,0.78413,0.81238,0 +9.209,-0.81225,-1.8583,-2.0675,0.78414,0.81225,0 +9.21,-0.81211,-1.8584,-2.0674,0.78415,0.81211,0 +9.211,-0.81198,-1.8585,-2.0673,0.78416,0.81198,0 +9.212,-0.81185,-1.8586,-2.0672,0.78417,0.81185,0 +9.213,-0.81171,-1.8587,-2.0671,0.78418,0.81171,0 +9.214,-0.81158,-1.8588,-2.067,0.78419,0.81158,0 +9.215,-0.81144,-1.8588,-2.0669,0.7842,0.81144,0 +9.216,-0.81131,-1.8589,-2.0669,0.78422,0.81131,0 +9.217,-0.81117,-1.859,-2.0668,0.78423,0.81117,0 +9.218,-0.81104,-1.8591,-2.0667,0.78424,0.81104,0 +9.219,-0.8109,-1.8592,-2.0666,0.78425,0.8109,0 +9.22,-0.81077,-1.8593,-2.0665,0.78426,0.81077,0 +9.221,-0.81063,-1.8594,-2.0664,0.78427,0.81063,0 +9.222,-0.8105,-1.8595,-2.0664,0.78428,0.8105,0 +9.223,-0.81037,-1.8596,-2.0663,0.78429,0.81037,0 +9.224,-0.81023,-1.8597,-2.0662,0.7843,0.81023,0 +9.225,-0.8101,-1.8598,-2.0661,0.78431,0.8101,0 +9.226,-0.80996,-1.8599,-2.066,0.78432,0.80996,0 +9.227,-0.80983,-1.86,-2.0659,0.78434,0.80983,0 +9.228,-0.80969,-1.8601,-2.0658,0.78435,0.80969,0 +9.229,-0.80956,-1.8602,-2.0658,0.78436,0.80956,0 +9.23,-0.80942,-1.8603,-2.0657,0.78437,0.80942,0 +9.231,-0.80929,-1.8604,-2.0656,0.78438,0.80929,0 +9.232,-0.80915,-1.8605,-2.0655,0.78439,0.80915,0 +9.233,-0.80902,-1.8606,-2.0654,0.7844,0.80902,0 +9.234,-0.80889,-1.8607,-2.0653,0.78441,0.80889,0 +9.235,-0.80875,-1.8608,-2.0652,0.78442,0.80875,0 +9.236,-0.80862,-1.8609,-2.0652,0.78443,0.80862,0 +9.237,-0.80848,-1.861,-2.0651,0.78444,0.80848,0 +9.238,-0.80835,-1.8611,-2.065,0.78445,0.80835,0 +9.239,-0.80821,-1.8611,-2.0649,0.78447,0.80821,0 +9.24,-0.80808,-1.8612,-2.0648,0.78448,0.80808,0 +9.241,-0.80794,-1.8613,-2.0647,0.78449,0.80794,0 +9.242,-0.80781,-1.8614,-2.0647,0.7845,0.80781,0 +9.243,-0.80767,-1.8615,-2.0646,0.78451,0.80767,0 +9.244,-0.80754,-1.8616,-2.0645,0.78452,0.80754,0 +9.245,-0.80741,-1.8617,-2.0644,0.78453,0.80741,0 +9.246,-0.80727,-1.8618,-2.0643,0.78454,0.80727,0 +9.247,-0.80714,-1.8619,-2.0642,0.78455,0.80714,0 +9.248,-0.807,-1.862,-2.0641,0.78456,0.807,0 +9.249,-0.80687,-1.8621,-2.0641,0.78457,0.80687,0 +9.25,-0.80673,-1.8622,-2.064,0.78459,0.80673,0 +9.251,-0.8066,-1.8623,-2.0639,0.7846,0.8066,0 +9.252,-0.80647,-1.8624,-2.0638,0.78461,0.80647,0 +9.253,-0.80634,-1.8625,-2.0637,0.78462,0.80634,0 +9.254,-0.80621,-1.8626,-2.0636,0.78463,0.80621,0 +9.255,-0.80608,-1.8627,-2.0636,0.78464,0.80608,0 +9.256,-0.80596,-1.8628,-2.0635,0.78465,0.80596,0 +9.257,-0.80584,-1.8629,-2.0634,0.78467,0.80584,0 +9.258,-0.80572,-1.8629,-2.0633,0.78468,0.80572,0 +9.259,-0.8056,-1.863,-2.0632,0.78469,0.8056,0 +9.26,-0.80548,-1.8631,-2.0632,0.78471,0.80548,0 +9.261,-0.80537,-1.8632,-2.0631,0.78472,0.80537,0 +9.262,-0.80525,-1.8633,-2.063,0.78473,0.80525,0 +9.263,-0.80513,-1.8634,-2.0629,0.78474,0.80513,0 +9.264,-0.80502,-1.8635,-2.0629,0.78476,0.80502,0 +9.265,-0.8049,-1.8636,-2.0628,0.78477,0.8049,0 +9.266,-0.80479,-1.8637,-2.0627,0.78478,0.80479,0 +9.267,-0.80467,-1.8637,-2.0626,0.7848,0.80467,0 +9.268,-0.80456,-1.8638,-2.0626,0.78481,0.80456,0 +9.269,-0.80444,-1.8639,-2.0625,0.78482,0.80444,0 +9.27,-0.80432,-1.864,-2.0624,0.78484,0.80432,0 +9.271,-0.80421,-1.8641,-2.0623,0.78485,0.80421,0 +9.272,-0.80409,-1.8642,-2.0623,0.78486,0.80409,0 +9.273,-0.80398,-1.8643,-2.0622,0.78488,0.80398,0 +9.274,-0.80386,-1.8644,-2.0621,0.78489,0.80386,0 +9.275,-0.80375,-1.8644,-2.062,0.7849,0.80375,0 +9.276,-0.80363,-1.8645,-2.062,0.78492,0.80363,0 +9.277,-0.80351,-1.8646,-2.0619,0.78493,0.80351,0 +9.278,-0.8034,-1.8647,-2.0618,0.78494,0.8034,0 +9.279,-0.80328,-1.8648,-2.0617,0.78496,0.80328,0 +9.28,-0.80317,-1.8649,-2.0617,0.78497,0.80317,0 +9.281,-0.80305,-1.865,-2.0616,0.78498,0.80305,0 +9.282,-0.80293,-1.8651,-2.0615,0.78499,0.80293,0 +9.283,-0.80282,-1.8652,-2.0614,0.78501,0.80282,0 +9.284,-0.8027,-1.8652,-2.0614,0.78502,0.8027,0 +9.285,-0.80259,-1.8653,-2.0613,0.78503,0.80259,0 +9.286,-0.80247,-1.8654,-2.0612,0.78505,0.80247,0 +9.287,-0.80236,-1.8655,-2.0611,0.78506,0.80236,0 +9.288,-0.80224,-1.8656,-2.0611,0.78507,0.80224,0 +9.289,-0.80212,-1.8657,-2.061,0.78509,0.80212,0 +9.29,-0.80201,-1.8658,-2.0609,0.7851,0.80201,0 +9.291,-0.80189,-1.8659,-2.0608,0.78511,0.80189,0 +9.292,-0.80178,-1.866,-2.0608,0.78513,0.80178,0 +9.293,-0.80166,-1.866,-2.0607,0.78514,0.80166,0 +9.294,-0.80155,-1.8661,-2.0606,0.78515,0.80155,0 +9.295,-0.80143,-1.8662,-2.0605,0.78517,0.80143,0 +9.296,-0.80131,-1.8663,-2.0605,0.78518,0.80131,0 +9.297,-0.8012,-1.8664,-2.0604,0.78519,0.8012,0 +9.298,-0.80108,-1.8665,-2.0603,0.7852,0.80108,0 +9.299,-0.80097,-1.8666,-2.0602,0.78522,0.80097,0 +9.3,-0.80085,-1.8667,-2.0602,0.78523,0.80085,0 +9.301,-0.80074,-1.8667,-2.0601,0.78524,0.80074,0 +9.302,-0.80062,-1.8668,-2.06,0.78526,0.80062,0 +9.303,-0.8005,-1.8669,-2.0599,0.78527,0.8005,0 +9.304,-0.80039,-1.867,-2.0599,0.78528,0.80039,0 +9.305,-0.80027,-1.8671,-2.0598,0.7853,0.80027,0 +9.306,-0.80016,-1.8672,-2.0597,0.78531,0.80016,0 +9.307,-0.80004,-1.8673,-2.0596,0.78532,0.80004,0 +9.308,-0.79993,-1.8674,-2.0596,0.78534,0.79993,0 +9.309,-0.79981,-1.8675,-2.0595,0.78535,0.79981,0 +9.31,-0.79969,-1.8675,-2.0594,0.78536,0.79969,0 +9.311,-0.79958,-1.8676,-2.0593,0.78538,0.79958,0 +9.312,-0.79946,-1.8677,-2.0593,0.78539,0.79946,0 +9.313,-0.79935,-1.8678,-2.0592,0.7854,0.79935,0 +9.314,-0.79923,-1.8679,-2.0591,0.78542,0.79923,0 +9.315,-0.79912,-1.868,-2.059,0.78543,0.79912,0 +9.316,-0.799,-1.8681,-2.059,0.78544,0.799,0 +9.317,-0.79888,-1.8682,-2.0589,0.78545,0.79888,0 +9.318,-0.79877,-1.8682,-2.0588,0.78547,0.79877,0 +9.319,-0.79865,-1.8683,-2.0587,0.78548,0.79865,0 +9.32,-0.79854,-1.8684,-2.0587,0.78549,0.79854,0 +9.321,-0.79842,-1.8685,-2.0586,0.78551,0.79842,0 +9.322,-0.79831,-1.8686,-2.0585,0.78552,0.79831,0 +9.323,-0.79819,-1.8687,-2.0584,0.78553,0.79819,0 +9.324,-0.79807,-1.8688,-2.0584,0.78555,0.79807,0 +9.325,-0.79796,-1.8689,-2.0583,0.78556,0.79796,0 +9.326,-0.79784,-1.869,-2.0582,0.78557,0.79784,0 +9.327,-0.79773,-1.869,-2.0581,0.78559,0.79773,0 +9.328,-0.79761,-1.8691,-2.0581,0.7856,0.79761,0 +9.329,-0.7975,-1.8692,-2.058,0.78561,0.7975,0 +9.33,-0.79738,-1.8693,-2.0579,0.78563,0.79738,0 +9.331,-0.79726,-1.8694,-2.0578,0.78564,0.79726,0 +9.332,-0.79715,-1.8695,-2.0578,0.78565,0.79715,0 +9.333,-0.79703,-1.8696,-2.0577,0.78566,0.79703,0 +9.334,-0.79692,-1.8697,-2.0576,0.78568,0.79692,0 +9.335,-0.7968,-1.8697,-2.0575,0.78569,0.7968,0 +9.336,-0.79669,-1.8698,-2.0575,0.78571,0.79669,0 +9.337,-0.79658,-1.8699,-2.0574,0.78572,0.79658,0 +9.338,-0.79648,-1.87,-2.0573,0.78573,0.79648,0 +9.339,-0.79637,-1.8701,-2.0573,0.78575,0.79637,0 +9.34,-0.79627,-1.8702,-2.0572,0.78576,0.79627,0 +9.341,-0.79616,-1.8703,-2.0571,0.78578,0.79616,0 +9.342,-0.79606,-1.8703,-2.0571,0.78579,0.79606,0 +9.343,-0.79597,-1.8704,-2.057,0.78581,0.79597,0 +9.344,-0.79587,-1.8705,-2.0569,0.78583,0.79587,0 +9.345,-0.79577,-1.8706,-2.0569,0.78584,0.79577,0 +9.346,-0.79567,-1.8707,-2.0568,0.78586,0.79567,0 +9.347,-0.79557,-1.8707,-2.0567,0.78587,0.79557,0 +9.348,-0.79548,-1.8708,-2.0567,0.78589,0.79548,0 +9.349,-0.79538,-1.8709,-2.0566,0.78591,0.79538,0 +9.35,-0.79528,-1.871,-2.0565,0.78592,0.79528,0 +9.351,-0.79518,-1.8711,-2.0565,0.78594,0.79518,0 +9.352,-0.79509,-1.8711,-2.0564,0.78595,0.79509,0 +9.353,-0.79499,-1.8712,-2.0563,0.78597,0.79499,0 +9.354,-0.79489,-1.8713,-2.0563,0.78598,0.79489,0 +9.355,-0.79479,-1.8714,-2.0562,0.786,0.79479,0 +9.356,-0.79469,-1.8715,-2.0561,0.78602,0.79469,0 +9.357,-0.7946,-1.8715,-2.0561,0.78603,0.7946,0 +9.358,-0.7945,-1.8716,-2.056,0.78605,0.7945,0 +9.359,-0.7944,-1.8717,-2.056,0.78606,0.7944,0 +9.36,-0.7943,-1.8718,-2.0559,0.78608,0.7943,0 +9.361,-0.79421,-1.8719,-2.0558,0.7861,0.79421,0 +9.362,-0.79411,-1.8719,-2.0558,0.78611,0.79411,0 +9.363,-0.79401,-1.872,-2.0557,0.78613,0.79401,0 +9.364,-0.79391,-1.8721,-2.0556,0.78614,0.79391,0 +9.365,-0.79382,-1.8722,-2.0556,0.78616,0.79382,0 +9.366,-0.79372,-1.8723,-2.0555,0.78617,0.79372,0 +9.367,-0.79362,-1.8723,-2.0554,0.78619,0.79362,0 +9.368,-0.79352,-1.8724,-2.0554,0.78621,0.79352,0 +9.369,-0.79342,-1.8725,-2.0553,0.78622,0.79342,0 +9.37,-0.79333,-1.8726,-2.0552,0.78624,0.79333,0 +9.371,-0.79323,-1.8727,-2.0552,0.78625,0.79323,0 +9.372,-0.79313,-1.8727,-2.0551,0.78627,0.79313,0 +9.373,-0.79303,-1.8728,-2.0551,0.78629,0.79303,0 +9.374,-0.79294,-1.8729,-2.055,0.7863,0.79294,0 +9.375,-0.79284,-1.873,-2.0549,0.78632,0.79284,0 +9.376,-0.79274,-1.8731,-2.0549,0.78633,0.79274,0 +9.377,-0.79264,-1.8731,-2.0548,0.78635,0.79264,0 +9.378,-0.79254,-1.8732,-2.0547,0.78637,0.79254,0 +9.379,-0.79245,-1.8733,-2.0547,0.78638,0.79245,0 +9.38,-0.79235,-1.8734,-2.0546,0.7864,0.79235,0 +9.381,-0.79225,-1.8735,-2.0545,0.78641,0.79225,0 +9.382,-0.79215,-1.8735,-2.0545,0.78643,0.79215,0 +9.383,-0.79206,-1.8736,-2.0544,0.78644,0.79206,0 +9.384,-0.79196,-1.8737,-2.0543,0.78646,0.79196,0 +9.385,-0.79186,-1.8738,-2.0543,0.78648,0.79186,0 +9.386,-0.79176,-1.8739,-2.0542,0.78649,0.79176,0 +9.387,-0.79166,-1.874,-2.0541,0.78651,0.79166,0 +9.388,-0.79157,-1.874,-2.0541,0.78652,0.79157,0 +9.389,-0.79147,-1.8741,-2.054,0.78654,0.79147,0 +9.39,-0.79137,-1.8742,-2.054,0.78656,0.79137,0 +9.391,-0.79127,-1.8743,-2.0539,0.78657,0.79127,0 +9.392,-0.79118,-1.8744,-2.0538,0.78659,0.79118,0 +9.393,-0.79108,-1.8744,-2.0538,0.7866,0.79108,0 +9.394,-0.79098,-1.8745,-2.0537,0.78662,0.79098,0 +9.395,-0.79088,-1.8746,-2.0536,0.78663,0.79088,0 +9.396,-0.79079,-1.8747,-2.0536,0.78665,0.79079,0 +9.397,-0.79069,-1.8748,-2.0535,0.78667,0.79069,0 +9.398,-0.79059,-1.8748,-2.0534,0.78668,0.79059,0 +9.399,-0.79049,-1.8749,-2.0534,0.7867,0.79049,0 +9.4,-0.79039,-1.875,-2.0533,0.78671,0.79039,0 +9.401,-0.7903,-1.8751,-2.0532,0.78673,0.7903,0 +9.402,-0.7902,-1.8752,-2.0532,0.78675,0.7902,0 +9.403,-0.7901,-1.8752,-2.0531,0.78676,0.7901,0 +9.404,-0.79,-1.8753,-2.0531,0.78678,0.79,0 +9.405,-0.78991,-1.8754,-2.053,0.78679,0.78991,0 +9.406,-0.78981,-1.8755,-2.0529,0.78681,0.78981,0 +9.407,-0.78971,-1.8756,-2.0529,0.78683,0.78971,0 +9.408,-0.78961,-1.8756,-2.0528,0.78684,0.78961,0 +9.409,-0.78951,-1.8757,-2.0527,0.78686,0.78951,0 +9.41,-0.78942,-1.8758,-2.0527,0.78687,0.78942,0 +9.411,-0.78932,-1.8759,-2.0526,0.78689,0.78932,0 +9.412,-0.78922,-1.876,-2.0525,0.7869,0.78922,0 +9.413,-0.78912,-1.876,-2.0525,0.78692,0.78912,0 +9.414,-0.78903,-1.8761,-2.0524,0.78694,0.78903,0 +9.415,-0.78893,-1.8762,-2.0523,0.78695,0.78893,0 +9.416,-0.78883,-1.8763,-2.0523,0.78697,0.78883,0 +9.417,-0.78873,-1.8764,-2.0522,0.78698,0.78873,0 +9.418,-0.78864,-1.8764,-2.0522,0.787,0.78864,0 +9.419,-0.78855,-1.8765,-2.0521,0.78701,0.78855,0 +9.42,-0.78847,-1.8766,-2.052,0.78703,0.78847,0 +9.421,-0.78838,-1.8766,-2.052,0.78704,0.78838,0 +9.422,-0.78831,-1.8767,-2.0519,0.78705,0.78831,0 +9.423,-0.78823,-1.8768,-2.0519,0.78706,0.78823,0 +9.424,-0.78816,-1.8768,-2.0518,0.78708,0.78816,0 +9.425,-0.78809,-1.8769,-2.0518,0.78709,0.78809,0 +9.426,-0.78802,-1.8769,-2.0517,0.7871,0.78802,0 +9.427,-0.78796,-1.877,-2.0517,0.78711,0.78796,0 +9.428,-0.78789,-1.8771,-2.0517,0.78712,0.78789,0 +9.429,-0.78783,-1.8771,-2.0516,0.78713,0.78783,0 +9.43,-0.78776,-1.8772,-2.0516,0.78714,0.78776,0 +9.431,-0.7877,-1.8772,-2.0515,0.78715,0.7877,0 +9.432,-0.78764,-1.8773,-2.0515,0.78716,0.78764,0 +9.433,-0.78757,-1.8773,-2.0514,0.78717,0.78757,0 +9.434,-0.78751,-1.8774,-2.0514,0.78718,0.78751,0 +9.435,-0.78744,-1.8774,-2.0513,0.78719,0.78744,0 +9.436,-0.78738,-1.8775,-2.0513,0.7872,0.78738,0 +9.437,-0.78731,-1.8775,-2.0513,0.78721,0.78731,0 +9.438,-0.78725,-1.8776,-2.0512,0.78722,0.78725,0 +9.439,-0.78718,-1.8777,-2.0512,0.78723,0.78718,0 +9.44,-0.78712,-1.8777,-2.0511,0.78724,0.78712,0 +9.441,-0.78706,-1.8778,-2.0511,0.78725,0.78706,0 +9.442,-0.78699,-1.8778,-2.051,0.78726,0.78699,0 +9.443,-0.78693,-1.8779,-2.051,0.78727,0.78693,0 +9.444,-0.78686,-1.8779,-2.0509,0.78728,0.78686,0 +9.445,-0.7868,-1.878,-2.0509,0.78729,0.7868,0 +9.446,-0.78673,-1.878,-2.0509,0.7873,0.78673,0 +9.447,-0.78667,-1.8781,-2.0508,0.78731,0.78667,0 +9.448,-0.78661,-1.8781,-2.0508,0.78732,0.78661,0 +9.449,-0.78654,-1.8782,-2.0507,0.78733,0.78654,0 +9.45,-0.78648,-1.8782,-2.0507,0.78734,0.78648,0 +9.451,-0.78641,-1.8783,-2.0506,0.78735,0.78641,0 +9.452,-0.78635,-1.8784,-2.0506,0.78736,0.78635,0 +9.453,-0.78628,-1.8784,-2.0506,0.78737,0.78628,0 +9.454,-0.78622,-1.8785,-2.0505,0.78738,0.78622,0 +9.455,-0.78615,-1.8785,-2.0505,0.78739,0.78615,0 +9.456,-0.78609,-1.8786,-2.0504,0.7874,0.78609,0 +9.457,-0.78603,-1.8786,-2.0504,0.78741,0.78603,0 +9.458,-0.78596,-1.8787,-2.0503,0.78742,0.78596,0 +9.459,-0.7859,-1.8787,-2.0503,0.78743,0.7859,0 +9.46,-0.78583,-1.8788,-2.0502,0.78744,0.78583,0 +9.461,-0.78577,-1.8788,-2.0502,0.78745,0.78577,0 +9.462,-0.7857,-1.8789,-2.0502,0.78746,0.7857,0 +9.463,-0.78564,-1.8789,-2.0501,0.78747,0.78564,0 +9.464,-0.78557,-1.879,-2.0501,0.78748,0.78557,0 +9.465,-0.78551,-1.8791,-2.05,0.78749,0.78551,0 +9.466,-0.78545,-1.8791,-2.05,0.7875,0.78545,0 +9.467,-0.78538,-1.8792,-2.0499,0.78751,0.78538,0 +9.468,-0.78532,-1.8792,-2.0499,0.78752,0.78532,0 +9.469,-0.78525,-1.8793,-2.0499,0.78753,0.78525,0 +9.47,-0.78519,-1.8793,-2.0498,0.78754,0.78519,0 +9.471,-0.78512,-1.8794,-2.0498,0.78755,0.78512,0 +9.472,-0.78506,-1.8794,-2.0497,0.78756,0.78506,0 +9.473,-0.78499,-1.8795,-2.0497,0.78757,0.78499,0 +9.474,-0.78493,-1.8795,-2.0496,0.78758,0.78493,0 +9.475,-0.78487,-1.8796,-2.0496,0.78759,0.78487,0 +9.476,-0.7848,-1.8796,-2.0495,0.7876,0.7848,0 +9.477,-0.78474,-1.8797,-2.0495,0.78761,0.78474,0 +9.478,-0.78467,-1.8798,-2.0495,0.78762,0.78467,0 +9.479,-0.78461,-1.8798,-2.0494,0.78763,0.78461,0 +9.48,-0.78454,-1.8799,-2.0494,0.78764,0.78454,0 +9.481,-0.78448,-1.8799,-2.0493,0.78765,0.78448,0 +9.482,-0.78441,-1.88,-2.0493,0.78766,0.78441,0 +9.483,-0.78435,-1.88,-2.0492,0.78767,0.78435,0 +9.484,-0.78429,-1.8801,-2.0492,0.78768,0.78429,0 +9.485,-0.78422,-1.8801,-2.0491,0.78769,0.78422,0 +9.486,-0.78416,-1.8802,-2.0491,0.7877,0.78416,0 +9.487,-0.78409,-1.8802,-2.0491,0.78771,0.78409,0 +9.488,-0.78403,-1.8803,-2.049,0.78772,0.78403,0 +9.489,-0.78396,-1.8803,-2.049,0.78773,0.78396,0 +9.49,-0.7839,-1.8804,-2.0489,0.78774,0.7839,0 +9.491,-0.78384,-1.8805,-2.0489,0.78775,0.78384,0 +9.492,-0.78377,-1.8805,-2.0488,0.78776,0.78377,0 +9.493,-0.78371,-1.8806,-2.0488,0.78777,0.78371,0 +9.494,-0.78364,-1.8806,-2.0488,0.78778,0.78364,0 +9.495,-0.78358,-1.8807,-2.0487,0.78779,0.78358,0 +9.496,-0.78351,-1.8807,-2.0487,0.7878,0.78351,0 +9.497,-0.78345,-1.8808,-2.0486,0.78781,0.78345,0 +9.498,-0.78338,-1.8808,-2.0486,0.78782,0.78338,0 +9.499,-0.78332,-1.8809,-2.0485,0.78783,0.78332,0 +9.5,-0.78326,-1.8809,-2.0485,0.78784,0.78326,0 +9.501,-0.78319,-1.881,-2.0484,0.78785,0.78319,0 +9.502,-0.78313,-1.881,-2.0484,0.78786,0.78313,0 +9.503,-0.78308,-1.8811,-2.0484,0.78787,0.78308,0 +9.504,-0.78302,-1.8811,-2.0483,0.78788,0.78302,0 +9.505,-0.78296,-1.8812,-2.0483,0.78789,0.78296,0 +9.506,-0.78291,-1.8812,-2.0483,0.78791,0.78291,0 +9.507,-0.78286,-1.8813,-2.0482,0.78792,0.78286,0 +9.508,-0.78281,-1.8813,-2.0482,0.78793,0.78281,0 +9.509,-0.78276,-1.8814,-2.0482,0.78795,0.78276,0 +9.51,-0.78271,-1.8814,-2.0481,0.78796,0.78271,0 +9.511,-0.78266,-1.8815,-2.0481,0.78797,0.78266,0 +9.512,-0.78262,-1.8815,-2.0481,0.78799,0.78262,0 +9.513,-0.78257,-1.8816,-2.048,0.788,0.78257,0 +9.514,-0.78252,-1.8816,-2.048,0.78801,0.78252,0 +9.515,-0.78247,-1.8817,-2.048,0.78803,0.78247,0 +9.516,-0.78243,-1.8817,-2.0479,0.78804,0.78243,0 +9.517,-0.78238,-1.8817,-2.0479,0.78806,0.78238,0 +9.518,-0.78233,-1.8818,-2.0479,0.78807,0.78233,0 +9.519,-0.78228,-1.8818,-2.0478,0.78808,0.78228,0 +9.52,-0.78223,-1.8819,-2.0478,0.7881,0.78223,0 +9.521,-0.78219,-1.8819,-2.0478,0.78811,0.78219,0 +9.522,-0.78214,-1.882,-2.0477,0.78812,0.78214,0 +9.523,-0.78209,-1.882,-2.0477,0.78814,0.78209,0 +9.524,-0.78204,-1.8821,-2.0477,0.78815,0.78204,0 +9.525,-0.78199,-1.8821,-2.0477,0.78817,0.78199,0 +9.526,-0.78195,-1.8821,-2.0476,0.78818,0.78195,0 +9.527,-0.7819,-1.8822,-2.0476,0.78819,0.7819,0 +9.528,-0.78185,-1.8822,-2.0476,0.78821,0.78185,0 +9.529,-0.7818,-1.8823,-2.0475,0.78822,0.7818,0 +9.53,-0.78175,-1.8823,-2.0475,0.78823,0.78175,0 +9.531,-0.78171,-1.8824,-2.0475,0.78825,0.78171,0 +9.532,-0.78166,-1.8824,-2.0474,0.78826,0.78166,0 +9.533,-0.78161,-1.8825,-2.0474,0.78828,0.78161,0 +9.534,-0.78156,-1.8825,-2.0474,0.78829,0.78156,0 +9.535,-0.78151,-1.8826,-2.0473,0.7883,0.78151,0 +9.536,-0.78147,-1.8826,-2.0473,0.78832,0.78147,0 +9.537,-0.78142,-1.8826,-2.0473,0.78833,0.78142,0 +9.538,-0.78137,-1.8827,-2.0472,0.78834,0.78137,0 +9.539,-0.78132,-1.8827,-2.0472,0.78836,0.78132,0 +9.54,-0.78127,-1.8828,-2.0472,0.78837,0.78127,0 +9.541,-0.78123,-1.8828,-2.0472,0.78839,0.78123,0 +9.542,-0.78118,-1.8829,-2.0471,0.7884,0.78118,0 +9.543,-0.78113,-1.8829,-2.0471,0.78841,0.78113,0 +9.544,-0.78108,-1.883,-2.0471,0.78843,0.78108,0 +9.545,-0.78104,-1.883,-2.047,0.78844,0.78104,0 +9.546,-0.78099,-1.8831,-2.047,0.78845,0.78099,0 +9.547,-0.78094,-1.8831,-2.047,0.78847,0.78094,0 +9.548,-0.78089,-1.8831,-2.0469,0.78848,0.78089,0 +9.549,-0.78084,-1.8832,-2.0469,0.7885,0.78084,0 +9.55,-0.7808,-1.8832,-2.0469,0.78851,0.7808,0 +9.551,-0.78075,-1.8833,-2.0468,0.78852,0.78075,0 +9.552,-0.7807,-1.8833,-2.0468,0.78854,0.7807,0 +9.553,-0.78065,-1.8834,-2.0468,0.78855,0.78065,0 +9.554,-0.7806,-1.8834,-2.0467,0.78856,0.7806,0 +9.555,-0.78056,-1.8835,-2.0467,0.78858,0.78056,0 +9.556,-0.78051,-1.8835,-2.0467,0.78859,0.78051,0 +9.557,-0.78046,-1.8835,-2.0466,0.78861,0.78046,0 +9.558,-0.78041,-1.8836,-2.0466,0.78862,0.78041,0 +9.559,-0.78036,-1.8836,-2.0466,0.78863,0.78036,0 +9.56,-0.78032,-1.8837,-2.0466,0.78865,0.78032,0 +9.561,-0.78027,-1.8837,-2.0465,0.78866,0.78027,0 +9.562,-0.78022,-1.8838,-2.0465,0.78867,0.78022,0 +9.563,-0.78017,-1.8838,-2.0465,0.78869,0.78017,0 +9.564,-0.78012,-1.8839,-2.0464,0.7887,0.78012,0 +9.565,-0.78008,-1.8839,-2.0464,0.78872,0.78008,0 +9.566,-0.78003,-1.884,-2.0464,0.78873,0.78003,0 +9.567,-0.77998,-1.884,-2.0463,0.78874,0.77998,0 +9.568,-0.77993,-1.884,-2.0463,0.78876,0.77993,0 +9.569,-0.77988,-1.8841,-2.0463,0.78877,0.77988,0 +9.57,-0.77984,-1.8841,-2.0462,0.78878,0.77984,0 +9.571,-0.77979,-1.8842,-2.0462,0.7888,0.77979,0 +9.572,-0.77974,-1.8842,-2.0462,0.78881,0.77974,0 +9.573,-0.77969,-1.8843,-2.0461,0.78883,0.77969,0 +9.574,-0.77965,-1.8843,-2.0461,0.78884,0.77965,0 +9.575,-0.7796,-1.8844,-2.0461,0.78885,0.7796,0 +9.576,-0.77955,-1.8844,-2.0461,0.78887,0.77955,0 +9.577,-0.7795,-1.8845,-2.046,0.78888,0.7795,0 +9.578,-0.77945,-1.8845,-2.046,0.78889,0.77945,0 +9.579,-0.77941,-1.8845,-2.046,0.78891,0.77941,0 +9.58,-0.77936,-1.8846,-2.0459,0.78892,0.77936,0 +9.581,-0.77931,-1.8846,-2.0459,0.78894,0.77931,0 +9.582,-0.77926,-1.8847,-2.0459,0.78895,0.77926,0 +9.583,-0.77921,-1.8847,-2.0458,0.78896,0.77921,0 +9.584,-0.77917,-1.8848,-2.0458,0.78898,0.77917,0 +9.585,-0.77913,-1.8848,-2.0458,0.789,0.77913,0 +9.586,-0.77908,-1.8849,-2.0458,0.78902,0.77908,0 +9.587,-0.77904,-1.8849,-2.0457,0.78905,0.77904,0 +9.588,-0.779,-1.885,-2.0457,0.78907,0.779,0 +9.589,-0.77896,-1.885,-2.0457,0.7891,0.77896,0 +9.59,-0.77893,-1.8851,-2.0457,0.78913,0.77893,0 +9.591,-0.77889,-1.8851,-2.0457,0.78916,0.77889,0 +9.592,-0.77886,-1.8852,-2.0456,0.7892,0.77886,0 +9.593,-0.77882,-1.8852,-2.0456,0.78923,0.77882,0 +9.594,-0.77879,-1.8853,-2.0456,0.78927,0.77879,0 +9.595,-0.77876,-1.8853,-2.0456,0.7893,0.77876,0 +9.596,-0.77872,-1.8854,-2.0456,0.78933,0.77872,0 +9.597,-0.77869,-1.8854,-2.0456,0.78937,0.77869,0 +9.598,-0.77866,-1.8855,-2.0455,0.7894,0.77866,0 +9.599,-0.77862,-1.8855,-2.0455,0.78944,0.77862,0 +9.6,-0.77859,-1.8855,-2.0455,0.78947,0.77859,0 +9.601,-0.77856,-1.8856,-2.0455,0.78951,0.77856,0 +9.602,-0.77852,-1.8856,-2.0455,0.78954,0.77852,0 +9.603,-0.77849,-1.8857,-2.0455,0.78958,0.77849,0 +9.604,-0.77846,-1.8857,-2.0455,0.78961,0.77846,0 +9.605,-0.77842,-1.8858,-2.0454,0.78965,0.77842,0 +9.606,-0.77839,-1.8858,-2.0454,0.78968,0.77839,0 +9.607,-0.77835,-1.8859,-2.0454,0.78972,0.77835,0 +9.608,-0.77832,-1.8859,-2.0454,0.78975,0.77832,0 +9.609,-0.77829,-1.886,-2.0454,0.78979,0.77829,0 +9.61,-0.77825,-1.886,-2.0454,0.78982,0.77825,0 +9.611,-0.77822,-1.8861,-2.0454,0.78986,0.77822,0 +9.612,-0.77819,-1.8861,-2.0453,0.78989,0.77819,0 +9.613,-0.77815,-1.8862,-2.0453,0.78993,0.77815,0 +9.614,-0.77812,-1.8862,-2.0453,0.78996,0.77812,0 +9.615,-0.77809,-1.8863,-2.0453,0.78999,0.77809,0 +9.616,-0.77805,-1.8863,-2.0453,0.79003,0.77805,0 +9.617,-0.77802,-1.8864,-2.0453,0.79006,0.77802,0 +9.618,-0.77799,-1.8864,-2.0453,0.7901,0.77799,0 +9.619,-0.77795,-1.8865,-2.0452,0.79013,0.77795,0 +9.62,-0.77792,-1.8865,-2.0452,0.79017,0.77792,0 +9.621,-0.77789,-1.8866,-2.0452,0.7902,0.77789,0 +9.622,-0.77785,-1.8866,-2.0452,0.79024,0.77785,0 +9.623,-0.77782,-1.8867,-2.0452,0.79027,0.77782,0 +9.624,-0.77778,-1.8867,-2.0452,0.79031,0.77778,0 +9.625,-0.77775,-1.8868,-2.0451,0.79034,0.77775,0 +9.626,-0.77772,-1.8868,-2.0451,0.79038,0.77772,0 +9.627,-0.77768,-1.8869,-2.0451,0.79041,0.77768,0 +9.628,-0.77765,-1.8869,-2.0451,0.79045,0.77765,0 +9.629,-0.77762,-1.887,-2.0451,0.79048,0.77762,0 +9.63,-0.77758,-1.887,-2.0451,0.79052,0.77758,0 +9.631,-0.77755,-1.8871,-2.0451,0.79055,0.77755,0 +9.632,-0.77752,-1.8871,-2.045,0.79058,0.77752,0 +9.633,-0.77748,-1.8872,-2.045,0.79062,0.77748,0 +9.634,-0.77745,-1.8872,-2.045,0.79065,0.77745,0 +9.635,-0.77742,-1.8873,-2.045,0.79069,0.77742,0 +9.636,-0.77738,-1.8873,-2.045,0.79072,0.77738,0 +9.637,-0.77735,-1.8874,-2.045,0.79076,0.77735,0 +9.638,-0.77732,-1.8874,-2.045,0.79079,0.77732,0 +9.639,-0.77728,-1.8875,-2.0449,0.79083,0.77728,0 +9.64,-0.77725,-1.8875,-2.0449,0.79086,0.77725,0 +9.641,-0.77721,-1.8876,-2.0449,0.7909,0.77721,0 +9.642,-0.77718,-1.8876,-2.0449,0.79093,0.77718,0 +9.643,-0.77715,-1.8877,-2.0449,0.79097,0.77715,0 +9.644,-0.77711,-1.8877,-2.0449,0.791,0.77711,0 +9.645,-0.77708,-1.8878,-2.0448,0.79104,0.77708,0 +9.646,-0.77705,-1.8878,-2.0448,0.79107,0.77705,0 +9.647,-0.77701,-1.8879,-2.0448,0.79111,0.77701,0 +9.648,-0.77698,-1.8879,-2.0448,0.79114,0.77698,0 +9.649,-0.77695,-1.888,-2.0448,0.79118,0.77695,0 +9.65,-0.77691,-1.888,-2.0448,0.79121,0.77691,0 +9.651,-0.77688,-1.8881,-2.0448,0.79124,0.77688,0 +9.652,-0.77685,-1.8881,-2.0447,0.79128,0.77685,0 +9.653,-0.77681,-1.8882,-2.0447,0.79131,0.77681,0 +9.654,-0.77678,-1.8882,-2.0447,0.79135,0.77678,0 +9.655,-0.77675,-1.8883,-2.0447,0.79138,0.77675,0 +9.656,-0.77671,-1.8883,-2.0447,0.79142,0.77671,0 +9.657,-0.77668,-1.8884,-2.0447,0.79145,0.77668,0 +9.658,-0.77664,-1.8884,-2.0447,0.79149,0.77664,0 +9.659,-0.77661,-1.8885,-2.0446,0.79152,0.77661,0 +9.66,-0.77658,-1.8885,-2.0446,0.79156,0.77658,0 +9.661,-0.77654,-1.8886,-2.0446,0.79159,0.77654,0 +9.662,-0.77651,-1.8886,-2.0446,0.79163,0.77651,0 +9.663,-0.77648,-1.8887,-2.0446,0.79166,0.77648,0 +9.664,-0.77644,-1.8887,-2.0446,0.7917,0.77644,0 +9.665,-0.77641,-1.8888,-2.0446,0.79173,0.77641,0 +9.666,-0.77638,-1.8888,-2.0445,0.79176,0.77638,0 +9.667,-0.77635,-1.8889,-2.0445,0.7918,0.77635,0 +9.668,-0.77632,-1.8889,-2.0445,0.79183,0.77632,0 +9.669,-0.77629,-1.889,-2.0445,0.79186,0.77629,0 +9.67,-0.77626,-1.889,-2.0445,0.79189,0.77626,0 +9.671,-0.77624,-1.889,-2.0445,0.79191,0.77624,0 +9.672,-0.77621,-1.8891,-2.0445,0.79194,0.77621,0 +9.673,-0.77619,-1.8891,-2.0445,0.79197,0.77619,0 +9.674,-0.77617,-1.8891,-2.0444,0.79199,0.77617,0 +9.675,-0.77615,-1.8892,-2.0444,0.79201,0.77615,0 +9.676,-0.77613,-1.8892,-2.0444,0.79203,0.77613,0 +9.677,-0.77611,-1.8892,-2.0444,0.79206,0.77611,0 +9.678,-0.77609,-1.8893,-2.0444,0.79208,0.77609,0 +9.679,-0.77607,-1.8893,-2.0444,0.7921,0.77607,0 +9.68,-0.77605,-1.8893,-2.0444,0.79212,0.77605,0 +9.681,-0.77603,-1.8893,-2.0444,0.79214,0.77603,0 +9.682,-0.77601,-1.8894,-2.0444,0.79217,0.77601,0 +9.683,-0.77599,-1.8894,-2.0444,0.79219,0.77599,0 +9.684,-0.77598,-1.8894,-2.0444,0.79221,0.77598,0 +9.685,-0.77596,-1.8895,-2.0444,0.79223,0.77596,0 +9.686,-0.77594,-1.8895,-2.0444,0.79226,0.77594,0 +9.687,-0.77592,-1.8895,-2.0443,0.79228,0.77592,0 +9.688,-0.7759,-1.8896,-2.0443,0.7923,0.7759,0 +9.689,-0.77588,-1.8896,-2.0443,0.79232,0.77588,0 +9.69,-0.77586,-1.8896,-2.0443,0.79234,0.77586,0 +9.691,-0.77584,-1.8896,-2.0443,0.79237,0.77584,0 +9.692,-0.77582,-1.8897,-2.0443,0.79239,0.77582,0 +9.693,-0.7758,-1.8897,-2.0443,0.79241,0.7758,0 +9.694,-0.77578,-1.8897,-2.0443,0.79243,0.77578,0 +9.695,-0.77576,-1.8898,-2.0443,0.79245,0.77576,0 +9.696,-0.77574,-1.8898,-2.0443,0.79248,0.77574,0 +9.697,-0.77572,-1.8898,-2.0443,0.7925,0.77572,0 +9.698,-0.7757,-1.8899,-2.0443,0.79252,0.7757,0 +9.699,-0.77569,-1.8899,-2.0442,0.79254,0.77569,0 +9.7,-0.77567,-1.8899,-2.0442,0.79257,0.77567,0 +9.701,-0.77565,-1.8899,-2.0442,0.79259,0.77565,0 +9.702,-0.77563,-1.89,-2.0442,0.79261,0.77563,0 +9.703,-0.77561,-1.89,-2.0442,0.79263,0.77561,0 +9.704,-0.77559,-1.89,-2.0442,0.79265,0.77559,0 +9.705,-0.77557,-1.8901,-2.0442,0.79268,0.77557,0 +9.706,-0.77555,-1.8901,-2.0442,0.7927,0.77555,0 +9.707,-0.77553,-1.8901,-2.0442,0.79272,0.77553,0 +9.708,-0.77551,-1.8902,-2.0442,0.79274,0.77551,0 +9.709,-0.77549,-1.8902,-2.0442,0.79276,0.77549,0 +9.71,-0.77547,-1.8902,-2.0442,0.79279,0.77547,0 +9.711,-0.77545,-1.8903,-2.0441,0.79281,0.77545,0 +9.712,-0.77543,-1.8903,-2.0441,0.79283,0.77543,0 +9.713,-0.77541,-1.8903,-2.0441,0.79285,0.77541,0 +9.714,-0.7754,-1.8903,-2.0441,0.79288,0.7754,0 +9.715,-0.77538,-1.8904,-2.0441,0.7929,0.77538,0 +9.716,-0.77536,-1.8904,-2.0441,0.79292,0.77536,0 +9.717,-0.77534,-1.8904,-2.0441,0.79294,0.77534,0 +9.718,-0.77532,-1.8905,-2.0441,0.79296,0.77532,0 +9.719,-0.7753,-1.8905,-2.0441,0.79299,0.7753,0 +9.72,-0.77528,-1.8905,-2.0441,0.79301,0.77528,0 +9.721,-0.77526,-1.8906,-2.0441,0.79303,0.77526,0 +9.722,-0.77524,-1.8906,-2.0441,0.79305,0.77524,0 +9.723,-0.77522,-1.8906,-2.0441,0.79307,0.77522,0 +9.724,-0.7752,-1.8906,-2.044,0.7931,0.7752,0 +9.725,-0.77518,-1.8907,-2.044,0.79312,0.77518,0 +9.726,-0.77516,-1.8907,-2.044,0.79314,0.77516,0 +9.727,-0.77514,-1.8907,-2.044,0.79316,0.77514,0 +9.728,-0.77512,-1.8908,-2.044,0.79319,0.77512,0 +9.729,-0.77511,-1.8908,-2.044,0.79321,0.77511,0 +9.73,-0.77509,-1.8908,-2.044,0.79323,0.77509,0 +9.731,-0.77507,-1.8909,-2.044,0.79325,0.77507,0 +9.732,-0.77505,-1.8909,-2.044,0.79327,0.77505,0 +9.733,-0.77503,-1.8909,-2.044,0.7933,0.77503,0 +9.734,-0.77501,-1.8909,-2.044,0.79332,0.77501,0 +9.735,-0.77499,-1.891,-2.044,0.79334,0.77499,0 +9.736,-0.77497,-1.891,-2.0439,0.79336,0.77497,0 +9.737,-0.77495,-1.891,-2.0439,0.79339,0.77495,0 +9.738,-0.77493,-1.8911,-2.0439,0.79341,0.77493,0 +9.739,-0.77491,-1.8911,-2.0439,0.79343,0.77491,0 +9.74,-0.77489,-1.8911,-2.0439,0.79345,0.77489,0 +9.741,-0.77487,-1.8912,-2.0439,0.79347,0.77487,0 +9.742,-0.77485,-1.8912,-2.0439,0.7935,0.77485,0 +9.743,-0.77483,-1.8912,-2.0439,0.79352,0.77483,0 +9.744,-0.77482,-1.8913,-2.0439,0.79354,0.77482,0 +9.745,-0.7748,-1.8913,-2.0439,0.79356,0.7748,0 +9.746,-0.77478,-1.8913,-2.0439,0.79358,0.77478,0 +9.747,-0.77476,-1.8913,-2.0439,0.79361,0.77476,0 +9.748,-0.77474,-1.8914,-2.0438,0.79363,0.77474,0 +9.749,-0.77472,-1.8914,-2.0438,0.79365,0.77472,0 +9.75,-0.7747,-1.8914,-2.0438,0.79367,0.7747,0 +9.751,-0.77469,-1.8915,-2.0438,0.79369,0.77469,0 +9.752,-0.77468,-1.8915,-2.0438,0.79372,0.77468,0 +9.753,-0.77467,-1.8915,-2.0438,0.79374,0.77467,0 +9.754,-0.77466,-1.8915,-2.0438,0.79376,0.77466,0 +9.755,-0.77465,-1.8915,-2.0438,0.79378,0.77465,0 +9.756,-0.77465,-1.8916,-2.0438,0.7938,0.77465,0 +9.757,-0.77465,-1.8916,-2.0438,0.79382,0.77465,0 +9.758,-0.77465,-1.8916,-2.0438,0.79384,0.77465,0 +9.759,-0.77465,-1.8916,-2.0439,0.79386,0.77465,0 +9.76,-0.77465,-1.8916,-2.0439,0.79388,0.77465,0 +9.761,-0.77465,-1.8916,-2.0439,0.7939,0.77465,0 +9.762,-0.77465,-1.8916,-2.0439,0.79392,0.77465,0 +9.763,-0.77465,-1.8917,-2.0439,0.79394,0.77465,0 +9.764,-0.77465,-1.8917,-2.0439,0.79397,0.77465,0 +9.765,-0.77465,-1.8917,-2.0439,0.79399,0.77465,0 +9.766,-0.77465,-1.8917,-2.0439,0.79401,0.77465,0 +9.767,-0.77465,-1.8917,-2.0439,0.79403,0.77465,0 +9.768,-0.77465,-1.8917,-2.0439,0.79405,0.77465,0 +9.769,-0.77465,-1.8917,-2.0439,0.79407,0.77465,0 +9.77,-0.77465,-1.8918,-2.0439,0.79409,0.77465,0 +9.771,-0.77465,-1.8918,-2.0439,0.79411,0.77465,0 +9.772,-0.77465,-1.8918,-2.0439,0.79413,0.77465,0 +9.773,-0.77465,-1.8918,-2.0439,0.79415,0.77465,0 +9.774,-0.77465,-1.8918,-2.0439,0.79417,0.77465,0 +9.775,-0.77465,-1.8918,-2.0439,0.79419,0.77465,0 +9.776,-0.77465,-1.8919,-2.044,0.79421,0.77465,0 +9.777,-0.77465,-1.8919,-2.044,0.79423,0.77465,0 +9.778,-0.77465,-1.8919,-2.044,0.79425,0.77465,0 +9.779,-0.77465,-1.8919,-2.044,0.79427,0.77465,0 +9.78,-0.77465,-1.8919,-2.044,0.79429,0.77465,0 +9.781,-0.77465,-1.8919,-2.044,0.79431,0.77465,0 +9.782,-0.77465,-1.8919,-2.044,0.79434,0.77465,0 +9.783,-0.77465,-1.892,-2.044,0.79436,0.77465,0 +9.784,-0.77465,-1.892,-2.044,0.79438,0.77465,0 +9.785,-0.77465,-1.892,-2.044,0.7944,0.77465,0 +9.786,-0.77465,-1.892,-2.044,0.79442,0.77465,0 +9.787,-0.77465,-1.892,-2.044,0.79444,0.77465,0 +9.788,-0.77465,-1.892,-2.044,0.79446,0.77465,0 +9.789,-0.77465,-1.892,-2.044,0.79448,0.77465,0 +9.79,-0.77465,-1.8921,-2.044,0.7945,0.77465,0 +9.791,-0.77465,-1.8921,-2.044,0.79452,0.77465,0 +9.792,-0.77465,-1.8921,-2.0441,0.79454,0.77465,0 +9.793,-0.77465,-1.8921,-2.0441,0.79456,0.77465,0 +9.794,-0.77465,-1.8921,-2.0441,0.79458,0.77465,0 +9.795,-0.77465,-1.8921,-2.0441,0.7946,0.77465,0 +9.796,-0.77465,-1.8921,-2.0441,0.79462,0.77465,0 +9.797,-0.77465,-1.8922,-2.0441,0.79464,0.77465,0 +9.798,-0.77465,-1.8922,-2.0441,0.79466,0.77465,0 +9.799,-0.77465,-1.8922,-2.0441,0.79468,0.77465,0 +9.8,-0.77465,-1.8922,-2.0441,0.7947,0.77465,0 +9.801,-0.77465,-1.8922,-2.0441,0.79473,0.77465,0 +9.802,-0.77465,-1.8922,-2.0441,0.79475,0.77465,0 +9.803,-0.77465,-1.8922,-2.0441,0.79477,0.77465,0 +9.804,-0.77465,-1.8923,-2.0441,0.79479,0.77465,0 +9.805,-0.77465,-1.8923,-2.0441,0.79481,0.77465,0 +9.806,-0.77465,-1.8923,-2.0441,0.79483,0.77465,0 +9.807,-0.77465,-1.8923,-2.0441,0.79485,0.77465,0 +9.808,-0.77465,-1.8923,-2.0441,0.79487,0.77465,0 +9.809,-0.77465,-1.8923,-2.0442,0.79489,0.77465,0 +9.81,-0.77465,-1.8923,-2.0442,0.79491,0.77465,0 +9.811,-0.77465,-1.8924,-2.0442,0.79493,0.77465,0 +9.812,-0.77465,-1.8924,-2.0442,0.79495,0.77465,0 +9.813,-0.77465,-1.8924,-2.0442,0.79497,0.77465,0 +9.814,-0.77465,-1.8924,-2.0442,0.79499,0.77465,0 +9.815,-0.77465,-1.8924,-2.0442,0.79501,0.77465,0 +9.816,-0.77465,-1.8924,-2.0442,0.79503,0.77465,0 +9.817,-0.77465,-1.8924,-2.0442,0.79505,0.77465,0 +9.818,-0.77465,-1.8925,-2.0442,0.79507,0.77465,0 +9.819,-0.77465,-1.8925,-2.0442,0.7951,0.77465,0 +9.82,-0.77465,-1.8925,-2.0442,0.79512,0.77465,0 +9.821,-0.77465,-1.8925,-2.0442,0.79514,0.77465,0 +9.822,-0.77465,-1.8925,-2.0442,0.79516,0.77465,0 +9.823,-0.77465,-1.8925,-2.0442,0.79518,0.77465,0 +9.824,-0.77465,-1.8925,-2.0442,0.7952,0.77465,0 +9.825,-0.77465,-1.8926,-2.0443,0.79522,0.77465,0 +9.826,-0.77465,-1.8926,-2.0443,0.79524,0.77465,0 +9.827,-0.77465,-1.8926,-2.0443,0.79526,0.77465,0 +9.828,-0.77465,-1.8926,-2.0443,0.79528,0.77465,0 +9.829,-0.77465,-1.8926,-2.0443,0.7953,0.77465,0 +9.83,-0.77465,-1.8926,-2.0443,0.79532,0.77465,0 +9.831,-0.77465,-1.8926,-2.0443,0.79534,0.77465,0 +9.832,-0.77465,-1.8927,-2.0443,0.79536,0.77465,0 +9.833,-0.77465,-1.8927,-2.0443,0.79538,0.77465,0 +9.834,-0.77465,-1.8927,-2.0443,0.79539,0.77465,0 +9.835,-0.77465,-1.8927,-2.0443,0.7954,0.77465,0 +9.836,-0.77465,-1.8927,-2.0443,0.79542,0.77465,0 +9.837,-0.77465,-1.8927,-2.0443,0.79542,0.77465,0 +9.838,-0.77465,-1.8927,-2.0443,0.79543,0.77465,0 +9.839,-0.77465,-1.8927,-2.0443,0.79543,0.77465,0 +9.84,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.841,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.842,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.843,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.844,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.845,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.846,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.847,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.848,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.849,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.85,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.851,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.852,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.853,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.854,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.855,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.856,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.857,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.858,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.859,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.86,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.861,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.862,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.863,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.864,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.865,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.866,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.867,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.868,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.869,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.87,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.871,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.872,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.873,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.874,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.875,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.876,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.877,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.878,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.879,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.88,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.881,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.882,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.883,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.884,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.885,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.886,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.887,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.888,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.889,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.89,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.891,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.892,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.893,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.894,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.895,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.896,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.897,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.898,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.899,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.9,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.901,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.902,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.903,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.904,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.905,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.906,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.907,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.908,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.909,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.91,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.911,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.912,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.913,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.914,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.915,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.916,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.917,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.918,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.919,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.92,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.921,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.922,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.923,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.924,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.925,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.926,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.927,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.928,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.929,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.93,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.931,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.932,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.933,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.934,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.935,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.936,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.937,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.938,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.939,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.94,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.941,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.942,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.943,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.944,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.945,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.946,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.947,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.948,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.949,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.95,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.951,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.952,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.953,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.954,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.955,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.956,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.957,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.958,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.959,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.96,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.961,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.962,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.963,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.964,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.965,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.966,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.967,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.968,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.969,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.97,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.971,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.972,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.973,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.974,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.975,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.976,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.977,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.978,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.979,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.98,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.981,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.982,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.983,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.984,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.985,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.986,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.987,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.988,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.989,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.99,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.991,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.992,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.993,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.994,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.995,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.996,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.997,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.998,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +9.999,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 +10,-0.77465,-1.8927,-2.0443,0.79544,0.77465,0 diff --git a/dmp/notes.md b/dmp/notes.md new file mode 100644 index 0000000000000000000000000000000000000000..35e852d3e8cf52b28423f996276f6f53a53fa7ec --- /dev/null +++ b/dmp/notes.md @@ -0,0 +1,59 @@ +# pixel trajectory: +----------------- +have your pixels in a 2D array of length N points : ((x0,y0), (x1,y1),...(xN,yN)) +time is just np.arange(N). +these guys are relatively sparse, ~150 points. +in the program the distribution is dependent on how fast you move your mouse, +which is why i assume means it's not of great importance as long as it +covers everything reasonably + +# 3D cartesian trajectory: +------------------------- +just put your pixels onto a plane onto a predefined place with the right coordinate transform. +ofc you have the pixel -> mm conversion and mins and maxes. whatever makes sense workspace-wise is good. + +# timed joint trajectory +----------------------------- +the UR matlab module just magically calculates what's needed. +thus just running clik along the points to get joint angles for each point is almost certainly fine, +although can be probably made better or worse. +once you got q(t), you just do the most basic finite-difference +to get q_dot(t) and q_ddot(t). +that's it as far as trajectory generation is concerned. +the result in the end is a +struct q_traj{ + t : 1 x N; + pos: 6 x N; + vel: 6 x N; + acc: 6 x N +} +how to read this from the .mat if you leave it this way idk. +but you'll almost certainly want to replicate this code anyway so who cares. + +# dmp-ing the trajectory +-------------------------- + +- idea type beat: we're doing it in joint space, but since it's just a demo, +doing it with speedl might be easier (it's not like +the damped pseudoinverse is peak performance, let's be real) + + +# control loop around trajectory following +------------------------------------------- +it's literally just feedforward position and feedback velocity +```python +def compute_ctrl(self, target_state, robot_state): + ff = 0. + fb = 0. + target_position = np.array(target_state.position) + target_velocity = np.array(target_state.velocity) + robot_position = np.array(robot_state.position) + if target_velocity.size > 0: + ff = target_velocity + if target_position.size > 0: + fb = self.kp * (target_position - robot_position) + vel_cmd = ff + fb + np.clip(vel_cmd, -self.vel_max, self.vel_max, out=vel_cmd) + + return vel_cmd +``` diff --git a/dmp/pdfs/neco_a_00393.pdf b/dmp/pdfs/neco_a_00393.pdf new file mode 100644 index 0000000000000000000000000000000000000000..07188d4a6ab8df8e4d375e92a0067e6575893ebf Binary files /dev/null and b/dmp/pdfs/neco_a_00393.pdf differ diff --git a/dmp/traj_scaling_node b/dmp/traj_scaling_node deleted file mode 100755 index e4e6acad8e99984466b41df2e84efdcd15a7fdea..0000000000000000000000000000000000000000 --- a/dmp/traj_scaling_node +++ /dev/null @@ -1,113 +0,0 @@ -#!/usr/bin/env python - -from motion_planning.online_traj_scaling import GMRwOA, TrajectoryGenerator -import numpy as np -import rospy -from robot_ctrl.msg import CtrlTarget -from std_msgs.msg import Float64, String -from motion_planning.msg import TrajGenState - - -class TrajGenNode: - def __init__(self): - self.active = False - self.rate = None - self.dt = None - self.traj_gen = None - - # Load parameters from server - if not self.load_params(): - rospy.logwarn("Trajectory Generator not initialized") - - # Setup ros topics - self.target_pub = rospy.Publisher("robot_ctrl/command", CtrlTarget, queue_size=1) - self.state_pub = rospy.Publisher("motion_planning/state", TrajGenState, queue_size=1) - rospy.Subscriber("motion_planning/command", String, self.command_parser) - - # Go into spin - self.spin() - - def load_params(self): - parameters = ['x0', 's_end', 'priors', 'mu', 'sigma', 'o_c', 'o_r'] - if not rospy.has_param('motion_planning/update_rate'): - rospy.logerr("Parameter " + rospy.get_namespace() + "motion_planning/update_rate not on parameter server.") - return False - update_rate = rospy.get_param('motion_planning/update_rate') - self.rate = rospy.Rate(update_rate) - params = {} - for i in range(len(parameters)): - if not rospy.has_param('motion_planning/' + parameters[i]): - rospy.logerr("Parameter " + rospy.get_namespace() + "motion_planning/" + parameters[i] + " not on parameter server.") - return False - params[parameters[i]] = rospy.get_param('motion_planning/' + parameters[i]) - gmr = GMRwOA(params) - self.traj_gen = TrajectoryGenerator(gmr) - return True - - def command_parser(self, msg): - if msg.data == 'start': - self.active = True - elif msg.data == 'stop': - self.active = False - elif msg.data == 'reset': - self.traj_gen.reset() - self.active = False - rospy.loginfo("Reset motion_planner.") - elif msg.data == 'step': - self.traj_gen.step(self.dt) - elif msg.data == 'load_params': - self.load_params() - rospy.loginfo("Reloaded motion_planner parameters.") - else: - rospy.loginfo("Invalid command string for motion planner.") - - # spin ----------------------------------------------------- - # ----------------------------------------------------------- - def spin(self): - print_flag = True - while not rospy.is_shutdown(): - - if self.active: - # Step DMP - self.traj_gen.step(self.dt) - # Send target trajectory state command - pub_msg = CtrlTarget() - pub_msg.header.stamp = rospy.Time.now() - pub_msg.acceleration = self.traj_gen.acc - pub_msg.velocity = self.traj_gen.vel - pub_msg.position = self.traj_gen.pos - self.target_pub.publish(pub_msg) - else: - print_flag = True - - # Publish DMP state command - pub_msg = TrajGenState() - pub_msg.header.stamp = rospy.Time.now() - pub_msg.acceleration = [0.0032*self.traj_gen.acc[0], 0, 0.0026*self.traj_gen.acc[1]] - pub_msg.velocity = [0.0032*self.traj_gen.vel[0], 0, 0.0026*self.traj_gen.vel[1]] - pub_msg.position = [0.0032*self.traj_gen.pos[0], 0, 0.0026*self.traj_gen.pos[1]+0.7] - pub_msg.s = self.traj_gen.s - pub_msg.s_dot = self.traj_gen.ds - self.state_pub.publish(pub_msg) - - # Notify when DMP trajectory is finished - if print_flag and self.traj_gen.s > self.traj_gen.dyn_sys.s_end: - rospy.loginfo("Trajectory finished.") - print_flag = False - - # Sleep - self.rate.sleep() - - -# -------------------------------------------------------------------- -# Here is the main entry point -if __name__ == '__main__': - try: - # Init the node: - rospy.init_node('TrajGenNode') - - # Initializing and continue running the main class: - TrajGenNode() - - except rospy.ROSInterruptException: - pass diff --git a/dmp/vel_ff_pos_fb_node b/dmp/vel_ff_pos_fb_node new file mode 100755 index 0000000000000000000000000000000000000000..d0033954fd934a8ee2617e2cbece24d6440100bc --- /dev/null +++ b/dmp/vel_ff_pos_fb_node @@ -0,0 +1,105 @@ +#!/usr/bin/env python + +import rospy +import numpy as np +from sensor_msgs.msg import JointState +from std_msgs.msg import Empty +from robot_ctrl.msg import CtrlTarget + +class VelFFPosFB: + def __init__(self, kp, vel_max): + # Controller parameters: + self.kp = kp + self.vel_max = vel_max + # Command state + self.vel_cmd = None + + def compute_ctrl(self, target_state, robot_state): + ff = 0. + fb = 0. + target_position = np.array(target_state.position) + target_velocity = np.array(target_state.velocity) + robot_position = np.array(robot_state.position) + if target_velocity.size > 0: + ff = target_velocity + if target_position.size > 0: + fb = self.kp * (target_position - robot_position) + vel_cmd = ff + fb + np.clip(vel_cmd, -self.vel_max, self.vel_max, out=vel_cmd) + + return vel_cmd + + +class VelFFPosFBNode: + def __init__(self): + self.ctrl = None + self.rate = None + self.max_msg_deadtime = 0.1 + self.robot_state = CtrlTarget() + self.target_state = CtrlTarget() + + if not self.load_params(0): + exit(1) + + self.vel_cmd_publisher = rospy.Publisher("robot_interface/vel_command", CtrlTarget, queue_size=1) + rospy.Subscriber("robot_interface/joint_states", JointState, self.state_update) + rospy.Subscriber("robot_ctrl/command", CtrlTarget, self.target_update) + rospy.Subscriber("robot_ctrl/reload_params", Empty, self.load_params) + + self.spin() + + def load_params(self,dummydata): + # Check necessary parameter existences + if not rospy.has_param('robot_ctrl/update_rate'): + rospy.logerr("Parameter " + rospy.get_namespace() + "robot_ctrl/update_rate not set.") + return False + if not rospy.has_param('robot_ctrl/kp'): + rospy.logerr("Parameter " + rospy.get_namespace() + "robot_ctrl/kp not set.") + return False + if not rospy.has_param('robot_ctrl/vel_max'): + rospy.logerr("Parameter " + rospy.get_namespace() + "robot_ctrl/vel_max not set.") + return False + # Load parameters from server + self.rate = rospy.Rate(rospy.get_param('robot_ctrl/update_rate')) + kp = rospy.get_param('robot_ctrl/kp') + vel_max = np.array(rospy.get_param('robot_ctrl/vel_max')) + # Create control object + self.ctrl = VelFFPosFB(kp, vel_max) + rospy.loginfo("Loaded robot_ctrl parameters.") + return True + + def state_update(self, msg): + self.robot_state = msg + + def target_update(self, msg): + self.target_state = msg + self.target_state.header.stamp = rospy.Time.now() + + def spin(self): + while (not rospy.is_shutdown()): + target_msg_deadtime = (rospy.Time.now() - self.target_state.header.stamp).to_sec() + robot_msg_deadtime = (rospy.Time.now() - self.robot_state.header.stamp).to_sec() + if target_msg_deadtime < self.max_msg_deadtime and robot_msg_deadtime < self.max_msg_deadtime: + # Compute velocity command + vel_cmd = self.ctrl.compute_ctrl(self.target_state, self.robot_state) + + # publish joint velocities command + cmd_msg = CtrlTarget() + cmd_msg.header.stamp = rospy.Time.now() + cmd_msg.velocity = vel_cmd + self.vel_cmd_publisher.publish(cmd_msg) + + self.rate.sleep() + + +# Here is the main entry point +if __name__ == '__main__': + try: + # Init the node + rospy.init_node('VelFFPosFBNode') + + # Initializing and continue running the main class + VelFFPosFBNode() + + except rospy.ROSInterruptException: + pass \ No newline at end of file diff --git a/docs/scriptManual-3.5.4.pdf b/docs/scriptManual-3.5.4.pdf new file mode 100644 index 0000000000000000000000000000000000000000..88ceef89c4986a8cf7ecc1701c1e3b44a03dfe7b Binary files /dev/null and b/docs/scriptManual-3.5.4.pdf differ diff --git a/util/freedrive.py b/util/freedrive.py new file mode 100644 index 0000000000000000000000000000000000000000..c0f753429327e865419df2d8799c6af2d675f63a --- /dev/null +++ b/util/freedrive.py @@ -0,0 +1,22 @@ +from rtde_control import RTDEControlInterface as RTDEControl +from rtde_receive import RTDEReceiveInterface as RTDEReceive +import time +import signal + +def handler(signum, frame): + print('i will end freedrive and exit') + rtde_control.endFreedriveMode() + exit() + + +rtde_control = RTDEControl("192.168.1.102") +rtde_receive = RTDEReceive("192.168.1.102") + +rtde_control.freedriveMode() +signal.signal(signal.SIGINT, handler) +time.sleep(100) + +#time.sleep(1) +#print(rtde_control.getFreedriveStatus()) +#rtde_control.endFreedriveMode() +#print("done")