diff --git a/.gitignore b/.gitignore index f6e1085a7abc7796ad1bb7a5eb3e4162b6e1260f..de5ccdf9c5397fda4af578af787b4b31fa9605ea 100644 --- a/.gitignore +++ b/.gitignore @@ -22,5 +22,6 @@ data/Gemini_Roccaraso_september_2023/HIL_CPP_files_ADA/** **/*.mat **/*.fig **/*.avi +**/*.csv data/msa-toolkit/* CdIdentification/estimatedCoefficients* \ No newline at end of file diff --git a/CdIdentification/mainCdIdentfication.m b/CdIdentification/mainCdIdentfication.m index 878126b59f01300ec21b5162cf0892e7e609faed..39fbc7a20c988e29d97a12e0a164bfa4823ab24b 100644 --- a/CdIdentification/mainCdIdentfication.m +++ b/CdIdentification/mainCdIdentfication.m @@ -59,7 +59,7 @@ else flagOverwrite =false; end -saveFileName = "flightData\"+settings.mission+"estimatedCorrectionFactor"; +saveFileName = "flightData\"+mission.name+"estimatedCorrectionFactor"; %% generate guess x0(1) = 1; % multiplicative factor for drag coefficient in the @@ -79,12 +79,12 @@ R = eye(6); R_m = inv(R); %% extract data from simulation -% fileNAS = "flightData\"+settings.mission+"\Boardcore_NASState"; -% fileOutputABK = "flightData\"+settings.mission+"\Boardcore_ServoData"; -fileNAS = "flightData\"+settings.mission+"\NASData_corrected"; -fileOutputABK = "flightData\"+settings.mission+"\ABKData_corrected"; +% fileNAS = "flightData\"+mission.name+"\Boardcore_NASState"; +% fileOutputABK = "flightData\"+mission.name+"\Boardcore_ServoData"; +fileNAS = "flightData\"+mission.name+"\NASData_corrected"; +fileOutputABK = "flightData\"+mission.name+"\ABKData_corrected"; -switch settings.mission +switch mission.name case 'Pyxis_Portugal_October_2022' t_start =3338; t_end = 3350; @@ -92,9 +92,9 @@ switch settings.mission error('We do not have the logs of the air brakes unfortunately for this flight.\n') case 'Gemini_Roccaraso_September_2023' - % t_start = 8536 + settings.tb; + % t_start = 8536 + rocket.motor.time(end); % t_end = 8553; - t_start = 1 + settings.tb; + t_start = 1 + rocket.motor.time(end); t_end = 18; end @@ -155,7 +155,7 @@ for i = 1: length(t_m) end end ABK_value = ABK_value*settings.servo.maxAngle; -time_offset = t_m(1)-settings.motor.expTime(end); +time_offset = t_m(1)-rocket.motor.time(end); ABK_time = ABK_time-time_offset; t_m = t_m-time_offset; ABK_perc = [ABK_time,ABK_value]; diff --git a/common b/common index f5b141b277caeb6d39e62dc8122b398e2eeff3f9..4ddde9cc3a41cb5eabcae6dc75dea3b3ac21bcc7 160000 --- a/common +++ b/common @@ -1 +1 @@ -Subproject commit f5b141b277caeb6d39e62dc8122b398e2eeff3f9 +Subproject commit 4ddde9cc3a41cb5eabcae6dc75dea3b3ac21bcc7 diff --git a/commonFunctions/control/control_PID.m b/commonFunctions/control/control_PID.m index fd77bec312fb95114e625ada422c0bcf4c0c9716..718b9f8dda94e4ee044a3a37e24748f90e2d7cf3 100644 --- a/commonFunctions/control/control_PID.m +++ b/commonFunctions/control/control_PID.m @@ -31,7 +31,7 @@ time = nas_state.time; z = nas_state.z; Vz = nas_state.vz; -[z_setpoint, Vz_setpoint, csett] = set_Trajectory(time,z-settings.z0, Vz, csett); +[z_setpoint, Vz_setpoint, csett] = set_Trajectory(time,z-environment.z0, Vz, csett); % [z_setpoint, Vz_setpoint, csett] = set_Trajectory(time,z, Vz, csett); %% PI ALGORITHM @@ -56,7 +56,7 @@ extMin = 0; %%%%%%% Cd_min = getDrag(V_mod,z,extMin, csett.coeff_Cd); -Cd_max = getDrag(V_mod,z,extMax, csett.coeff_Cd); % coefficients for getDrag are set in configSimulator -> settings.mission +Cd_max = getDrag(V_mod,z,extMax, csett.coeff_Cd); % coefficients for getDrag are set in configSimulator -> mission.name Umin = 0.5*ro*Cd_min*csett.S0*Vz*V_mod; % min force Umax = 0.5*ro*Cd_max*csett.S0*Vz*V_mod; % max force @@ -93,7 +93,7 @@ N_points = size(csett.reference.Vz,2); -switch settings.mission +switch mission.name case 'Lynx_Roccaraso_September_2021' alpha_available = linspace(0,0.89,N_points); ext_available = zeros(1,N_points); @@ -143,7 +143,7 @@ delta_S = delta_S_available(index_minimum); %% TRANSFORMATION FROM delta_S to SERVOMOTOR ANGLE DEGREES -switch settings.mission +switch mission.name case 'Lynx_Roccaraso_September_2021' alpha_rad = (-csett.b + sqrt(csett.b^2 + 4*csett.a*delta_S)) / (2*csett.a); case 'Lynx_Portugal_October_2021' diff --git a/commonFunctions/control/control_Servo.m b/commonFunctions/control/control_Servo.m index ad6f3f52408cd070ae0448b71f9b22b1e3b6e448..9a10cdf64f0686cb7b1205faa166a8ffdb3b35a9 100644 --- a/commonFunctions/control/control_Servo.m +++ b/commonFunctions/control/control_Servo.m @@ -33,7 +33,7 @@ CONTROL_ALGORITHM_SERVO_DEGREE Finds trejectory (z-Vz) to follow and uses a PI % Control variable limits -switch settings.mission +switch mission.name case 'Pyxis_Portugal_October_2022' alphaMax= 68; % degrees case 'Pyxis_Roccaraso_September_2022' diff --git a/commonFunctions/kalman/run_ADA.m b/commonFunctions/kalman/run_ADA.m index deed7647ba5b644337f684d30f3a2fff62f30e37..86c6a974708f88d4394581e52d93b59a474c477c 100644 --- a/commonFunctions/kalman/run_ADA.m +++ b/commonFunctions/kalman/run_ADA.m @@ -122,7 +122,7 @@ if length(t_ada)>1 if strcmp(settings.scenario, 'descent') || ada.flag_apo if ada.flagOpenPara == false - if xv(ii,1) < settings.para(1).z_cut + if xv(ii,1) < settings.ada.para.z_cut ada.paraCounter = ada.paraCounter+1; else ada.paraCounter = 0; diff --git a/commonFunctions/kalman/run_MEA.m b/commonFunctions/kalman/run_MEA.m index 0d63e89bf10ca79f5238c5193b748df2dccc4aae..27a95d46cd310178f9b6d9b3a50aa405241c3f44 100644 --- a/commonFunctions/kalman/run_MEA.m +++ b/commonFunctions/kalman/run_MEA.m @@ -1,4 +1,4 @@ -function [sensorData,sensorTot] = run_MEA(sensorData,sensorTot,settings,contSettings,u,T1) +function [sensorData,sensorTot] = run_MEA(sensorData,sensorTot,settings,contSettings,u,T1,engineT0,environment,rocket, mission) % mass estimation @@ -50,7 +50,7 @@ for ii = 2:length(t_mea) end end %accelerometer correction (not for 2023) - if ~contains(settings.mission, '2023') + if ~contains(mission.name, '2023') K_t = settings.mea.K_t; alpha = settings.mea.alpha; c = settings.mea.c; @@ -66,10 +66,10 @@ for ii = 2:length(t_mea) cd = 1*getDrag(vnorm_nas(ii), -z_nas(ii), 0, contSettings.coeff_Cd); %add correction shut_down?? [~,~,P_e, rho] = atmosisa(-z_nas(ii)); q = 0.5*rho*vnorm_nas(ii)^2; %dynamic pressure - F_a = q*settings.S*cd; %aerodynamic force + F_a = q*rocket.crossSection*cd; %aerodynamic force if -z_nas(ii,1)> 800 - F_s = (P_0-P_e)*settings.motor.Ae ; + F_s = (P_0-P_e)*rocket.motor.ae; else F_s = 0; end @@ -110,14 +110,14 @@ for ii = 2:length(t_mea) if propagation_steps >=1 [z_pred, vz_pred] = PropagateState(-z_nas(ii),-vz_nas(ii), ... K_t .* sensorTot.comb_chamber.measures(index_chambPress), ... - settings.S, CD, rho,x(ii, 3), 0.02, propagation_steps); + rocket.crossSection, CD, rho,x(ii, 3), 0.02, propagation_steps); else z_pred = -z_nas(ii); vz_pred = -vz_nas(ii); end - predicted_apogee(ii) = z_pred-settings.z0 + 1./(2.*( 0.5.*rho .* CD * settings.S ./ mass))... - .* log(1 + (vz_pred.^2 .* (0.5 .* rho .* CD .* settings.S) ./ mass) ./ 9.81 ); + predicted_apogee(ii) = z_pred-environment.z0 + 1./(2.*( 0.5.*rho .* CD * rocket.crossSection ./ mass))... + .* log(1 + (vz_pred.^2 .* (0.5 .* rho .* CD .* rocket.crossSection) ./ mass) ./ 9.81 ); % retrieve NAS data index_NAS = sum(t_mea(ii) >= t_nas); diff --git a/commonFunctions/kalman/run_NAS.m b/commonFunctions/kalman/run_NAS.m index e8ce47ab03ef5e16a13adf3e9c9f9b11ede60d3f..7c978cebde5486486010022f747a9e635723991b 100644 --- a/commonFunctions/kalman/run_NAS.m +++ b/commonFunctions/kalman/run_NAS.m @@ -1,4 +1,4 @@ -function [sensorData,sensorTot,nas] = run_NAS(Tf, mag_NED,sensorData,sensorTot,settings) +function [sensorData,sensorTot,nas] = run_NAS(Tf, mag_NED,sensorData,sensorTot,settings, environment) % Author: Alejandro Montero % Co-Author: Alessandro Del Duca @@ -161,7 +161,7 @@ if length(t_nas) > 1 [x_lin(ii,:),P_lin(:,:,ii),~] = correctionGPS(x_lin(ii,:),... P_lin(:,:,ii),sensorTot.gps.position_measures(index_GPS,1:2),... sensorTot.gps.velocity_measures(index_GPS,1:2),nas.sigma_GPS,... - fix, settings.lat0, settings.lon0,nas.GPS.a,nas.GPS.b); + fix, environment.lat0, environment.lon0,nas.GPS.a,nas.GPS.b); end sensorTot.gps.lastindex = index_GPS; end @@ -170,7 +170,7 @@ if length(t_nas) > 1 % barometer index_bar = sum(t_nas(ii) >= t_barotemp); - [x_lin(ii,:),P_lin(:,:,ii),~] = correctionBarometer(x_lin(ii,:),P_lin(:,:,ii),sensorTot.barometer.pressure_measures(index_bar),nas.sigma_baro,nas.baro,settings.z0); + [x_lin(ii,:),P_lin(:,:,ii),~] = correctionBarometer(x_lin(ii,:),P_lin(:,:,ii),sensorTot.barometer.pressure_measures(index_bar),nas.sigma_baro,nas.baro,environment.z0); % magnetometer [xq(ii,:),P_q(:,:,ii),~,~] = correctorQuat(xq(ii,:),P_q(:,:,ii),sensorTot.imu.magnetometer_measures(index_imu,:),nas.sigma_mag,mag_NED); @@ -185,7 +185,7 @@ if length(t_nas) > 1 timestampPitotCorrection = t_nas; % [x_lin(ii,:),P_lin(4:6,4:6,ii),~] = correctionPitot_pressures(x_lin(ii,:),P_lin(4:6,4:6,ii),sensorTot.pitot.total_pressure(index_pit,:),sensorTot.pitot.static_pressure(index_pit,:),nas.sigma_pitot,xq(ii,1:4),nas.Mach_max); % [x_lin(ii,:),P_lin(4:6,4:6,ii),~] = correctionPitot_airspeed(x_lin(ii,:),P_lin(4:6,4:6,ii),sensorTot.pitot.airspeed(index_pit,:),nas.sigma_pitot2,settings.OMEGA); - [x_lin(ii,:),P_lin(:,:,ii),~] = correctionPitot_pressureRatio(x_lin(ii,:), P_lin(1:6,1:6),sensorTot.pitot.dynamic_pressure(index_pit,:),sensorTot.pitot.static_pressure(index_pit,:),nas.sigma_pitot2,settings.OMEGA); + [x_lin(ii,:),P_lin(:,:,ii),~] = correctionPitot_pressureRatio(x_lin(ii,:), P_lin(1:6,1:6),sensorTot.pitot.dynamic_pressure(index_pit,:),sensorTot.pitot.static_pressure(index_pit,:),nas.sigma_pitot2,environment.omega); end end sensorTot.pitot.lastindex = index_pit; @@ -197,7 +197,7 @@ if length(t_nas) > 1 P_c(7:12,7:12,ii) = P_q(:,:,ii); if nas.flag_apo == false - if -x(ii,6) < nas.v_thr && -x(ii,3) > 100 + settings.z0 + if -x(ii,6) < nas.v_thr && -x(ii,3) > 100 + environment.z0 nas.counter = nas.counter + 1; else nas.counter = 0; @@ -214,7 +214,7 @@ if length(t_nas) > 1 sensorData.nas.P = P_c; sensorData.nas.time = t_nas; sensorData.nas.timestampPitotCorrection = timestampPitotCorrection; - if abs(sensorData.nas.states(1,3)) >nas.stopPitotAltitude+ settings.z0 + if abs(sensorData.nas.states(1,3)) >nas.stopPitotAltitude+ environment.z0 nas.flagStopPitotCorrection = true; end sensorTot.nas.states(sensorTot.nas.n_old:sensorTot.nas.n_old + size(sensorData.nas.states(:,1),1)-2,:) = sensorData.nas.states(2:end,:); % NAS output diff --git a/commonFunctions/kalman/run_WES.m b/commonFunctions/kalman/run_WES.m index ff87c0fc291869996ac1679a69a4a88dabdd7a3c..aca118c0677c2e0e0519a60651e39ca90df391c3 100644 --- a/commonFunctions/kalman/run_WES.m +++ b/commonFunctions/kalman/run_WES.m @@ -2,30 +2,30 @@ function [WES] = run_WES(vel_est,WES) %% WES acquisition -if WES.N < WES.N_cal - - % here there was a if t> N*period, which I think is useless because now - % it goes at a discrete frequency set outside of the function - WES.N = WES.N + 1; - - WES.A(WES.N,:) = vel_est; - WES.b(WES.N,1) = norm(vel_est)^2; - - % update mean - WES.V_mean = (WES.V_mean.*(WES.N-1)+vel_est)./WES.N; - WES.V2_mean = (WES.V2_mean.*(WES.N-1)+norm(vel_est)^2)./WES.N; - - - %% calibration - if WES.N == WES.N_cal - WES.A = WES.A - mean(WES.A,1); - WES.b = 0.5*(WES.b - mean(WES.b)); - WES.wind_est = (WES.A'*WES.A)\(WES.A'*WES.b); -% WES.V_h_i = norm(vel_est-WES.wind_est); - end - -else - if WES.state == 1 % Guidance NOT running, only calibrations +% if WES.N < WES.N_cal +% +% % here there was a if t> N*period, which I think is useless because now +% % it goes at a discrete frequency set outside of the function +% WES.N = WES.N + 1; +% +% WES.A(WES.N,:) = vel_est; +% WES.b(WES.N,1) = norm(vel_est)^2; +% +% % update mean +% WES.V_mean = (WES.V_mean.*(WES.N-1)+vel_est)./WES.N; +% WES.V2_mean = (WES.V2_mean.*(WES.N-1)+norm(vel_est)^2)./WES.N; +% +% +% %% calibration +% if WES.N == WES.N_cal +% WES.A = WES.A - mean(WES.A,1); +% WES.b = 0.5*(WES.b - mean(WES.b)); +% WES.wind_est = (WES.A'*WES.A)\(WES.A'*WES.b); +% % WES.V_h_i = norm(vel_est-WES.wind_est); +% end +% +% else +% if WES.state == 1 % Guidance NOT running, only calibrations % ------ Recursive Least Squares ------ % New number of samples WES.N = WES.N + 1; @@ -37,17 +37,17 @@ else % RLS phi = vel_est-WES.V_mean; y = 0.5*(norm(vel_est)^2 - WES.V2_mean); - Ep = y - phi*WES.wind_est; + Ep = y - phi*WES.wind_est'; beta = WES.fFactor + phi*WES.Funv*phi'; WES.Funv = (1/WES.fFactor)*(WES.Funv - (1/beta)*WES.Funv*(phi'*phi)*WES.Funv); % check consistency of the ./ in 1./ beta K = WES.Funv*phi'; WES.Funv = 0.5*(WES.Funv + WES.Funv'); - WES.wind_est = WES.wind_est + K*Ep; + WES.wind_est = WES.wind_est + K'*Ep; % WES.V_h_i = norm(WES.V_mean-wind_est); % update and save for next iteration % else % WES = WES; - end + % end end diff --git a/commonFunctions/miscellaneous/extension_From_Angle.m b/commonFunctions/miscellaneous/extension_From_Angle.m index a359c0f13b3022335208d94686e73e2e8c4f6ae3..1532b36c3739962f11ee661d891d91e0805ade4b 100644 --- a/commonFunctions/miscellaneous/extension_From_Angle.m +++ b/commonFunctions/miscellaneous/extension_From_Angle.m @@ -1,4 +1,4 @@ -function [x,varargout] = extension_From_Angle(alpha, settings) +function [x,varargout] = extension_From_Angle(alpha, settings, mission) % HELP % alpha must be already in radiants % @@ -6,14 +6,14 @@ function [x,varargout] = extension_From_Angle(alpha, settings) % alpha: servo angle reference % settings: a struct containing everything basically -switch settings.mission +switch mission.name - case 'Lyra_Roccaraso_September_2024' + case '2024_Lyra_Roccaraso_September' x = settings.arb.extPol(1)*alpha.^4 + settings.arb.extPol(2)*alpha.^3+settings.arb.extPol(3)*alpha.^2 + settings.arb.extPol(4).*alpha; deltaS = alpha * settings.arb.surfPol; varargout{1} = deltaS; - case 'Lyra_Portugal_October_2024' % to be modified when updated data are available + case '2024_Lyra_Portugal_October' % to be modified when updated data are available x = settings.arb.extPol(1)*alpha.^4 + settings.arb.extPol(2)*alpha.^3+settings.arb.extPol(3)*alpha.^2 + settings.arb.extPol(4).*alpha; deltaS = alpha * settings.arb.surfPol; diff --git a/commonFunctions/miscellaneous/generateSensorMeasurements.m b/commonFunctions/miscellaneous/generateSensorMeasurements.m index 0f71d191920d564353ff0204ca6071fb071f67b5..5caaebe00bee0f76dfcd04ea5ef864d1cc14a9ca 100644 --- a/commonFunctions/miscellaneous/generateSensorMeasurements.m +++ b/commonFunctions/miscellaneous/generateSensorMeasurements.m @@ -1,4 +1,6 @@ -function [sensorData] = generateSensorMeasurements(magneticFieldApprox, Y, Tf, wind, sensorData,sensorTot, settings, engineT0, currentState, availableStates) +function [sensorData] = generateSensorMeasurements(magneticFieldApprox, Y, Tf,... + wind, sensorData,sensorTot, settings, engineT0, currentState, availableStates,... + environment, mission, rocket) %{ @@ -52,7 +54,7 @@ sensorData.magnetometer.time = (sensorTot.imu.time(end):1/freq.magnetometerFrequ sensorData.magnetometer.measures = zeros(size(sensorData.magnetometer.time,1),3)*100; sensorData.magnetometer.measures(1,:) = sensorTot.imu.magnetometer_measures(end,:)*100; if length(sensorData.magnetometer.time)>1 - z = -interp1(Tf,Y(:,3),sensorData.magnetometer.time(2:end)) + settings.z0; + z = -interp1(Tf,Y(:,3),sensorData.magnetometer.time(2:end)) + environment.z0; Q = interp1(Tf,Y(:,10:13),sensorData.magnetometer.time(2:end)); magnFieldInertial = magneticFieldApprox(z); sensorData.magnetometer.measures(2:end,:) = quatrotate(Q, magnFieldInertial); @@ -72,7 +74,7 @@ sensorData.gps.velocityMeasures(1,:) = sensorTot.gps.velocity_measures(end,:); if length(sensorData.gps.time)>1 TfGPS = round(Tf*1e4)/1e4; % as the GPS is usually very slow, this helps to stabilize truncation error sensorData.gps.positionMeasures(2:end, :) = ... - interp1(TfGPS,[Y(:,1:2),-Y(:,3)+settings.z0],sensorData.gps.time(2:end)); + interp1(TfGPS,[Y(:,1:2),-Y(:,3)+environment.z0],sensorData.gps.time(2:end)); vel = interp1(TfGPS,Y(:,4:6),sensorData.gps.time(2:end)); quat = interp1(TfGPS,Y(:,10:13),sensorData.gps.time(2:end)); sensorData.gps.velocityMeasures(2:end, :) = quatrotate(quatconj(quat),vel); @@ -90,9 +92,9 @@ for i_baro = 1:length(sensorData.barometer_sens) sensorData.barometer_sens{i_baro}.measures = zeros(size(sensorData.barometer_sens{i_baro}.time,1),1); sensorData.barometer_sens{i_baro}.z = zeros(size(sensorData.barometer_sens{i_baro}.time,1),1); % this initialization is needed in acquisition_system, do not delete it unless you know what you are doing. Needed in order to have arrays of the same size. Otherwise, if the new array is shorter (e.g. 2 instead of 3 elements) the last element is brought in the next sensorTot saving step and breaks the simulation sensorData.barometer_sens{i_baro}.measures(1) = sensorTot.barometer_sens{i_baro}.pressure_measures(end); - [sensorData.barometer_sens{i_baro}.temperature,~,~,~] = atmosisa(-interp1(Tf,Y(:,3),sensorData.barometer_sens{i_baro}.time) + settings.z0); + [sensorData.barometer_sens{i_baro}.temperature,~,~,~] = atmosisa(-interp1(Tf,Y(:,3),sensorData.barometer_sens{i_baro}.time) + environment.z0); if length(sensorData.barometer_sens{i_baro}.time)>1 - z = -interp1(Tf,Y(:,3),sensorData.barometer_sens{i_baro}.time(2:end)) + settings.z0; + z = -interp1(Tf,Y(:,3),sensorData.barometer_sens{i_baro}.time(2:end)) + environment.z0; [~, ~, P, ~] = atmosisa(z); sensorData.barometer_sens{i_baro}.measures(2:end) = P; end @@ -119,7 +121,7 @@ if isfield(freq, 'pitotFrequency') sensorData.pitot.temperature(1) = sensorTot.pitot.temperature(end); if length(sensorData.pitot.time)>1 TfPitot = round(Tf*1e4)/1e4; - z = -interp1(TfPitot,Y(:,3),sensorData.pitot.time(2:end)) + settings.z0; + z = -interp1(TfPitot,Y(:,3),sensorData.pitot.time(2:end)) + environment.z0; v = interp1(TfPitot,Y(:,4),sensorData.pitot.time(2:end)); Q = interp1(TfPitot,Y(:,10:13),sensorData.pitot.time(2:end)); wind_body = quatrotate(Q,wind); @@ -137,12 +139,12 @@ if isfield(freq, 'pitotFrequency') end %% chamber pressure sensor -if (contains(settings.mission,'_2023') || contains(settings.mission,'_2024')) && currentState ~= availableStates.on_ground +if (contains(mission.name,'2023') || contains(mission.name,'2024')) && currentState ~= availableStates.on_ground sensorData.chamberPressure.time = (sensorTot.comb_chamber.time(end):1/freq.chamberPressureFrequency:Tf(end))'; sensorData.chamberPressure.measures = zeros(size(sensorData.chamberPressure.time,1),1); sensorData.chamberPressure.measures(1) = sensorTot.comb_chamber.measures(end); if length(sensorData.chamberPressure.time) >1 - sensorData.chamberPressure.measures(2:end)= interp1(settings.motor.expTime, settings.motor.expThrust,sensorData.chamberPressure.time(2:end)-engineT0)/settings.motor.K; + sensorData.chamberPressure.measures(2:end)= interp1(rocket.motor.time, rocket.motor.thrust,sensorData.chamberPressure.time(2:end)-engineT0)/settings.motor.K; end else sensorData.chamberPressure.time = (sensorTot.comb_chamber.time(end):1/freq.chamberPressureFrequency:Tf(end))'; diff --git a/commonFunctions/miscellaneous/manageSignalFrequencies.m b/commonFunctions/miscellaneous/manageSignalFrequencies.m index 408425ce1977df0f61499ab20d0a98794f4e5a95..884fd316f32e3a9e2bce5a49f3d8b0da8e7715ae 100644 --- a/commonFunctions/miscellaneous/manageSignalFrequencies.m +++ b/commonFunctions/miscellaneous/manageSignalFrequencies.m @@ -213,13 +213,13 @@ if freq.magnetometerFrequency > freq.controlFrequency Q(i, :) = Y(iTimeMagnetometer == T, 10:13); end end - magnFieldInertial = magneticFieldApprox(z + settings.z0)'; + magnFieldInertial = magneticFieldApprox(z + environment.z0)'; sensorData.magnetometer.measures = quatrotate(Q, magnFieldInertial); elseif freq.magnetometerFrequency == freq.controlFrequency z = -Y(end, 3); Q = Y(end, 10:13); - magnFieldInertial = magneticFieldApprox(z + settings.z0)'; + magnFieldInertial = magneticFieldApprox(z + environment.z0)'; sensorData.magnetometer.measures = quatrotate(Q, magnFieldInertial); sensorData.magnetometer.time = T(end); @@ -236,14 +236,14 @@ else Yinterp = m *(iTimeMagnetometer-T0)+Y0; z = - Yinterp(1); Q = Yinterp(2:end); - magnFieldInertial = magneticFieldApprox(z + settings.z0)'; + magnFieldInertial = magneticFieldApprox(z + environment.z0)'; sensorData.magnetometer.measures = quatrotate(Q, magnFieldInertial); sensorData.magnetometer.t0 = iTimeMagnetometer; elseif abs(T(i) - sensorData.magnetometer.t0 - 1/freq.magnetometerFrequency) <1e-6 % for stability purposes this is not an == iTimeMagnetometer = sensorData.magnetometer.t0 + 1/freq.magnetometerFrequency; z = - Y(i, 3); Q = Y(i, 10:13); - magnFieldInertial = magneticFieldApprox(z + settings.z0)'; + magnFieldInertial = magneticFieldApprox(z + environment.z0)'; sensorData.magnetometer.measures = quatrotate(Q, magnFieldInertial); sensorData.magnetometer.t0 = iTimeMagnetometer; end @@ -408,7 +408,7 @@ for i_baro = 1:length(sensorData.barometer_sens) z(i) = -Y(abs(iTimeBarometer - T)<1e-6, 3); end sensorData.barometer_sens{i_baro}.z(i) = z(i); - [Temp, ~, P, ~] = atmosisa(sensorData.barometer_sens{i_baro}.z(i)+settings.z0); + [Temp, ~, P, ~] = atmosisa(sensorData.barometer_sens{i_baro}.z(i)+environment.z0); sensorData.barometer_sens{i_baro}.measures(i) = P; sensorData.barometer_sens{i_baro}.temperature(i) = Temp; @@ -419,7 +419,7 @@ for i_baro = 1:length(sensorData.barometer_sens) z = -Y(end, 3); sensorData.barometer_sens{i_baro}.z = z; sensorData.barometer_sens{i_baro}.t0 = T(end); - [Temp, ~, P, ~] = atmosisa(sensorData.barometer_sens{i_baro}.z+settings.z0); + [Temp, ~, P, ~] = atmosisa(sensorData.barometer_sens{i_baro}.z+environment.z0); sensorData.barometer_sens{i_baro}.measures = P; sensorData.barometer_sens{i_baro}.temperature = Temp; @@ -437,7 +437,7 @@ for i_baro = 1:length(sensorData.barometer_sens) sensorData.barometer_sens{i_baro}.z = z; sensorData.barometer_sens{i_baro}.t0 = iTimeBarometer; sensorData.barometer_sens{i_baro}.time = iTimeBarometer; - [Temp, ~, P, ~] = atmosisa(sensorData.barometer_sens{i_baro}.z+settings.z0); + [Temp, ~, P, ~] = atmosisa(sensorData.barometer_sens{i_baro}.z+environment.z0); sensorData.barometer_sens{i_baro}.measures = P; sensorData.barometer_sens{i_baro}.temperature = Temp; @@ -447,7 +447,7 @@ for i_baro = 1:length(sensorData.barometer_sens) sensorData.barometer_sens{i_baro}.t0 = iTimeBarometer; sensorData.barometer_sens{i_baro}.time = iTimeBarometer; sensorData.barometer_sens{i_baro}.z = z; - [Temp, ~, P, ~] = atmosisa(sensorData.barometer_sens{i_baro}.z+settings.z0); + [Temp, ~, P, ~] = atmosisa(sensorData.barometer_sens{i_baro}.z+environment.z0); sensorData.barometer_sens{i_baro}.measures = P; sensorData.barometer_sens{i_baro}.temperature = Temp; end @@ -495,7 +495,7 @@ if isfield(freq, 'pitotFrequency') Y0 = Y(index0, 10:13); m = (Y1 - Y0)./(T1 - T0); Q(i,:) = m * (iTimePitot-T0)+Y0; - [Temp, a, P, ~] = atmosisa(z_pit(i) + settings.z0); + [Temp, a, P, ~] = atmosisa(z_pit(i) + environment.z0); wind_ned = [uw, vw, ww]; wind_body = quatrotate(Q(i,:),wind_ned); v = (vx(i) + wind_body(1))'; @@ -506,7 +506,7 @@ if isfield(freq, 'pitotFrequency') vx(i) = Y(abs(iTimePitot - T)<1e-6, 4); z_pit(i) = -Y(abs(iTimePitot - T)<1e-6, 3); Q(i,:) = [Y(abs(iTimePitot - T)<1e-6, 10:13)]; - [Temp, a, P, ~] = atmosisa(z_pit(i) + settings.z0); + [Temp, a, P, ~] = atmosisa(z_pit(i) + environment.z0); wind_ned = [uw, vw, ww]; wind_body = quatrotate(Q(i,:),wind_ned); v = (vx(i) + wind_body(1))'; @@ -522,7 +522,7 @@ if isfield(freq, 'pitotFrequency') vx = Y(end, 4); z_pit = -Y(end, 3); Q = Y(end, 10:13); - [Temp, a, P, ~] = atmosisa(z_pit + settings.z0); + [Temp, a, P, ~] = atmosisa(z_pit + environment.z0); wind_ned = [uw, vw, ww]; wind_body = quatrotate(Q,wind_ned); v = (vx + wind_body(1))'; @@ -552,7 +552,7 @@ if isfield(freq, 'pitotFrequency') m = (Y1 - Y0)./(T1 - T0); Q = m * (iTimePitot-T0)+Y0; sensorData.pitot.t0 = iTimePitot; - [Temp, a, P, ~] = atmosisa(z_pit + settings.z0); + [Temp, a, P, ~] = atmosisa(z_pit + environment.z0); wind_ned = [uw, vw, ww]; wind_body = quatrotate(Q,wind_ned); v = (vx + wind_body(1))'; @@ -566,7 +566,7 @@ if isfield(freq, 'pitotFrequency') sensorData.pitot.t0 = iTimePitot; vx = Y(i, 4); Q = Y(i,10:13); - [Temp, a, P, ~] = atmosisa(z_pit + settings.z0); + [Temp, a, P, ~] = atmosisa(z_pit + environment.z0); wind_ned = [uw, vw, ww]; wind_body = quatrotate(Q,wind_ned); v = (vx + wind_body(1))'; @@ -583,7 +583,7 @@ if isfield(freq, 'pitotFrequency') end %% chamber pressure sensor -if contains(settings.mission,'_2023') +if contains(mission.name,'_2023') if freq.chamberPressureFrequency > freq.controlFrequency dt = 1/freq.chamberPressureFrequency; sensorData.chamberPressure.time = sensorData.chamberPressure.t0+dt:dt:T(end); @@ -592,27 +592,27 @@ if contains(settings.mission,'_2023') for i = 1:N iTimechamberPressure = sensorData.chamberPressure.time(i); - Thrust(i) = interp1(settings.motor.expTime, settings.motor.expThrust,iTimechamberPressure ); + Thrust(i) = interp1(rocket.motor.time, rocket.motor.thrust,iTimechamberPressure ); end sensorData.chamberPressure.measures = Thrust/settings.motor.K; elseif freq.chamberPressureFrequency == freq.controlFrequency sensorData.chamberPressure.time = T(end); - Thrust = interp1(settings.motor.expTime, settings.motor.expThrust,T(end)); + Thrust = interp1(rocket.motor.time, rocket.motor.thrust,T(end)); sensorData.chamberPressure.measures = Thrust/settings.motor.K; else for i = 1:length(T) if T(i) - sensorData.chamberPressure.t0 > 1/freq.chamberPressureFrequency iTimechamberPressure = sensorData.chamberPressure.t0 + 1/freq.chamberPressureFrequency; - Thrust(i) = interp1(settings.motor.expTime, settings.motor.expThrust,iTimechamberPressure ); + Thrust(i) = interp1(rocket.motor.time, rocket.motor.thrust,iTimechamberPressure ); sensorData.chamberPressure.measures(i) = Thrust(i)/settings.motor.K; sensorData.chamberPressure.t0 = iTimechamberPressure ; sensorData.chamberPressure.time = iTimechamberPressure; elseif T(i) - sensorData.chamberPressure.t0 == 1/freq.chamberPressureFrequency iTimechamberPressure = sensorData.chamberPressure.t0 + 1/freq.chamberPressureFrequency; - Thrust(i) = interp1(settings.motor.expTime, settings.motor.expThrust,iTimechamberPressure ); + Thrust(i) = interp1(rocket.motor.time, rocket.motor.thrust,iTimechamberPressure ); sensorData.chamberPressure.measures(i) = Thrust(i)/settings.motor.K; sensorData.chamberPressure.t0 = iTimechamberPressure; sensorData.chamberPressure.time = iTimechamberPressure; diff --git a/commonFunctions/miscellaneous/settingsEngineCut.m b/commonFunctions/miscellaneous/settingsEngineCut.m index d7dcd90f87da42e0a469edd7096745799b6f51a4..79571b87758cbfba5210e61ff0e6de9467f10c23 100644 --- a/commonFunctions/miscellaneous/settingsEngineCut.m +++ b/commonFunctions/miscellaneous/settingsEngineCut.m @@ -1,4 +1,4 @@ -function settings = settingsEngineCut(settings, engineT0) +function [settings, rocket] = settingsEngineCut(settings, engineT0, rocket) %{ settingsEngineCut - This function computes specifc parameters at engine cut event @@ -23,39 +23,34 @@ function settings = settingsEngineCut(settings, engineT0) SPDX-License-Identifier: GPL-3.0-or-later %} - settings.timeEngineCut = settings.timeEngineCut - engineT0; - - if (settings.timeEngineCut) > 0 && ( settings.timeEngineCut <= (settings.tb - settings.tCO) ) + rocket.motor.cutoffTime = rocket.motor.cutoffTime - engineT0; + rocket.updateCutoff; + if (rocket.motor.cutoffTime) > 0 && ( rocket.motor.cutoffTime <= (rocket.motor.time(end) - rocket.motor.cutoffTransient) ) - tEC = settings.timeEngineCut; % controlled shutoff moment, 0.3 is the delay - tCO = settings.tCO; % cutoff transient duration + tEC = rocket.motor.cutoffTime; % controlled shutoff moment, 0.3 is the delay + tCO = rocket.motor.cutoffTransient; % cutoff transient duration - for i = 1: length(settings.motor.expTime) - if settings.motor.expTime(i) >= settings.timeEngineCut + for i = 1: length(rocket.motor.time) + if rocket.motor.time(i) >= rocket.motor.cutoffTime - settings.motor.expThrust(i) = settings.motor.expThrust(i) * (1 - (settings.motor.expTime(i) - tEC)/tCO ); + rocket.motor.thrust(i) = rocket.motor.thrust(i) * (1 - (rocket.motor.time(i) - tEC)/tCO ); - if settings.motor.expTime(i) > tEC + tCO || settings.motor.expThrust(i) < 0 - settings.motor.expThrust(i) = 0; + if rocket.motor.time(i) > tEC + tCO || rocket.motor.thrust(i) < 0 + rocket.motor.thrust(i) = 0; end end end - settings.timeEngineCut = settings.timeEngineCut + settings.tCO; - - settings.expMengineCut = interpLinear(settings.motor.expTime, settings.motor.expM, settings.timeEngineCut); - settings.IengineCut(1) = interpLinear(settings.motor.expTime, settings.I(1,:), settings.timeEngineCut); - settings.IengineCut(2) = interpLinear(settings.motor.expTime, settings.I(2,:), settings.timeEngineCut); - settings.IengineCut(3) = interpLinear(settings.motor.expTime, settings.I(3,:), settings.timeEngineCut); - - elseif settings.timeEngineCut >= (settings.tb - settings.tCO) + rocket.motor.cutoffTime = rocket.motor.cutoffTime + rocket.motor.cutoffTransient; + rocket.updateCutoff; + + elseif rocket.motor.cutoffTime >= (rocket.motor.time(end) - rocket.motor.cutoffTransient) - settings.timeEngineCut = inf; + rocket.motor.cutoffTime = rocket.motor.time(end); - elseif settings.timeEngineCut <= 0 - error('settings.timeEngineCut must be grater than zero'); + elseif rocket.motor.cutoffTime <= 0 + error('rocket.motor.cutoffTime must be grater than zero'); end - settings.timeEngineCut = settings.timeEngineCut + engineT0; end \ No newline at end of file diff --git a/commonFunctions/odeFunctions/accelerationOnlyAscent.m b/commonFunctions/odeFunctions/accelerationOnlyAscent.m index 49e6b85711743bf0604dd39ad7aff93a50d9173d..2d2514dd640b43018790656a204536b9f7fdea97 100644 --- a/commonFunctions/odeFunctions/accelerationOnlyAscent.m +++ b/commonFunctions/odeFunctions/accelerationOnlyAscent.m @@ -52,7 +52,7 @@ if -z < 0 % z is directed as the gravity vector z = 0; end -h = -z + settings.z0; +h = -z + environment.z0; atmC = [9.80665, 1.4, 287.0531, 0.0065, 11000, 20000, ... 1.225, 101325, 288.15]; % atmosisa constants: @@ -82,7 +82,7 @@ S = settings.S; % [m^2] cross surface CoeffsE = settings.CoeffsE; % Empty Rocket Coefficients CoeffsF = settings.CoeffsF; % Full Rocket Coefficients g = 9.80655; % [N/kg] module of gravitational field at zero -tb = settings.tb; % [s] Burning Time +tb = rocket.motor.time(end); % [s] Burning Time OMEGA = settings.OMEGA; % [rad] Elevation Angle in the launch pad %% TIME-DEPENDENTS VARIABLES diff --git a/commonFunctions/odeFunctions/accelerometerAscent.m b/commonFunctions/odeFunctions/accelerometerAscent.m index 6eeb6e842fb77030e94dfd5f13314b4bb572c078..5329e109a1a2f6d821ed33868bef6d873dcaa195 100644 --- a/commonFunctions/odeFunctions/accelerometerAscent.m +++ b/commonFunctions/odeFunctions/accelerometerAscent.m @@ -33,7 +33,7 @@ ap = Y(17); S = settings.S; % [m^2] cross surface C = settings.C; % [m] caliber g = settings.g0/(1 + (-z*1e-3/6371))^2; % [N/kg] module of gravitational field -tb = settings.tb; % [s] Burning Time +tb = rocket.motor.time(end); % [s] Burning Time local = settings.Local; % vector containing inputs for atmosphereData @@ -48,14 +48,14 @@ local = settings.Local; % vector containing inputs for atmospher %% INERTIAS if settings.HREmot if t < tb - if t < settings.timeEngineCut - Ixx = interpLinear(settings.motor.expTime, settings.I(1,:), t); - Iyy = interpLinear(settings.motor.expTime, settings.I(2,:), t); - Izz = interpLinear(settings.motor.expTime, settings.I(3,:), t); - - Ixxdot = interpLinear(settings.motor.expTime, settings.Idot(1,:), t); - Iyydot = interpLinear(settings.motor.expTime, settings.Idot(2,:), t); - Izzdot = interpLinear(settings.motor.expTime, settings.Idot(3,:), t); + if t < rocket.motor.cutoffTime + Ixx = interpLinear(rocket.motor.time, settings.I(1,:), t); + Iyy = interpLinear(rocket.motor.time, settings.I(2,:), t); + Izz = interpLinear(rocket.motor.time, settings.I(3,:), t); + + Ixxdot = interpLinear(rocket.motor.time, settings.Idot(1,:), t); + Iyydot = interpLinear(rocket.motor.time, settings.Idot(2,:), t); + Izzdot = interpLinear(rocket.motor.time, settings.Idot(3,:), t); else I = settings.IengineCut; Idot = zeros(3, 1); @@ -63,7 +63,7 @@ if settings.HREmot Ixxdot = Idot(1); Iyydot = Idot(2); Izzdot = Idot(3); end else - if settings.timeEngineCut < tb + if rocket.motor.cutoffTime < tb I = settings.IengineCut; Ixx = I(1); Iyy = I(2); Izz = I(3); else @@ -104,7 +104,7 @@ if -z < 0 % z is directed as the gravity vector z = 0; end -h = -z + settings.z0; +h = -z + environment.z0; atmC = [9.80665, 1.4, 287.0531, 0.0065, 11000, 20000, ... 1.225, 101325, 288.15]; % atmosisa constants: @@ -134,10 +134,10 @@ M = V_norm/a; %% TIME-DEPENDENTS VARIABLES if t < tb if settings.HREmot - if t < settings.timeEngineCut - m = interpLinear(settings.motor.expTime, settings.mTotalTime, t); - T = interpLinear(settings.motor.expTime, settings.motor.expThrust, t); - Pe = interpLinear(settings.motor.expTime, settings.motor.Pe, t); + if t < rocket.motor.cutoffTime + m = interpLinear(rocket.motor.time, settings.mTotalTime, t); + T = interpLinear(rocket.motor.time, rocket.motor.thrust, t); + Pe = interpLinear(rocket.motor.time, settings.motor.Pe, t); T = T + settings.motor.Ae*(Pe - P); else m = settings.expMengineCut + settings.ms; @@ -145,16 +145,16 @@ if t < tb end else dI = 1/tb*([Ixxf Iyyf Izzf]' - [Ixxe Iyye Izze]'); - m = settings.ms + interpLinear(settings.motor.expTime, settings.motor.expM, t); + m = settings.ms + interpLinear(rocket.motor.time, settings.motor.expM, t); Ixxdot = -dI(1); Iyydot = -dI(2); Izzdot = -dI(3); - T = interpLinear(settings.motor.expTime, settings.motor.expThrust, t); + T = interpLinear(rocket.motor.time, rocket.motor.thrust, t); end else % for t >= tb the fligth condition is the empty one(no interpolation needed) if settings.HREmot - if settings.timeEngineCut < tb + if rocket.motor.cutoffTime < tb m = settings.ms + settings.expMengineCut; else m = settings.ms + settings.motor.expM(end); diff --git a/commonFunctions/odeFunctions/accelerometerDescent.m b/commonFunctions/odeFunctions/accelerometerDescent.m index 5753fd299937ef185367da095ac4a680c62e7c06..343eb3f001e91d10b83dd6d9c298016e5dbb9556 100644 --- a/commonFunctions/odeFunctions/accelerometerDescent.m +++ b/commonFunctions/odeFunctions/accelerometerDescent.m @@ -37,7 +37,7 @@ if -z < 0 z = 0; end -[~, ~, ~, rho] = atmosisa(-z+settings.z0); +[~, ~, ~, rho] = atmosisa(-z+environment.z0); %% WIND [~,ind_wind] = min(settings.wind.output_time-t); wind = settings.wind.output_body(:,ind_wind); diff --git a/commonFunctions/odeFunctions/ascentControl.m b/commonFunctions/odeFunctions/ascentControl.m index 708c92cbf205a4b3cf276bdda91a686fe195f04a..5aee11197c4011d7d535762255c64dafc65e5ac4 100644 --- a/commonFunctions/odeFunctions/ascentControl.m +++ b/commonFunctions/odeFunctions/ascentControl.m @@ -70,7 +70,7 @@ end S = settings.S; % [m^2] cross surface C = settings.C; % [m] caliber g = settings.g0/(1 + (-z*1e-3/6371))^2; % [N/kg] module of gravitational field -tb = settings.tb; % [s] Burning Time +tb = rocket.motor.time(end); % [s] Burning Time local = settings.Local; % vector containing inputs for atmosphereData OMEGA = settings.OMEGA; @@ -84,15 +84,15 @@ end %% INERTIAS if t-engineT0 < tb - if t-engineT0 < settings.timeEngineCut - I = interpLinear(settings.motor.expTime, settings.I, t-engineT0); - Idot = interpLinear(settings.motor.expTime, settings.Idot, t-engineT0); + if t-engineT0 < rocket.motor.cutoffTime + I = interpLinear(rocket.motor.time, settings.I, t-engineT0); + Idot = interpLinear(rocket.motor.time, settings.Idot, t-engineT0); else I = settings.IengineCut; Idot = zeros(3, 1); end else - if settings.timeEngineCut < tb + if rocket.motor.cutoffTime < tb I = settings.IengineCut; else I = settings.I(:, end); @@ -155,7 +155,7 @@ if -z < 0 % z is directed as the gravity vector z = 0; end -absoluteAltitude = -z + settings.z0; +absoluteAltitude = -z + environment.z0; [~, a, P, rho] = atmosphereData(absoluteAltitude, g, local); M = V_norm/a; @@ -164,10 +164,10 @@ M_value = M; %% TIME-DEPENDENTS VARIABLES if t-engineT0 < tb - if t < settings.timeEngineCut - m = interpLinear(settings.motor.expTime, settings.mTotalTime, t-engineT0); - T = interpLinear(settings.motor.expTime, settings.motor.expThrust, t-engineT0); - Pe = interpLinear(settings.motor.expTime, settings.motor.Pe, t-engineT0); + if t < rocket.motor.cutoffTime + m = interpLinear(rocket.motor.time, settings.mTotalTime, t-engineT0); + T = interpLinear(rocket.motor.time, rocket.motor.thrust, t-engineT0); + Pe = interpLinear(rocket.motor.time, settings.motor.Pe, t-engineT0); T = T + settings.motor.Ae*(Pe - P); else m = settings.expMengineCut + settings.ms; @@ -176,7 +176,7 @@ if t-engineT0 < tb else % for t >= tb the fligth condition is the empty one(no interpolation needed) - if settings.timeEngineCut < tb + if rocket.motor.cutoffTime < tb m = settings.ms + settings.expMengineCut; else m = settings.ms + settings.motor.expM(end); @@ -201,7 +201,7 @@ beta_value = beta; %% CHOSING THE EMPTY CONDITION VALUE % interpolation of the coefficients with the value in the nearest condition of the Coeffs matrix -if t-engineT0 >= settings.tControl && M <= settings.MachControl +if t-engineT0 >= settings.tControl && M <= rocket.airbrakes.maxMach c = settings.control; else c = 1; @@ -354,7 +354,7 @@ else if ~settings.identification - if (M_value < settings.MachControl) %|| ~settings.machControlActive + if (M_value < rocket.airbrakes.maxMach) %|| ~settings.machControlActive % set velocity of servo (air brakes) if length(ap_ref_vec)==2 % for the recallOdeFunction if t < t_change_ref diff --git a/commonFunctions/odeFunctions/descentParachute.m b/commonFunctions/odeFunctions/descentParachute.m deleted file mode 100644 index eaf3fe4c7d4fb400e2fb3a275be16d4301df650d..0000000000000000000000000000000000000000 --- a/commonFunctions/odeFunctions/descentParachute.m +++ /dev/null @@ -1,218 +0,0 @@ -function [dY,parout] = descentParachute(t, Y, settings, uw, vw, ww, para, Q ,uncert) -%{ - -descentParachute - ode function of the 3DOF Rigid Rocket-Paraachute Model - -INPUTS: - - t, integration time; - - Y, state vector, [ x y z | u v w ]: - - * (x y z), NED{north, east, down} horizontal frame; - * (u v w), horizontal frame velocities. - - - settings, rocket data structure; - - uw, wind component along x; - - vw, wind component along y; - - ww, wind component along z; - - uncert, wind uncertanties; - - Hour, hour of the day of the needed simulation; - - Day, day of the month of the needed simulation; - -OUTPUTS: - - dY, state derivatives; - -Author: Ruben Di Battista -Skyward Experimental Rocketry | CRD Dept | crd@skywarder.eu -email: ruben.dibattista@skywarder.eu -April 2014; Last revision: 31.XII.2014 - -Author: Francesco Colombi -Skyward Experimental Rocketry | CRD Dept | crd@skywarder.eu -email: francesco.colombi@skywarder.eu -Release date: 16/04/2016 - -Author: Adriano Filippo Inno -Skyward Experimental Rocketry | AFD Dept | crd@skywarder.eu -email: adriano.filippo.inno@skywarder.eu -Release date: 13/01/2018 - -%} - -% recalling the state -% x = Y(1); -% y = Y(2); -z = Y(3); -u = Y(4); -v = Y(5); -w = Y(6); - - -local = settings.Local; -%% CONSTANTS -S = settings.para(para).S; % [m^2] Surface -CD = settings.para(para).CD; % [/] Parachute Drag Coefficient -CL = settings.para(para).CL; % [/] Parachute Lift Coefficient -if para == 1 - pmass = 0 ; % [kg] detached mass -else - pmass = sum(settings.para(1:para-1).mass) + settings.mnc; -end - - % [N/kg] magnitude of the gravitational field at zero - -m = settings.ms - pmass; % [kg] descend mass -g = settings.g0/(1 + (-z*1e-3/6371))^2; % [N/kg] module of gravitational field - -%% ADDING WIND (supposed to be added in NED axes); - -% if settings.wind.model -% -% if settings.stoch.N > 1 -% [uw, vw, ww] = windMatlabGenerator(settings, z, t, Hour, Day); -% else -% [uw, vw, ww] = windMatlabGenerator(settings, z, t); -% end -% -% elseif settings.wind.input -% [uw, vw, ww] = windInputGenerator(settings, z, uncert); -% -% elseif settings.wind.variable -% [uw, vw, ww] = windVariableGenerator(z, settings.stoch); -% end - -switch settings.windModel - - case "atmospherical" - [uw, vw, ww] = windMatlabGenerator(settings, z, t); - - case "multiplicative" - uncert = settings.wind.inputUncertainty; - [uw, vw, ww] = windInputGenerator(settings, z, uncert); - - case "constant" - uw = settings.constWind(1); vw = settings.constWind(2); ww = settings.constWind(3); -end - - -wind =[uw; vw; ww]; % body -Vels = [u; v; w]; - -% Relative velocities (plus wind); -ur = u - wind(1); -vr = v - wind(2); -wr = w - wind(3); - -V_norm = norm([ur vr wr]); - - -%% ATMOSPHERE DATA -if -z < 0 % z is directed as the gravity vector - z = 0; -end - -absoluteAltitude = -z + settings.z0; -[~, ~, P, rho] = atmosphereData(absoluteAltitude, g, local); - -%% REFERENCE FRAME -% The parachutes are approximated as rectangular surfaces with the normal -% vector perpendicular to the relative velocity - -t_vect = [ur vr wr]; % Tangenzial vector -h_vect = [vr -ur 0]; % horizontal vector - -if all(abs(h_vect) < 1e-8) - h_vect = [vw -uw 0]; -end - -n_vect = cross(t_vect, h_vect); % Normal vector - -if norm(t_vect) < 1e-8 - t_vers = [0 0 0]; -else - t_vers = t_vect/norm(t_vect); % Tangenzial versor -end - -if norm(n_vect) < 1e-8 - n_vers = [0 0 0]; -else - n_vers = n_vect/norm(n_vect); % normal versor -end - -if (n_vers(3) > 0) % If the normal vector is downward directed - n_vers = -n_vers; -end - - - -%% FORCES -D = -0.5*rho*V_norm^2*S*CD*t_vers'; % [N] Drag vector -L = 0.5*rho*V_norm^2*S*CL*n_vers'; % [N] Lift vector -Fg = m*g*[0 0 1]'; % [N] Gravitational Force vector -F = L + Fg + D; % [N] total forces vector -% F = Fg; -F_acc = F-Fg; % [N] accelerometer felt forces - -%% STATE DERIVATIVES -% velocity -acc = F/m; - - -%% FINAL DERIVATIVE STATE ASSEMBLING -dY(1:3) = Vels; % ned -dY(4:6) = acc; - - -dY = dY'; - -%% SAVING THE QUANTITIES FOR THE PLOTS - -if nargout == 2 -% parout.integration.t = t; -% -% parout.interp.M = M_value; -% parout.interp.alpha = alpha_value; -% parout.interp.beta = beta_value; -% parout.interp.alt = -z; - parout.interp.mass = m; -% - parout.wind.NED_wind = [uw, vw, ww]; - parout.wind.body_wind = wind; - -% -% parout.rotations.dcm = dcm; -% -% parout.velocities = Vels; -% -% parout.forces.AeroDyn_Forces = [X, Y, Z]; -% parout.forces.T = T; -% - parout.air.rho = rho; - parout.air.P = P; -% - parout.accelerations.body_acc = acc; -% parout.accelerations.ang_acc = [dp, dq, dr]; - parout.accelerometer.body_acc = quatrotate(Q,(F_acc/m)'); -% parout.coeff.CA = CA; -% parout.coeff.CYB = CYB; -% parout.coeff.CNA = CNA; -% parout.coeff.Cl = Cl; -% parout.coeff.Clp = Clp; -% %-------------------------------------------- -% %parout.coeff.Clb = Clb; -% %-------------------------------------------- -% parout.coeff.Cma = Cma; -% parout.coeff.Cmad = Cmad; -% parout.coeff.Cmq = Cmq; -% parout.coeff.Cnb = Cnb; -% parout.coeff.Cnr = Cnr; -% parout.coeff.Cnp = Cnp; -% parout.coeff.XCPlon = XCPlon; -% parout.coeff.XCPlat = XCPlat; -% -% sgn = sign(dot(cross(Myz, Fyz), [1 0 0])); -% XCPtot = (sgn * norm(Myz)/norm(Fyz)); -% err = 100*abs((acosd(dot(Fyz/norm(Fyz), Myz/norm(Myz))) - 90)/90); -% XCPtot = XCPtot - polyval(settings.regPoli, err); -% parout.coeff.XCPtot = XCPtot; - -end \ No newline at end of file diff --git a/commonFunctions/odeFunctions/descentParafoil.m b/commonFunctions/odeFunctions/descentParafoil_OLD.m similarity index 99% rename from commonFunctions/odeFunctions/descentParafoil.m rename to commonFunctions/odeFunctions/descentParafoil_OLD.m index e0dd70d3879c3c3a9aa02b14d1c005724b1123e5..2e984a7ab9b6d977f08850ad488d41002b4983f0 100644 --- a/commonFunctions/odeFunctions/descentParafoil.m +++ b/commonFunctions/odeFunctions/descentParafoil_OLD.m @@ -114,7 +114,7 @@ if -z < 0 % z is directed as the gravity vector z = 0; end -absoluteAltitude = -z + settings.z0; +absoluteAltitude = -z + environment.z0; [~, ~, ~, rho] = atmosphereData(absoluteAltitude, g, local); %% AERODYNAMICS ANGLES diff --git a/commonFunctions/sensors/acquisition_Sys.m b/commonFunctions/sensors/acquisition_Sys.m index c93982d766631227602cbece6945185497ad5d5c..4cec1c6a57107945d980be6a8b590a02c1b0dcfd 100644 --- a/commonFunctions/sensors/acquisition_Sys.m +++ b/commonFunctions/sensors/acquisition_Sys.m @@ -1,4 +1,4 @@ -function [sensorData, sensorTot] = acquisition_Sys(sensorData, sensorSettings, sensorTot, settings, t) +function [sensorData, sensorTot] = acquisition_Sys(sensorData, sensorSettings, sensorTot, t, mission) %{ Routine to simulate the data acquisition from the sensors, that use the class sensors in: "skyward-matlab-control-simulator\sensors" @@ -27,7 +27,7 @@ OUTPUT: %% Baro Acquisition loop -if ~contains(settings.mission, '_2023') +if ~contains(mission.name, '2023') sensorSettings.barometer2 = sensorSettings.barometer1; sensorSettings.barometer3 = sensorSettings.barometer1; end @@ -178,7 +178,7 @@ if isfield(sensorData.pitot,'time') end %% Chamber Pressure acquisition loop -if contains(settings.mission,'_2023') || contains(settings.mission,'_2024') +if contains(mission.name,'2023') || contains(mission.name,'2024') for ii=1:length(sensorData.chamberPressure.time) sensorData.chamberPressure.measures(ii) = sensorSettings.comb_chamber.sens(sensorData.chamberPressure.measures(ii)*1000,50); % 50 temperature in °C (random) sensorData.chamberPressure.measures(ii) = sensorData.chamberPressure.measures(ii)/1000; diff --git a/commonFunctions/wind/wind_matlab_generator.m b/commonFunctions/wind/wind_matlab_generator.m index 715312b3c2dd010c3afe47083d25c4e231dd5af6..f369db4de08e1ea66c83eb5513fc8428f4bbe6af 100644 --- a/commonFunctions/wind/wind_matlab_generator.m +++ b/commonFunctions/wind/wind_matlab_generator.m @@ -20,7 +20,7 @@ January 2016; Last revision: 17.I.2016 %} -h = -z + settings.z0; +h = -z + environment.z0; if h < 0 h = 0; end @@ -36,7 +36,7 @@ Seconds = Hour*3600; %% HORIZONTAL WIND -[uw,vw] = atmoshwm(settings.lat0,settings.lon0,h,'day',Day,... +[uw,vw] = atmoshwm(environment.lat0,environment.lon0,h,'day',Day,... 'seconds',Seconds+t,'model','quiet','version','14'); % NED reference ww = settings.wind.ww; diff --git a/data/Lynx_Portugal_October_2021/configLynx_Portugal_October_2021.m b/data/2021_Lynx_Portugal_October/configLynx_Portugal_October_2021.m similarity index 98% rename from data/Lynx_Portugal_October_2021/configLynx_Portugal_October_2021.m rename to data/2021_Lynx_Portugal_October/configLynx_Portugal_October_2021.m index 2263514446ade050a3545e048f2dec8770bf7b7f..7b353af96038783f560da2fefca56b63efca81fa 100644 --- a/data/Lynx_Portugal_October_2021/configLynx_Portugal_October_2021.m +++ b/data/2021_Lynx_Portugal_October/configLynx_Portugal_October_2021.m @@ -93,9 +93,9 @@ settings.nas.counter = 0; settings.nas.t_kalman = -1; % Apogee detection timestamp settings.nas.flag_apo = false; % True when the apogee is detected -settings.nas.lat0 = settings.lat0; -settings.nas.lon0 = settings.lon0; -settings.nas.z0 = -settings.z0; +settings.nas.lat0 = environment.lat0; +settings.nas.lon0 = environment.lon0; +settings.nas.z0 = -environment.z0; settings.nas.spheroid = wgs84Ellipsoid; % Process noise covariance matrix for the linear dynamics diff --git a/data/Lynx_Roccaraso_September_2021/configLynx_Roccaraso_September_2021.m b/data/2021_Lynx_Roccaraso_September/configLynx_Roccaraso_September_2021.m similarity index 97% rename from data/Lynx_Roccaraso_September_2021/configLynx_Roccaraso_September_2021.m rename to data/2021_Lynx_Roccaraso_September/configLynx_Roccaraso_September_2021.m index 01d714685af332a9286b4fa1a9bffd9218fdaed2..d2224e7d201e5fdded82a573e0f4941ae6db8bfa 100644 --- a/data/Lynx_Roccaraso_September_2021/configLynx_Roccaraso_September_2021.m +++ b/data/2021_Lynx_Roccaraso_September/configLynx_Roccaraso_September_2021.m @@ -51,9 +51,9 @@ settings.nas.counter = 0; settings.nas.t_kalman = -1; % Apogee detection timestamp settings.nas.flag_apo = false; % True when the apogee is detected -settings.nas.lat0 = settings.lat0; -settings.nas.lon0 = settings.lon0; -settings.nas.z0 = -settings.z0; +settings.nas.lat0 = environment.lat0; +settings.nas.lon0 = environment.lon0; +settings.nas.z0 = -environment.z0; settings.nas.spheroid = wgs84Ellipsoid; % Process noise covariance matrix for the linear dynamics diff --git a/data/Pyxis_Portugal_October_2022/configPyxis_Portugal_October_2022.m b/data/2022_Pyxis_Portugal_October/configPyxis_Portugal_October_2022.m similarity index 96% rename from data/Pyxis_Portugal_October_2022/configPyxis_Portugal_October_2022.m rename to data/2022_Pyxis_Portugal_October/configPyxis_Portugal_October_2022.m index 54062bb9bb56251d197a0302ff1e22877f72bee1..217b249d2f45bd726d5fc549d1d11540383a6aba 100644 --- a/data/Pyxis_Portugal_October_2022/configPyxis_Portugal_October_2022.m +++ b/data/2022_Pyxis_Portugal_October/configPyxis_Portugal_October_2022.m @@ -106,9 +106,9 @@ settings.nas.stopPitotAltitude = 500; settings.nas.t_nas = -1; % Apogee detection timestamp settings.nas.flag_apo = false; % True when the apogee is detected -settings.nas.lat0 = settings.lat0; -settings.nas.lon0 = settings.lon0; -settings.nas.z0 = -settings.z0; +settings.nas.lat0 = environment.lat0; +settings.nas.lon0 = environment.lon0; +settings.nas.z0 = -environment.z0; settings.nas.spheroid = wgs84Ellipsoid; % Process noise covariance matrix for the linear dynamics @@ -133,7 +133,7 @@ settings.ada.P0 = [ 0.1 0 0; % In 0 0.1 0; % state covariance matrix 0 0 0.1;]; [settings.ada.temp_ref, ~,... - settings.ada.p_ref, ~] = atmosisa(settings.z0); % Reference temperature in kelvin and pressure in Pa + settings.ada.p_ref, ~] = atmosisa(environment.z0); % Reference temperature in kelvin and pressure in Pa settings.ada.v0 = -10; % Vertical velocity initial condition settings.ada.a0 = -100; % Acceleration velocity initial condition diff --git a/data/Pyxis_Portugal_October_2022/initSensorsPyxis_Portugal_October_2022.m b/data/2022_Pyxis_Portugal_October/initSensorsPyxis_Portugal_October_2022.m similarity index 96% rename from data/Pyxis_Portugal_October_2022/initSensorsPyxis_Portugal_October_2022.m rename to data/2022_Pyxis_Portugal_October/initSensorsPyxis_Portugal_October_2022.m index 8dc13cd55f1ce016a572b982d3a9215a123c01cc..0f30c71c8f39459cbabbd8b868b6178d72945f9a 100644 --- a/data/Pyxis_Portugal_October_2022/initSensorsPyxis_Portugal_October_2022.m +++ b/data/2022_Pyxis_Portugal_October/initSensorsPyxis_Portugal_October_2022.m @@ -6,9 +6,9 @@ % Release date: 01/03/2021 %% extract info -lat0 = settings.lat0; -lon0 = settings.lon0; -z0 = settings.z0; +lat0 = environment.lat0; +lon0 = environment.lon0; +z0 = environment.z0; %% initial barometer sensor MS580301BA01 ep_p_0 = csvread('ep_p_0.csv'); @@ -136,15 +136,15 @@ sensorSettings.magnetometer2.transMatrix = diag([1 1 1]); % % total measurements -[~,~,P0,~] = atmosisa(settings.z0); +[~,~,P0,~] = atmosisa(environment.z0); sensorTot.barometer_sens{1}.pressure_measures = P0; sensorTot.barometer_sens{2}.pressure_measures = P0; sensorTot.barometer_sens{3}.pressure_measures = P0; -sensorTot.barometer_sens{1}.altitude = -settings.z0; -sensorTot.barometer_sens{2}.altitude = -settings.z0; -sensorTot.barometer_sens{3}.altitude = -settings.z0; +sensorTot.barometer_sens{1}.altitude = -environment.z0; +sensorTot.barometer_sens{2}.altitude = -environment.z0; +sensorTot.barometer_sens{3}.altitude = -environment.z0; sensorTot.barometer.pressure_measures = P0; -sensorTot.barometer.altitude = -settings.z0; +sensorTot.barometer.altitude = -environment.z0; sensorTot.comb_chamber.measures = 0; sensorTot.imu.accelerometer_measures = [0, 0, 0]; sensorTot.imu.gyro_measures = [0, 0, 0]; diff --git a/data/Pyxis_Roccaraso_September_2022/configPyxis_Roccaraso_September_2022.m b/data/2022_Pyxis_Roccaraso_September/configPyxis_Roccaraso_September_2022.m similarity index 96% rename from data/Pyxis_Roccaraso_September_2022/configPyxis_Roccaraso_September_2022.m rename to data/2022_Pyxis_Roccaraso_September/configPyxis_Roccaraso_September_2022.m index 4bb825e8d8d7e8de7429e229373684c1dba15f92..00a4ed9991c81d5fcfe3e590ecddd068e8cb5205 100644 --- a/data/Pyxis_Roccaraso_September_2022/configPyxis_Roccaraso_September_2022.m +++ b/data/2022_Pyxis_Roccaraso_September/configPyxis_Roccaraso_September_2022.m @@ -107,9 +107,9 @@ settings.nas.stopPitotAltitude = 500; settings.nas.t_nas = -1; % Apogee detection timestamp settings.nas.flag_apo = false; % True when the apogee is detected -settings.nas.lat0 = settings.lat0; -settings.nas.lon0 = settings.lon0; -settings.nas.z0 = -settings.z0; +settings.nas.lat0 = environment.lat0; +settings.nas.lon0 = environment.lon0; +settings.nas.z0 = -environment.z0; settings.nas.spheroid = wgs84Ellipsoid; % Process noise covariance matrix for the linear dynamics @@ -134,7 +134,7 @@ settings.ada.P0 = [ 0.1 0 0; % In 0 0.1 0; % state covariance matrix 0 0 0.1;]; [settings.ada.temp_ref, ~,... - settings.ada.p_ref, ~] = atmosisa(settings.z0); % Reference temperature in kelvin and pressure in Pa + settings.ada.p_ref, ~] = atmosisa(environment.z0); % Reference temperature in kelvin and pressure in Pa settings.ada.v0 = -10; % Vertical velocity initial condition settings.ada.a0 = -100; % Acceleration velocity initial condition diff --git a/data/Pyxis_Roccaraso_September_2022/initSensorsPyxis_Roccaraso_September_2022.m b/data/2022_Pyxis_Roccaraso_September/initSensorsPyxis_Roccaraso_September_2022.m similarity index 96% rename from data/Pyxis_Roccaraso_September_2022/initSensorsPyxis_Roccaraso_September_2022.m rename to data/2022_Pyxis_Roccaraso_September/initSensorsPyxis_Roccaraso_September_2022.m index fc527a3804fb49cef6a70a47643509edf1da70ee..74c96094c462f3f5c7ecfd676097a73793891967 100644 --- a/data/Pyxis_Roccaraso_September_2022/initSensorsPyxis_Roccaraso_September_2022.m +++ b/data/2022_Pyxis_Roccaraso_September/initSensorsPyxis_Roccaraso_September_2022.m @@ -6,9 +6,9 @@ % Release date: 01/03/2021 %% extract info -lat0 = settings.lat0; -lon0 = settings.lon0; -z0 = settings.z0; +lat0 = environment.lat0; +lon0 = environment.lon0; +z0 = environment.z0; %% initial barometer sensor MS580301BA01 ep_p_0 = csvread('ep_p_0.csv'); @@ -136,15 +136,15 @@ sensorSettings.magnetometer2.transMatrix = diag([1 1 1]); % % total measurements -[~,~,P0,~] = atmosisa(settings.z0); +[~,~,P0,~] = atmosisa(environment.z0); sensorTot.barometer_sens{1}.pressure_measures = P0; sensorTot.barometer_sens{2}.pressure_measures = P0; sensorTot.barometer_sens{3}.pressure_measures = P0; -sensorTot.barometer_sens{1}.altitude = -settings.z0; -sensorTot.barometer_sens{2}.altitude = -settings.z0; -sensorTot.barometer_sens{3}.altitude = -settings.z0; +sensorTot.barometer_sens{1}.altitude = -environment.z0; +sensorTot.barometer_sens{2}.altitude = -environment.z0; +sensorTot.barometer_sens{3}.altitude = -environment.z0; sensorTot.barometer.pressure_measures = P0; -sensorTot.barometer.altitude = -settings.z0; +sensorTot.barometer.altitude = -environment.z0; sensorTot.comb_chamber.measures = 0; sensorTot.imu.accelerometer_measures = [0, 0, 0]; sensorTot.imu.gyro_measures = [0, 0, 0]; diff --git a/data/Gemini_Portugal_October_2023/configGemini_Portugal_October_2023.m b/data/2023_Gemini_Portugal_October/configGemini_Portugal_October_2023.m similarity index 97% rename from data/Gemini_Portugal_October_2023/configGemini_Portugal_October_2023.m rename to data/2023_Gemini_Portugal_October/configGemini_Portugal_October_2023.m index 5bdb0058a4db512e756e762cb99ecba7265c21cf..2c8765878a7811aa3767bc39e4bce287e42aa348 100644 --- a/data/Gemini_Portugal_October_2023/configGemini_Portugal_October_2023.m +++ b/data/2023_Gemini_Portugal_October/configGemini_Portugal_October_2023.m @@ -110,9 +110,9 @@ settings.nas.stopPitotAltitude = 800; settings.nas.t_nas = -1; % Apogee detection timestamp settings.nas.flag_apo = false; % True when the apogee is detected -settings.nas.lat0 = settings.lat0; -settings.nas.lon0 = settings.lon0; -settings.nas.z0 = -settings.z0; +settings.nas.lat0 = environment.lat0; +settings.nas.lon0 = environment.lon0; +settings.nas.z0 = -environment.z0; settings.nas.spheroid = wgs84Ellipsoid; @@ -138,7 +138,7 @@ settings.ada.P0 = [ 0.1 0 0; % In 0 0.1 0; % state covariance matrix 0 0 0.1;]; [settings.ada.temp_ref, ~,... - settings.ada.p_ref, ~] = atmosisa(settings.z0); % Reference temperature in kelvin and pressure in Pa + settings.ada.p_ref, ~] = atmosisa(environment.z0); % Reference temperature in kelvin and pressure in Pa settings.ada.v0 = -10; % Vertical velocity initial condition settings.ada.a0 = -100; % Acceleration velocity initial condition diff --git a/data/Gemini_Portugal_October_2023/initSensorsGemini_Portugal_October_2023.m b/data/2023_Gemini_Portugal_October/initSensorsGemini_Portugal_October_2023.m similarity index 98% rename from data/Gemini_Portugal_October_2023/initSensorsGemini_Portugal_October_2023.m rename to data/2023_Gemini_Portugal_October/initSensorsGemini_Portugal_October_2023.m index b29a98782268b5737b55338bd94732cd91832e7e..869e472a35c9bf57ac8a03acf13984cc62c9cf68 100644 --- a/data/Gemini_Portugal_October_2023/initSensorsGemini_Portugal_October_2023.m +++ b/data/2023_Gemini_Portugal_October/initSensorsGemini_Portugal_October_2023.m @@ -136,9 +136,9 @@ sensorSettings.magnetometer.transMatrix = diag([1 1 1]); % a sensorSettings.GPS = GPS(); % lon, in degree lat in deree, alt in m sensorSettings.GPS.noiseVariance = [2e-9*ones(2,1);5;0.0011*ones(3,1)]; % [deg; deg; m; m/s; m/s; m/s]^2 sensorSettings.GPS.transMatrix = diag([1 1 1]); % axis transformation -sensorSettings.lat0 = settings.lat0; -sensorSettings.lon0 = settings.lon0; -sensorSettings.z0 = settings.z0; +sensorSettings.lat0 = environment.lat0; +sensorSettings.lon0 = environment.lon0; +sensorSettings.z0 = environment.z0; sensorSettings.spheroid = wgs84Ellipsoid; %% initial chamber pressure sensor NAT825281 diff --git a/data/Gemini_Roccaraso_September_2023/configGemini_Roccaraso_September_2023.m b/data/2023_Gemini_Roccaraso_September/configGemini_Roccaraso_September_2023.m similarity index 97% rename from data/Gemini_Roccaraso_September_2023/configGemini_Roccaraso_September_2023.m rename to data/2023_Gemini_Roccaraso_September/configGemini_Roccaraso_September_2023.m index e39dbf0197f3d18764a9a3638ce978181293e433..4e9ef648c533f46deb245eaff97955667a408347 100644 --- a/data/Gemini_Roccaraso_September_2023/configGemini_Roccaraso_September_2023.m +++ b/data/2023_Gemini_Roccaraso_September/configGemini_Roccaraso_September_2023.m @@ -108,9 +108,9 @@ settings.nas.stopPitotAltitude = 500; settings.nas.t_nas = -1; % Apogee detection timestamp settings.nas.flag_apo = false; % True when the apogee is detected -settings.nas.lat0 = settings.lat0; -settings.nas.lon0 = settings.lon0; -settings.nas.z0 = -settings.z0; +settings.nas.lat0 = environment.lat0; +settings.nas.lon0 = environment.lon0; +settings.nas.z0 = -environment.z0; settings.nas.spheroid = wgs84Ellipsoid; % Process noise covariance matrix for the linear dynamics @@ -135,7 +135,7 @@ settings.ada.P0 = [ 0.1 0 0; % In 0 0.1 0; % state covariance matrix 0 0 0.1;]; [settings.ada.temp_ref, ~,... - settings.ada.p_ref, ~] = atmosisa(settings.z0); % Reference temperature in kelvin and pressure in Pa + settings.ada.p_ref, ~] = atmosisa(environment.z0); % Reference temperature in kelvin and pressure in Pa settings.ada.v0 = 0; % Vertical velocity initial condition settings.ada.a0 = 0; % Acceleration velocity initial condition diff --git a/data/Gemini_Roccaraso_September_2023/initSensorsGemini_Roccaraso_September_2023.m b/data/2023_Gemini_Roccaraso_September/initSensorsGemini_Roccaraso_September_2023.m similarity index 98% rename from data/Gemini_Roccaraso_September_2023/initSensorsGemini_Roccaraso_September_2023.m rename to data/2023_Gemini_Roccaraso_September/initSensorsGemini_Roccaraso_September_2023.m index 7767f8076da978b50403b18e95321c7c5e7bdb51..839930076de47c06e1c4ca5543244f9b226141fb 100644 --- a/data/Gemini_Roccaraso_September_2023/initSensorsGemini_Roccaraso_September_2023.m +++ b/data/2023_Gemini_Roccaraso_September/initSensorsGemini_Roccaraso_September_2023.m @@ -134,9 +134,9 @@ sensorSettings.magnetometer.transMatrix = diag([1 1 1]); % a sensorSettings.GPS = GPS(); % lon, in degree lat in deree, alt in m sensorSettings.GPS.noiseVariance = [2e-9*ones(2,1);5;0.0011*ones(3,1)]; % [deg; deg; m; m/s; m/s; m/s]^2 sensorSettings.GPS.transMatrix = diag([1 1 1]); % axis transformation -sensorSettings.lat0 = settings.lat0; -sensorSettings.lon0 = settings.lon0; -sensorSettings.z0 = settings.z0; +sensorSettings.lat0 = environment.lat0; +sensorSettings.lon0 = environment.lon0; +sensorSettings.z0 = environment.z0; sensorSettings.spheroid = wgs84Ellipsoid; %% initial chamber pressure sensor NAT825281 diff --git a/data/Lyra_Portugal_October_2024/configLyra_Portugal_October_2024.m b/data/2024_Lyra_Portugal_October/config2024_Lyra_Portugal_October.m similarity index 90% rename from data/Lyra_Portugal_October_2024/configLyra_Portugal_October_2024.m rename to data/2024_Lyra_Portugal_October/config2024_Lyra_Portugal_October.m index a611f87183ecc7119a1c242a48ead0ff85a114a8..245714472adf1d40a7304f49d3c2a6128c5cc27a 100644 --- a/data/Lyra_Portugal_October_2024/configLyra_Portugal_October_2024.m +++ b/data/2024_Lyra_Portugal_October/config2024_Lyra_Portugal_October.m @@ -59,7 +59,7 @@ settings.arb.extPol(1) = -0.009083; % co settings.arb.extPol(2) = 0.02473; % coefficient for extension - alpha^3 settings.arb.extPol(3) = -0.01677; % coefficient for extension - alpha^2 settings.arb.extPol(4) = 0.03129; % coefficient for extension - alpha -settings.arb.maxExt = settings.hprot(end); % maximum extension of air brake aerodynamic surface +settings.arb.maxExt = rocket.airbrakes.height(end); % maximum extension of air brake aerodynamic surface % servo angle to exposed surface of the airbrakes (GEMINI) settings.arb.surfPol = 0.00932857142857; % coefficient for surface - alpha @@ -78,7 +78,7 @@ settings.arb.R = 66e-3; % tr x = @(alpha) settings.arb.extPol(1)*alpha.^4 + ... settings.arb.extPol(2)*alpha.^3+settings.arb.extPol(3)*alpha.^2 + ... settings.arb.extPol(4).*alpha; -fun = @(alpha) x(alpha) - settings.hprot(end); +fun = @(alpha) x(alpha) - settings.arb.maxExt ; settings.servo.maxAngle = fzero(fun, deg2rad(50)); settings.servo.maxAngle = fix(settings.servo.maxAngle*1e9)/1e9; % to avoid computational error propagation (truncates the angle to the ninth decimal) @@ -109,9 +109,9 @@ settings.nas.stopPitotAltitude = 800; settings.nas.t_nas = -1; % Apogee detection timestamp settings.nas.flag_apo = false; % True when the apogee is detected -settings.nas.lat0 = settings.lat0; -settings.nas.lon0 = settings.lon0; -settings.nas.z0 = -settings.z0; +settings.nas.lat0 = environment.lat0; +settings.nas.lon0 = environment.lon0; +settings.nas.z0 = -environment.z0; settings.nas.spheroid = wgs84Ellipsoid; @@ -137,14 +137,13 @@ settings.ada.P0 = [ 0.1 0 0; % In 0 0.1 0; % state covariance matrix 0 0 0.1;]; [settings.ada.temp_ref, ~,... - settings.ada.p_ref, ~] = atmosisa(settings.z0); % Reference temperature in kelvin and pressure in Pa + settings.ada.p_ref, ~] = atmosisa(environment.z0); % Reference temperature in kelvin and pressure in Pa settings.ada.v0 = -10; % Vertical velocity initial condition settings.ada.a0 = -100; % Acceleration velocity initial condition settings.ada.x0 = [settings.ada.p_ref, settings.ada.v0, settings.ada.a0]; % Ada initial condition - -settings.ada.v_thr = 2.5; % Velocity threshold for the detected apogee +settings.ada.v_thr = 0; % Velocity threshold for the detected apogee settings.ada.count_thr = 5; % If the apogee is detected count_thr time, the algorithm will return the apogee event settings.ada.counter = 0; settings.ada.altitude_confidence_thr = 5; % If the ada recognizes altitude_confidence_thr samples under parachute cutting altitude, it sends the command @@ -152,12 +151,21 @@ settings.ada.altitude_confidence_thr = 5; % If settings.ada.t_ada = -1; % Apogee detection timestamp settings.ada.flag_apo = false; % True when the apogee is detected settings.ada.shadowmode = 18; + +if ~settings.parafoil + settings.ada.para.z_cut = rocket.parachutes(1,1).finalAltitude; +else + settings.ada.para.z_cut = rocket.parachutes(1,2).finalAltitude; +end + %% MEA TUNING PARAMETERS / MOTOR SHUT DOWN TUNING PARAMETERS %motor model for kalman filter prediction/correction scheme -settings.mea.engine_model_A1 = [1.850256474259625, -0.850256474275721, 0; 1.000000000000000, 0, 0; -7.901993537244965e-04 , 7.901993537244965e-04, 1]; + + +settings.mea.engine_model_A1 = [1.62583090191848 -0.680722129751093 0; 1 0 0; -0.00102053146869855 0.000494919888520664 1]; settings.mea.engine_model_B1 = [2;0;0]; -settings.mea.engine_model_C1 = [0.944030389140057, -0.945656895768324 ,0]; -settings.mea.K_t = 104.2; +settings.mea.engine_model_C1 = [1.00196621875211 -0.485916431287183 0]; +settings.mea.K_t = 105.2; % covariance matrices settings.mea.Q = eye(3); % model noise covariance matrix @@ -177,4 +185,4 @@ Rs = 1.0e+03*[0.4771 1.4391]; % variable variance coefficients for accelerometer settings.mea.alpha = (Rs(2) - Rs(1))/(100^2-30^2); settings.mea.c = -settings.mea.alpha*30^2+Rs(1); -settings.mea.mass_interval = [settings.ms; settings.m0]; +settings.mea.mass_interval = [rocket.massNoMotor + rocket.motor.structureMass; rocket.mass(1)]; diff --git a/data/Lyra_Portugal_October_2024/initSensorsLyra_Portugal_October_2024.m b/data/2024_Lyra_Portugal_October/initSensors2024_Lyra_Portugal_October.m similarity index 98% rename from data/Lyra_Portugal_October_2024/initSensorsLyra_Portugal_October_2024.m rename to data/2024_Lyra_Portugal_October/initSensors2024_Lyra_Portugal_October.m index c4b1f7703ae69782c2bd05df832b67578e81ab4e..e71cad63fe40dc3ea8e1425ac9b74e5dec45d91e 100644 --- a/data/Lyra_Portugal_October_2024/initSensorsLyra_Portugal_October_2024.m +++ b/data/2024_Lyra_Portugal_October/initSensors2024_Lyra_Portugal_October.m @@ -136,9 +136,9 @@ sensorSettings.magnetometer.transMatrix = diag([1 1 1]); % a sensorSettings.GPS = GPS(); % lon, in degree lat in deree, alt in m sensorSettings.GPS.noiseVariance = [2e-9*ones(2,1);5;0.0011*ones(3,1)]; % [deg; deg; m; m/s; m/s; m/s]^2 sensorSettings.GPS.transMatrix = diag([1 1 1]); % axis transformation -sensorSettings.lat0 = settings.lat0; -sensorSettings.lon0 = settings.lon0; -sensorSettings.z0 = settings.z0; +sensorSettings.lat0 = environment.lat0; +sensorSettings.lon0 = environment.lon0; +sensorSettings.z0 = environment.z0; sensorSettings.spheroid = wgs84Ellipsoid; %% initial chamber pressure sensor NAT825281 diff --git a/data/Lyra_Roccaraso_September_2024/configLyra_Roccaraso_September_2024.m b/data/2024_Lyra_Roccaraso_September/configLyra_Roccaraso_September_2024.m similarity index 95% rename from data/Lyra_Roccaraso_September_2024/configLyra_Roccaraso_September_2024.m rename to data/2024_Lyra_Roccaraso_September/configLyra_Roccaraso_September_2024.m index 6497549045d9feef75843750aa011ea0ee089878..d01883844589602655f669fbff1d5b62d0479b6d 100644 --- a/data/Lyra_Roccaraso_September_2024/configLyra_Roccaraso_September_2024.m +++ b/data/2024_Lyra_Roccaraso_September/configLyra_Roccaraso_September_2024.m @@ -108,9 +108,9 @@ settings.nas.stopPitotAltitude = 300; settings.nas.t_nas = -1; % Apogee detection timestamp settings.nas.flag_apo = false; % True when the apogee is detected -settings.nas.lat0 = settings.lat0; -settings.nas.lon0 = settings.lon0; -settings.nas.z0 = -settings.z0; +settings.nas.lat0 = environment.lat0; +settings.nas.lon0 = environment.lon0; +settings.nas.z0 = -environment.z0; settings.nas.spheroid = wgs84Ellipsoid; % Process noise covariance matrix for the linear dynamics @@ -135,7 +135,7 @@ settings.ada.P0 = [ 0.1 0 0; % In 0 0.1 0; % state covariance matrix 0 0 0.1;]; [settings.ada.temp_ref, ~,... - settings.ada.p_ref, ~] = atmosisa(settings.z0); % Reference temperature in kelvin and pressure in Pa + settings.ada.p_ref, ~] = atmosisa(environment.z0); % Reference temperature in kelvin and pressure in Pa settings.ada.v0 = -10; % Vertical velocity initial condition settings.ada.a0 = -100; % Acceleration velocity initial condition @@ -153,10 +153,10 @@ settings.ada.flag_apo = false; % Tru settings.ada.shadowmode = 10; %% MEA TUNING PARAMETERS / MOTOR SHUT DOWN TUNING PARAMETERS -settings.mea.engine_model_A1 = [1.850256474259625, -0.850256474275721, 0; 1.000000000000000, 0, 0; -7.901993537244965e-04 , 7.901993537244965e-04, 1]; +settings.mea.engine_model_A1 = [1.62583090191848 -0.680722129751093 0; 1 0 0; -0.00102053146869855 0.000494919888520664 1]; settings.mea.engine_model_B1 = [2;0;0]; -settings.mea.engine_model_C1 = [0.944030389140057, -0.945656895768324 ,0]; -settings.mea.K_t = 104.2; +settings.mea.engine_model_C1 = [1.00196621875211 -0.485916431287183 0]; +settings.mea.K_t = 105.2; % covariance matrices settings.mea.Q = eye(3); % model noise covariance matrix diff --git a/data/Lyra_Roccaraso_September_2024/initSensorsLyra_Roccaraso_September_2024.m b/data/2024_Lyra_Roccaraso_September/initSensorsLyra_Roccaraso_September_2024.m similarity index 98% rename from data/Lyra_Roccaraso_September_2024/initSensorsLyra_Roccaraso_September_2024.m rename to data/2024_Lyra_Roccaraso_September/initSensorsLyra_Roccaraso_September_2024.m index 2d4fd749c57f28028e4391741870362c5cc2f282..da8926581abb876e3c55a1846b7d35d75862b87a 100644 --- a/data/Lyra_Roccaraso_September_2024/initSensorsLyra_Roccaraso_September_2024.m +++ b/data/2024_Lyra_Roccaraso_September/initSensorsLyra_Roccaraso_September_2024.m @@ -134,9 +134,9 @@ sensorSettings.magnetometer.transMatrix = diag([1 1 1]); % a sensorSettings.GPS = GPS(); % lon, in degree lat in deree, alt in m sensorSettings.GPS.noiseVariance = [2e-9*ones(2,1);5;0.0011*ones(3,1)]; % [deg; deg; m; m/s; m/s; m/s]^2 sensorSettings.GPS.transMatrix = diag([1 1 1]); % axis transformation -sensorSettings.lat0 = settings.lat0; -sensorSettings.lon0 = settings.lon0; -sensorSettings.z0 = settings.z0; +sensorSettings.lat0 = environment.lat0; +sensorSettings.lon0 = environment.lon0; +sensorSettings.z0 = environment.z0; sensorSettings.spheroid = wgs84Ellipsoid; %% initial chamber pressure sensor NAT825281 diff --git a/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_configABK_Gemini_Portugal_October_2023.csv b/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_configABK_Gemini_Portugal_October_2023.csv deleted file mode 100644 index 9d2aa051f2ef293f20fb8972fbe278afb6fc8986..0000000000000000000000000000000000000000 --- a/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_configABK_Gemini_Portugal_October_2023.csv +++ /dev/null @@ -1,2 +0,0 @@ -ABK_FREQUENCY,REFERENCE_DZ,STARTING_FILTER_VALUE,CHANGE_FILTER_MINIMUM_ALTITUDE,CHANGE_FILTER_MAXIMUM_ALTITUDE,ABK_CRITICAL_ALTITUDE,ABK_REFERENCE_LOWEST_MASS,DELTA_MASS,ESTIMATED_MASS,N_FORWARD,ABK_DELAY_FROM_SHUTDOWN -10,10,0.9,1000,3000,2990,26,0.4,28.504918688224,0,0.5 diff --git a/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_outputABK_Gemini_Portugal_October_2023.csv b/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_outputABK_Gemini_Portugal_October_2023.csv deleted file mode 100644 index fb172bb10f13ab1183f86cd1278cf46a65f752c4..0000000000000000000000000000000000000000 --- a/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_outputABK_Gemini_Portugal_October_2023.csv +++ /dev/null @@ -1,10468 +0,0 @@ -ABK -0.662643888531034 -0.694038399280397 -0.708846704237871 -0.739884518712291 -0.75522344098566 -0.787605513453206 -0.804510471674133 -0.839435882396657 -0.854152958311713 -0.889845260110717 -0.926986718700358 -0.9438055256115 -0.979441347050942 -0.993562427588679 -0.99930634701924 -0.99992360540037 -0.999991409286141 -0.999999012227781 -0.99999988393272 -0.999999986077884 -0.999999998294218 -0.999999999786746 -0.999999999972827 -0.999999999996476 -0.999999999999535 -0.999999999999937 -0.999999999999991 -0.999999999999999 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -0.995959342232919 -0.991368210156137 -0.986255082875228 -0.980645851626976 -0.974952119952211 -0.969181073930609 -0.963300170425925 -0.957416358005206 -0.951533138738589 -0.945200640725308 -0.938444176293359 -0.931541023943055 -0.924214273007593 -0.916490266691404 -0.90879901068304 -0.901143553418689 -0.893301516222314 -0.885151088773195 -0.876714657695605 -0.867982006241983 -0.858976279786052 -0.849830821127902 -0.840556601447161 -0.831168312399212 -0.822015505240068 -0.813090581573397 -0.804378373886387 -0.795779098501852 -0.787292147514545 -0.778805450623311 -0.770325120052803 -0.761740145993372 -0.752869017958638 -0.743736454854267 -0.734490180187477 -0.725145187684125 -0.716002196687285 -0.707318900788865 -0.699072476679057 -0.691035495038589 -0.683200873916668 -0.675145018799738 -0.666977195925427 -0.658710991714583 -0.650527498451947 -0.642427949595718 -0.634012844464645 -0.625298012462533 -0.616311778623024 -0.607269094847993 -0.598182809519209 -0.58913065529361 -0.580022255396623 -0.57087119709666 -0.561721393817728 -0.552582683660539 -0.543543330898541 -0.534623204198393 -0.525823172684405 -0.517276274776313 -0.508972669826645 -0.500468417992035 -0.491610767021705 -0.482438507103492 -0.473420250961843 -0.464555229981059 -0.455782174289083 -0.447166908696612 -0.438707874902254 -0.430386438318592 -0.422202344388796 -0.414176586242265 -0.406310918427146 -0.398602574886291 -0.390957274219102 -0.383380166247957 -0.37576201617721 -0.36804024735035 -0.360235492846609 -0.352676742207084 -0.345353772934224 -0.338161821547503 -0.331116485830223 -0.32421556745422 -0.317327731463799 -0.310462641639361 -0.303675992114644 -0.296879903902435 -0.290086778430148 -0.283443309378178 -0.276947063432042 -0.270575487697921 -0.264340320230504 -0.258239694950384 -0.252244537187748 -0.246355553956485 -0.240530399512495 -0.23472135519061 -0.228937868992523 -0.2232380620386 -0.217624933637024 -0.212079994564803 -0.206643983066525 -0.201317121139538 -0.19611371974249 -0.191032097187043 -0.186012215657174 -0.181003228988449 -0.176015205061363 -0.171091143606711 -0.16623585632482 -0.161501939274555 -0.156899340041187 -0.152424941251599 -0.148075396523023 -0.143847679763217 -0.139708294061775 -0.13569501887762 -0.131803891873279 -0.127975368454002 -0.124212153351182 -0.120543087264999 -0.116978690790911 -0.113516427153614 -0.110177893764734 -0.106957780354718 -0.103810390349005 -0.100736314812749 -0.0977352806767121 -0.0948031989944525 -0.0919400048263839 -0.0891710329557143 -0.0864632359933097 -0.0838169171465979 -0.081243841282796 -0.0787426140317441 -0.0762684574981564 -0.0738391448542293 -0.0714564430062553 -0.0691503120233999 -0.0669184422243453 -0.064734671398317 -0.0626130964239797 -0.0605526592718398 -0.0585678294872355 -0.0566554930826233 -0.054783543146763 -0.0529527916302454 -0.0511639450342808 -0.0494131693851185 -0.0477014397480857 -0.046050733729594 -0.0444507091271637 -0.0429003275225699 -0.0414023000665039 -0.0399550473638277 -0.0385552985476744 -0.0372076140377231 -0.0359099401852557 -0.0346585404922802 -0.0334517628962945 -0.0322755019339355 -0.0311316480597785 -0.0300200065807009 -0.0289460294507619 -0.0279086259350801 -0.0269056412763106 -0.025934176804609 -0.0249936005509938 -0.0240867841370313 -0.0232125804867263 -0.0223634223326504 -0.0215399887231167 -0.0207419209901318 -0.0199708141975421 -0.0192259723225999 -0.0184996435278584 -0.0177942676058226 -0.0171097634695274 -0.0164575888953458 -0.0158359013638002 -0.0152319779167694 -0.0146459607957425 -0.0140777320130392 -0.013525257901223 -0.0129886232150004 -0.0124718394360301 -0.0119706520446842 -0.0114850017460816 -0.0110160319665251 -0.0105634184814258 -0.0101249021944373 -0.009702409474856 -0.00929553685881385 -0.00890718728852595 -0.00853643687276874 -0.00817898551410632 -0.00783211772115998 -0.00749590053265595 -0.00717152644669105 -0.00685879784154464 -0.00655812651580203 -0.00626648572093204 -0.00598397789804059 -0.00571251994663112 -0.00545182552193908 -0.00520392307698162 -0.0049678873599116 -0.00474311767409866 -0.00452658840814392 -0.00431816586073559 -0.00411881717804023 -0.00392777667805632 -0.00374477658575048 -0.00356971532649447 -0.00340230134431445 -0.00324151655376463 -0.00308729891352616 -0.002939471155696 -0.00279868671246344 -0.0026646181188924 -0.0025365560297274 -0.00241396361339453 -0.00229666810104543 -0.00218455677861001 -0.00207744671796833 -0.00197497005686785 -0.00187763767598149 -0.0017851881284621 -0.00169697442356199 -0.00161283133766823 -0.00153250949049067 -0.00145562400356295 -0.00138207887888248 -0.00131223658281363 -0.00124591421446741 -0.00118260941994945 -0.00112241250584056 -0.00106518178308557 -0.00101077047674585 -0.000959049560115561 -0.000909557812113445 -0.000862309409475397 -0.000817231190047994 -0.000774652077592777 -0.000734424035609205 -0.000696076771593514 -0.000659410376012807 -0.000624381164450626 -0.000591212379095176 -0.000559806357470585 -0.000529708866493379 -0.00050077450102976 -0.000473004113967143 -0.00044673233403501 -0.000421882709487266 -0.000398205946232771 -0.000375626524727672 -0.000354116326182989 -0.000333884177853382 -0.000314851008233021 -0.000296938549952277 -0.000280089973335131 -0.000264238968968565 -0.000249244364675294 -0.000235063922917137 -0.000221653911720629 -0.000209001574702193 -0.000197065129725537 -0.000185759771697616 -0.000175057027016792 -0.000164924217588489 -0.000155296415397669 -0.000146156471639724 -0.000137519420130382 -0.00012936104487102 -0.000121657054917681 -0.000114390920085841 -0.000107539873162963 -0.000101086296825712 -9.50084830986671e-05 -8.92699013455167e-05 -8.38379759430497e-05 -7.87003208820986e-05 -7.3865953183484e-05 -6.93181742692225e-05 -6.50361473854871e-05 -6.10102383572988e-05 -5.72260192582019e-05 -5.36565620780267e-05 -5.02916942413678e-05 -4.71255954464622e-05 -4.41525747117183e-05 -4.13615257353602e-05 -3.873946230169e-05 -3.62769293661905e-05 -3.39519547589166e-05 -3.1766102647771e-05 -2.97120664768749e-05 -2.77905731395508e-05 -2.59931511772034e-05 -2.43018773729757e-05 -2.27118625559282e-05 -2.12179560605393e-05 -1.98187821882736e-05 -1.85087132590885e-05 -1.728239912344e-05 -1.61371548389143e-05 -1.50676703899234e-05 -1.40637639350936e-05 -1.31219698157469e-05 -1.22419914295459e-05 -1.14185254528088e-05 -1.06482100083364e-05 -9.92819336588704e-06 -9.25537365565232e-06 -8.6301252151464e-06 -8.04460252740428e-06 -7.49654779310769e-06 -6.98380415442288e-06 -6.50431262264138e-06 -6.05485410322194e-06 -5.63487128370023e-06 -5.24260163544071e-06 -4.87891861135959e-06 -4.54162920723756e-06 -4.226465899634e-06 -3.93263281127683e-06 -3.65874729982881e-06 -3.40320366418099e-06 -3.1648534622913e-06 -2.94256208437979e-06 -2.73443685321598e-06 -2.53973245566977e-06 -2.35846751975637e-06 -2.18976193852227e-06 -2.03261605792383e-06 -1.88644470064585e-06 -1.75051585138688e-06 -1.62404479148876e-06 -1.50641107875447e-06 -1.39660180298473e-06 -1.29443930137994e-06 -1.19943085480552e-06 -1.11129015991318e-06 -1.02953376872504e-06 -9.53576431300585e-07 -8.82829315906605e-07 -8.16978965966839e-07 -7.5607581799124e-07 -6.99746119256386e-07 -6.47357536046823e-07 -5.98685250111388e-07 -5.53488805139813e-07 -5.11558029878842e-07 -4.72673571397467e-07 -4.36883816604369e-07 -4.03912721241945e-07 -3.73528252685645e-07 -3.45334050640108e-07 -3.19183006716785e-07 -2.95033818102332e-07 -2.72613889317044e-07 -2.51810435268878e-07 -2.32535633619749e-07 -2.14683890950036e-07 -1.98200066333194e-07 -1.82935685835191e-07 -1.6880583996211e-07 -1.55688047190992e-07 -1.4351892197342e-07 -1.32291215144031e-07 -1.2192675127312e-07 -1.1236101059827e-07 -1.03512038998623e-07 -9.53300272029832e-08 -8.77760613109311e-08 -8.08003895383071e-08 -7.43611182543355e-08 -6.84054123685573e-08 -6.2900412839012e-08 -5.78308896671153e-08 -5.31591167877965e-08 -4.8855184982682e-08 -4.49057854699473e-08 -4.12811541196039e-08 -3.79532320864561e-08 -3.49035651112712e-08 -3.21079120199497e-08 -2.95281795047732e-08 -2.71486285009973e-08 -2.49461197277372e-08 -2.29135251972756e-08 -2.10387692107355e-08 -1.93122568987883e-08 -1.77228791833735e-08 -1.62570064319643e-08 -1.49047981418998e-08 -1.36583471482893e-08 -1.25114210471415e-08 -1.14566400356418e-08 -1.04913408915526e-08 -9.60982911139406e-09 -8.80458453929368e-09 -8.06579209608061e-09 -7.38809770647173e-09 -6.76684679305925e-09 -6.19796273285864e-09 -5.67702851603693e-09 -5.19906513112846e-09 -4.7606291135707e-09 -4.35767637242938e-09 -3.98795597860434e-09 -3.64883421497219e-09 -3.33778022985829e-09 -3.05256526785316e-09 -2.79130200528673e-09 -2.55256029541049e-09 -2.33438528901748e-09 -2.13415806274763e-09 -1.9504873390521e-09 -1.78169598928411e-09 -1.62722848642914e-09 -1.48590489171489e-09 -1.35655757416432e-09 -1.23820865810797e-09 -1.12996128593641e-09 -1.03116810259966e-09 -9.41006269768254e-10 -8.58841214234222e-10 -7.83952367023887e-10 -7.15293434827996e-10 -6.5241115133014e-10 -5.94848681889433e-10 -5.42211756027225e-10 -4.94097982848896e-10 -4.50098894306726e-10 -4.09933361347986e-10 -3.73278096425208e-10 -3.3981060220363e-10 -3.09264966685849e-10 -2.8128259979238e-10 -2.55558716244883e-10 -2.31946783312381e-10 -2.10452595852003e-10 -1.90894446780117e-10 -1.73175767668888e-10 -1.57110609447896e-10 -1.42543910256584e-10 -1.29292223873909e-10 -1.17241437190436e-10 -1.06278521856947e-10 -9.63009941292091e-11 -8.72254212745418e-11 -7.89830821626619e-11 -7.15003660226263e-11 -6.46999562508127e-11 -5.85292858804841e-11 -5.29322844322614e-11 -4.7850386218748e-11 -4.32388302791332e-11 -3.90711062638951e-11 -3.53065175047486e-11 -3.19059662025839e-11 -2.88228264074458e-11 -2.60288075378219e-11 -2.35053209541681e-11 -2.12313046674786e-11 -1.91815528051311e-11 -1.7330192825315e-11 -1.56579935680654e-11 -1.4149757960828e-11 -1.27944366144714e-11 -1.15756562319519e-11 -1.04699046118689e-11 -9.46710102547363e-12 -8.55503798240096e-12 -7.72689382516563e-12 -6.97546721244578e-12 -6.29802459834889e-12 -5.68718141318594e-12 -5.13329054210305e-12 -4.63211427716296e-12 -4.17879970878288e-12 -3.76943031492739e-12 -3.39980495358039e-12 -3.06504002911401e-12 -2.76170176124488e-12 -2.48704556059147e-12 -2.23896660093934e-12 -2.01499261017008e-12 -1.81361154355729e-12 -1.63285917366623e-12 -1.4705632322136e-12 -1.32395216108387e-12 -1.19157014900252e-12 -1.07207791236108e-12 -9.64204123193961e-13 -8.66868373980786e-13 -7.79172408254358e-13 -7.00187098520213e-13 -6.28888391866581e-13 -5.64469134010487e-13 -5.06317938966944e-13 -4.54062947986771e-13 -4.07119598651772e-13 -3.65020644471135e-13 -3.27350054208221e-13 -2.93633032126349e-13 -2.6327905035197e-13 -2.35967801389462e-13 -2.11455750396448e-13 -1.89480355329618e-13 -1.69780709843382e-13 -1.52048165502758e-13 -1.36097547944426e-13 -1.21823198447428e-13 -1.09030330508826e-13 -9.75674629916399e-14 -8.73104504376314e-14 -7.81325048947128e-14 -6.99036440576243e-14 -6.25571504087768e-14 -5.5996486294769e-14 -5.01111456222943e-14 -4.4833400723858e-14 -4.00974060351386e-14 -3.58551981281151e-14 -3.20562255442356e-14 -2.86494586444975e-14 -2.55958542439406e-14 -2.2851306626426e-14 -2.03804942237495e-14 -1.8159089021751e-14 -1.61816922569387e-14 -1.44212790745671e-14 -1.28501425243457e-14 -1.14476853272433e-14 -1.01961608408102e-14 -9.07865316483432e-15 -8.08121683820841e-15 -7.19104095737168e-15 -6.39790938069283e-15 -5.69139417918318e-15 -5.06005985250464e-15 -4.49631823860125e-15 -3.99417141086429e-15 -3.54823014064316e-15 -3.15219281218272e-15 -2.80036216314467e-15 -2.48780864679578e-15 -2.20920189232694e-15 -1.96133461907824e-15 -1.74088365792611e-15 -1.54468286636171e-15 -1.37014237610527e-15 -1.21482856525849e-15 -1.07663618357737e-15 -9.53749364430831e-16 -8.44750724364841e-16 -7.48091892156892e-16 -6.62232748926181e-16 -5.86157967610413e-16 -5.18763581966324e-16 -4.59089946775422e-16 -4.06257421299524e-16 -3.59366541776277e-16 -3.17905315092397e-16 -2.81243167162218e-16 -2.4870992933799e-16 -2.19855429461875e-16 -1.94338481193901e-16 -1.71761730830351e-16 -1.51789776071631e-16 -1.34128711134698e-16 -1.18513030432959e-16 -1.04705939758198e-16 -9.24957754633742e-17 -8.16996788398162e-17 -7.21545292726373e-17 -6.37168301382048e-17 -5.62639763323154e-17 -4.9675720909624e-17 -4.38528829512089e-17 -3.86933953521212e-17 -3.41245859819975e-17 -3.00910210176668e-17 -2.65332634650739e-17 -2.33953738641464e-17 -2.0619366121696e-17 -1.81649065673053e-17 -1.60037948285537e-17 -1.41029346747407e-17 -1.24305611338036e-17 -1.09516535356061e-17 -9.64456940696214e-18 -8.49269063520663e-18 -7.47721030543244e-18 -6.58216232903387e-18 -5.79209157603778e-18 -5.09501760433017e-18 -4.48185975650689e-18 -3.94037470375745e-18 -3.46251065031167e-18 -3.04162563587993e-18 -2.67107702037702e-18 -2.34566726215452e-18 -2.05978040278776e-18 -1.80863778640815e-18 -1.58804501674427e-18 -1.39429928579491e-18 -1.22346800819237e-18 -1.07315131872156e-18 -9.40950636066674e-19 -8.24874283371734e-19 -7.22981405434993e-19 -6.33444358687173e-19 -5.54669039348885e-19 -4.8541346192728e-19 -4.24708318391957e-19 -3.71513517467639e-19 -3.24793680947347e-19 -2.83956833432484e-19 -2.4826155987956e-19 -2.16921684272953e-19 -1.89426776584096e-19 -1.6536073460663e-19 -1.44251130650285e-19 -1.25751053203097e-19 -1.09596484301892e-19 -9.54945001823465e-20 -8.31940009844818e-20 -7.24350424960736e-20 -6.30313996148126e-20 -5.48566815216579e-20 -4.77491425329404e-20 -4.15536299596196e-20 -3.61470118949886e-20 -3.1431284706782e-20 -2.73205162847103e-20 -2.3738784869402e-20 -2.06290504582699e-20 -1.79303322440642e-20 -1.55877759639358e-20 -1.35438710615792e-20 -1.17617563114176e-20 -1.02168971561762e-20 -8.8749422248056e-21 -7.70926008287547e-21 -6.69455622115443e-21 -5.81162818441103e-21 -5.04154073048611e-21 -4.37083808523007e-21 -3.78713499250742e-21 -3.28282001239113e-21 -2.84687814778234e-21 -2.46812235686576e-21 -2.13889314571331e-21 -1.8528581303112e-21 -1.60484193767884e-21 -1.38983168954083e-21 -1.20335482126382e-21 -1.04177884536675e-21 -9.01799807215516e-22 -7.80456142679068e-22 -6.75296364863734e-22 -5.8411432210436e-22 -5.05019902876601e-22 -4.36448412510157e-22 -3.77106843183924e-22 -3.25766698794518e-22 -2.81399485884936e-22 -2.42983663822318e-22 -2.09736371369889e-22 -1.81071021617546e-22 -1.56351240294034e-22 -1.34972040347785e-22 -1.16535065866866e-22 -1.00632584638206e-22 -8.68515742087717e-23 -7.49172461174156e-23 -6.46076165866619e-23 -5.56877405627355e-23 -4.79752190281355e-23 -4.13208323645143e-23 -3.55811473505322e-23 -3.06245907589783e-23 -2.63431514341119e-23 -2.26475158470033e-23 -1.94647811050093e-23 -1.67247345719114e-23 -1.43692966609183e-23 -1.23450975479429e-23 -1.06056623096198e-23 -9.10904223765707e-24 -7.82174149539387e-24 -6.71624745045257e-24 -5.76646268890539e-24 -4.95055654626009e-24 -4.24850420940278e-24 -3.64469584513451e-24 -3.1260214764307e-24 -2.68120788274516e-24 -2.29973413842646e-24 -1.97292062661699e-24 -1.6928749013774e-24 -1.45225847221693e-24 -1.24513328587233e-24 -1.0669614938565e-24 -9.14137219337984e-25 -7.83081210983905e-25 -6.70697140590243e-25 -5.74225006149359e-25 -4.91450173752088e-25 -4.20522803707178e-25 -3.59762428985799e-25 -3.07695911147123e-25 -2.63127173490015e-25 -2.24983419610837e-25 -1.92320893123904e-25 -1.6436059784153e-25 -1.40491015332384e-25 -1.2010178500119e-25 -1.0268331772277e-25 -8.77581133939019e-26 -7.49751420087317e-26 -6.40388126129606e-26 -5.46710962742306e-26 -4.66517477414938e-26 -3.98166490842391e-26 -3.39896363070239e-26 -2.90056148390377e-26 -2.47500753528277e-26 -2.11169890595068e-26 -1.80133085227832e-26 -1.53625981989793e-26 -1.3096297278247e-26 -1.11610274587286e-26 -9.50903177472776e-27 -8.09807944572412e-27 -6.89362638414813e-27 -5.86610682637544e-27 -4.98868974568721e-27 -4.2400012172838e-27 -3.60324352803061e-27 -3.06176534196128e-27 -2.60091404247674e-27 -2.20845480013415e-27 -1.87441613784547e-27 -1.5903123759321e-27 -1.3487873502675e-27 -1.14374167863577e-27 -9.69750379447691e-28 -8.22132957495025e-28 -6.96926011480468e-28 -5.90739343322427e-28 -5.00760879355858e-28 -4.24551415027323e-28 -3.59993459137642e-28 -3.05179191705122e-28 -2.58651618743422e-28 -2.19230833910106e-28 -1.85869931548562e-28 -1.57628600099554e-28 -1.3356914086125e-28 -1.13092443448837e-28 -9.57300838074105e-29 -8.10103097253623e-29 -6.85352005060904e-29 -5.79677071991404e-29 -4.90186671166361e-29 -4.14399396777558e-29 -3.50205861149931e-29 -2.95855608974639e-29 -2.49825216339585e-29 -2.1086261411341e-29 -1.77924303299873e-29 -1.50129877229835e-29 -1.26676553153936e-29 -1.06863484412476e-29 -9.01301686222308e-30 -7.59898590829918e-30 -6.4025996044009e-30 -5.39115113959685e-30 -4.53801766323567e-30 -3.81869942817653e-30 -3.21391794534619e-30 -2.70605901310163e-30 -2.27938874493485e-30 -1.91870130588567e-30 -1.61403728834071e-30 -1.35715452608375e-30 -1.14045598092089e-30 -9.57789255522273e-31 -8.04241432687971e-31 -6.75198068921112e-31 -5.66716586567061e-31 -4.75703312812581e-31 -3.99339159734902e-31 -3.3499569236355e-31 -2.8082647092566e-31 -2.35418525841023e-31 -1.97370831383473e-31 -1.65487376674403e-31 -1.38724504308598e-31 -1.162657055817e-31 -9.74193157821488e-32 -8.1623219321803e-32 -6.83847514914924e-32 -5.73028094388725e-32 -4.80244605379908e-32 -4.02173384218711e-32 -3.36469252024299e-32 -2.8123646589735e-32 -2.3502387252891e-32 -1.96367658632005e-32 -1.6396812077984e-32 -1.36843331239258e-32 -1.14148497382778e-32 -9.52089063515098e-33 -7.94050231239416e-33 -6.61940109392131e-33 -5.51557477928913e-33 -4.59378909035304e-33 -3.82618110675582e-33 -3.18694692360486e-33 -2.6538919288197e-33 -2.209219127629e-33 -1.83842969354044e-33 -1.52978746275701e-33 -1.27289555232123e-33 -1.05872215063285e-33 -8.80196505039804e-34 -7.31462923284322e-34 -6.07564937774203e-34 -5.04415050612404e-34 -4.18624113607533e-34 -3.47356744412695e-34 -2.88168222357691e-34 -2.39013121792104e-34 -1.98201327959156e-34 -1.64350894422981e-34 -1.3621087042047e-34 -1.12832258641636e-34 -9.34424944815273e-35 -7.73658889156746e-35 -6.40492830255654e-35 -5.30461076438989e-35 -4.395042817757e-35 -3.63990956285144e-35 -3.01329959255693e-35 -2.49269808241096e-35 -2.06099209716622e-35 -1.70321604462191e-35 -1.40730287445988e-35 -1.16260753125065e-35 -9.60130293024811e-36 -7.9270637341058e-36 -6.54310839916287e-36 -5.40128230024062e-36 -4.45913369545477e-36 -3.68015182866934e-36 -3.03654423099809e-36 -2.50493320464684e-36 -2.06705412166862e-36 -1.70625365321783e-36 -1.40768869412597e-36 -1.16054963301387e-36 -9.56147185691924e-37 -7.87609720399143e-37 -6.486731461522e-37 -5.34113221462187e-37 -4.39619153365569e-37 -3.61710896843473e-37 -2.97612763531751e-37 -2.44876661005203e-37 -2.01404680255673e-37 -1.65576558648148e-37 -1.36063596369949e-37 -1.11839483403153e-37 -9.19509558384566e-38 -7.5582790811343e-38 -6.21231498246325e-38 -5.10563731070293e-38 -4.19479413598756e-38 -3.44540689950669e-38 -2.82971685703411e-38 -2.3244061979544e-38 -1.9096187143574e-38 -1.56833999885353e-38 -1.28764988535193e-38 -1.05655202376436e-38 -8.66220826619374e-39 -7.09614093360411e-39 -5.8118806309142e-39 -4.75900245465064e-39 -3.89652443372101e-39 -3.19061598420936e-39 -2.6128068239534e-39 -2.13943653259131e-39 -1.7516730981863e-39 -1.4335462068257e-39 -1.17269454087069e-39 -9.58912762190962e-40 -7.83857326354344e-40 -6.40565696105782e-40 -5.23315566637534e-40 -4.27599478405603e-40 -3.49448398417004e-40 -2.85502202413656e-40 -2.33195888122443e-40 -1.90422100461283e-40 -1.55446975892075e-40 -1.26858776228663e-40 -1.03560665044815e-40 -8.45672377849302e-41 -6.90381022832809e-41 -5.6341012586015e-41 -4.59636943687389e-41 -3.74852722145611e-41 -3.05609656048116e-41 -2.49117044855735e-41 -2.03023809608884e-41 -1.65425083838842e-41 -1.34776990911193e-41 -1.09797461307603e-41 -8.94072313321993e-42 -7.27528184255567e-42 -5.91607363979136e-42 -4.80971089025209e-42 -3.90939833138644e-42 -3.17752454800075e-42 -2.58359145088161e-42 -2.10141111605882e-42 -1.70975545696366e-42 -1.391520611566e-42 -1.1319929352039e-42 -9.20986215929653e-43 -7.49405976848321e-43 -6.0953212805718e-43 -4.95561720240012e-43 -4.02847832844835e-43 -3.27398634424687e-43 -2.66016944929714e-43 -2.16097286096022e-43 -1.75509453805395e-43 -1.42479054610454e-43 -1.15669209449957e-43 -9.39076932154208e-44 -7.62013079464294e-44 -6.18029039096487e-44 -5.01077228981017e-44 -4.06135514782985e-44 -3.2908834600749e-44 -2.66593803067983e-44 -2.15917378191883e-44 -1.74845914016683e-44 -1.41543132512832e-44 -1.14549295041217e-44 -9.26789632805662e-45 -7.49651392884549e-45 -6.06165893515257e-45 -4.90114407308e-45 -3.96258856178123e-45 -3.20272922615078e-45 -2.58777333153189e-45 -2.08973776998106e-45 -1.68658250360447e-45 -1.36044766747179e-45 -1.09688153728236e-45 -8.83991241401464e-46 -7.122192059744e-46 -5.73515490497889e-46 -4.61583411049475e-46 -3.71428527596343e-46 -2.98829681098089e-46 -2.40431627199352e-46 -1.93476743712866e-46 -1.55716342493692e-46 -1.25384706348328e-46 -1.01007751860807e-46 -8.13423517332206e-47 -6.54598488262514e-47 -5.26428308864489e-47 -4.23225676387856e-47 -3.40155995633006e-47 -2.73226966794818e-47 -2.19320657156544e-47 -1.75936292862525e-47 -1.41153353732518e-47 -1.1326248364321e-47 -9.08733663537873e-48 -7.28958708640715e-48 -5.84639934182407e-48 -4.68961360193928e-48 -3.76225112458431e-48 -3.01693396507536e-48 -2.4183091504067e-48 -1.93772349483056e-48 -1.552137256964e-48 -1.24288772388371e-48 -9.95206790021501e-49 -7.96911630815385e-49 -6.38150212457779e-49 -5.10964775010677e-49 -4.09087834844199e-49 -3.27308744692193e-49 -2.61647671219168e-49 -2.08980758274668e-49 -1.66965992213415e-49 -1.3343786816225e-49 -1.06582900051268e-49 -8.51090711373451e-50 -6.79435997354773e-50 -5.4220908926746e-50 -4.32549763067746e-50 -3.45008006731426e-50 -2.75130817432118e-50 -2.19366197906349e-50 -1.74855976373251e-50 -1.3934008111439e-50 -1.11023384096295e-50 -8.84371923694812e-51 -7.042745031802e-51 -5.60813956225032e-51 -4.46547202091678e-51 -3.55330285543393e-51 -2.82509495919079e-51 -2.24430215174129e-51 -1.78298888762779e-51 -1.41656158288356e-51 -1.1253346315957e-51 -8.93653279989768e-52 -7.09419678860286e-52 -5.62948842673432e-52 -4.46552065021451e-52 -3.54089209174501e-52 -2.80648706581468e-52 -2.22346221115332e-52 -1.76094537094597e-52 -1.39417376788425e-52 -1.10372864303834e-52 -8.7363455910745e-53 -6.91389423172409e-53 -5.47179196354132e-53 -4.33062905495365e-53 -3.4266118912051e-53 -2.71079669582381e-53 -2.14412706825611e-53 -1.69590178321258e-53 -1.34137003762159e-53 -1.06051926543148e-53 -8.37943545941081e-54 -6.61677163357551e-54 -5.22319760341073e-54 -4.1218375369709e-54 -3.25215788125084e-54 -2.56493470699399e-54 -2.0221396326765e-54 -1.59398969266371e-54 -1.25632574263841e-54 -9.89519037883405e-55 -7.78954259092624e-55 -6.12877312069768e-55 -4.82091713532771e-55 -3.79126821522749e-55 -2.98038640327195e-55 -2.3422300460522e-55 -1.84018027942733e-55 -1.44480102392915e-55 -1.13365750025629e-55 -8.89337905258562e-56 -6.97290736876932e-56 -5.46425793410015e-56 -4.2811556065133e-56 -3.35356775118289e-56 -2.62595247162784e-56 -2.05515947640163e-56 -1.60764695257436e-56 -1.25708067061161e-56 -9.82582776385012e-57 -7.67863746737847e-57 -5.99964636363471e-57 -4.68702160877629e-57 -3.66279820528518e-57 -2.86332472210067e-57 -2.23783679930513e-57 -1.74837407275695e-57 -1.36550723341017e-57 -1.06581644792944e-57 -8.31397255234265e-58 -6.48526792037165e-58 -5.06008965842872e-58 -3.94909234335326e-58 -3.08202929676851e-58 -2.40534693541285e-58 -1.87687630408556e-58 -1.46409492915834e-58 -1.14178202820744e-58 -8.90428835690974e-59 -6.94413724457716e-59 -5.41526263020665e-59 -4.22132655839192e-59 -3.2893693410379e-59 -2.56284311598398e-59 -1.99654797405888e-59 -1.55486796406172e-59 -1.21051972854094e-59 -9.42149542799714e-60 -7.33157330065018e-60 -5.70436128384951e-60 -4.43698671324353e-60 -3.45058770221394e-60 -2.68302762762676e-60 -2.08552474578616e-60 -1.6205740580086e-60 -1.25936955600243e-60 -9.78936970093558e-61 -7.61151378309474e-61 -5.91525630791155e-61 -4.59483097611837e-61 -3.56848618647311e-61 -2.76962713847288e-61 -2.14827784489907e-61 -1.66659580590806e-61 -1.29312276699406e-61 -1.00297517790456e-61 -7.77493436962779e-62 -6.0237579068938e-62 -4.66635024887305e-62 -3.6143403549253e-62 -2.79917664289327e-62 -2.16744650786894e-62 -1.67797996651474e-62 -1.29878337248394e-62 -1.00508284369824e-62 -7.78089796713628e-63 -6.02421217851988e-63 -4.66458706196538e-63 -3.60996929705986e-63 -2.79240641952855e-63 -2.1603406426162e-63 -1.67131409297316e-63 -1.29296673037634e-63 -9.99896812975734e-64 -7.7297821174096e-64 -5.9749664186469e-64 -4.61878390615036e-64 -3.57062327558441e-64 -2.75893651343238e-64 -2.13072784791128e-64 -1.64466217849841e-64 -1.26914939843001e-64 -9.79130088084158e-65 -7.55383751417665e-65 -5.82767694731307e-65 -4.49456037423022e-65 -3.4641916003987e-65 -2.6683852181387e-65 -2.05544451177086e-65 -1.58334035994487e-65 -1.21947412183224e-65 -9.38805269299691e-66 -7.22419968264844e-66 -5.55716811419318e-66 -4.27338774292866e-66 -3.28430192124578e-66 -2.52233576682484e-66 -1.93580577678532e-66 -1.48452667468449e-66 -1.13760693092923e-66 -8.71484901583226e-67 -6.67694071003685e-67 -5.11616799672448e-67 -3.91905167135733e-67 -3.00117282209673e-67 -2.29773039889357e-67 -1.75891118813827e-67 -1.34625850320476e-67 -1.03035262090961e-67 -7.88529664165794e-68 -6.03226277477115e-68 -4.61133652316155e-68 -3.5226372074918e-68 -2.69062406310506e-68 -2.05487246841405e-68 -1.56977493153646e-68 -1.19954129814577e-68 -9.16886611856159e-69 -7.0048263808063e-69 -5.34894112055966e-69 -4.08378544953904e-69 -3.11753979887489e-69 -2.37967405637932e-69 -1.81587937754868e-69 -1.38524176586531e-69 -1.05595982968425e-69 -8.04307027565638e-70 -6.12153082039559e-70 -4.65790369046205e-70 -3.5433782262292e-70 -2.69509614767613e-70 -2.04907949993946e-70 -1.55731787867861e-70 -1.18321406140092e-70 -8.98714920785216e-71 -6.82771300951944e-71 -5.18910362565645e-71 -3.94520325927807e-71 -2.99790522495159e-71 -2.27690848214214e-71 -1.72876150443608e-71 -1.31235160606709e-71 -9.96079943342613e-72 -7.55909048427245e-72 -5.73560618526578e-72 -4.35072488149155e-72 -3.30005361760326e-72 -2.5029903340246e-72 -1.89822909329433e-72 -1.43943421894412e-72 -1.09070670196405e-72 -8.25605788560716e-73 -6.24309611237292e-73 -4.71968459853466e-73 -3.56710638362077e-73 -2.69619842173429e-73 -2.03875117037488e-73 -1.54222940546461e-73 -1.16629695304044e-73 -8.81757983853008e-74 -6.66617358179531e-74 -5.03912601544357e-74 -3.80879560207191e-74 -2.8773535772649e-74 -2.172598806988e-74 -1.63969978178568e-74 -1.23733122656772e-74 -9.33570999608415e-75 -7.04155362409927e-75 -5.30951118459364e-75 -4.00109367872803e-75 -3.01366461333804e-75 -2.26887338218434e-75 -1.7074298064257e-75 -1.28439655135942e-75 -9.65962988036313e-76 -7.26329876372066e-76 -5.46038265207346e-76 -4.10452490194271e-76 -3.08500522259776e-76 -2.31820065141559e-76 -1.74145566936028e-76 -1.30781135423379e-76 -9.82102585921201e-77 -7.37478518120719e-77 -5.53677538729549e-77 -4.15654214455805e-77 -3.12016264740184e-77 -2.34123618136828e-77 -1.75607227612777e-77 -1.31631041713447e-77 -9.86187949514508e-78 -7.38505662286202e-78 -5.53021515132438e-78 -4.14119382949877e-78 -3.10055771607327e-78 -2.32160878832103e-78 -1.73849419871428e-78 -1.30148985028275e-78 -9.74083359353214e-79 -7.28719500899503e-79 -5.45095580567441e-79 -4.0769512775825e-79 -3.0474153088022e-79 -2.27651132156369e-79 -1.69983865231045e-79 -1.2688168834047e-79 -9.46779700838968e-80 -7.06457562725621e-80 -5.27122845964664e-80 -3.93163548302823e-80 -2.93187680566021e-80 -2.185913353063e-80 -1.62966811124963e-80 -1.21491551697571e-80 -9.05314236723491e-81 -6.74535229581245e-81 -5.02532800797329e-81 -3.74403658281399e-81 -2.78953762579067e-81 -2.07769374851142e-81 -1.54695689691877e-81 -1.15140407375577e-81 -8.56851892388526e-82 -6.37551619632042e-82 -4.74063089815204e-82 -3.5246879120902e-82 -2.62042086782264e-82 -1.94739292376011e-82 -1.44668584215404e-82 -1.07426481248186e-82 -7.97420175613015e-83 -5.9170822813065e-83 -4.38963534417496e-83 -3.25576999647891e-83 -2.41357974526298e-83 -1.7884852082594e-83 -1.32474188027708e-83 -9.8081753033603e-84 -7.25876627380959e-84 -5.37147060171565e-84 -3.97477911827447e-84 -2.94119360465926e-84 -2.17568843382015e-84 -1.6089307998408e-84 -1.18873742870886e-84 -8.77439986122013e-85 -6.47060494751533e-85 -4.77320099183999e-85 -3.52215921509641e-85 -2.59711370171752e-85 -1.91387177489091e-85 -1.40955909707283e-85 -1.03762715757444e-85 -7.63474107382437e-86 -5.61618197987571e-86 -4.1302448033051e-86 -3.0367054048639e-86 -2.23199545197472e-86 -1.64003417226359e-86 -1.20467485682484e-86 -8.84302057479502e-87 -6.48716195111837e-87 -4.75556871444418e-87 -3.48380536673915e-87 -2.55060673186705e-87 -1.86579269368333e-87 -1.36372076969803e-87 -9.96177346296594e-88 -7.27286640404114e-88 -5.31090364252401e-88 -3.87840724228742e-88 -2.83244328158289e-88 -2.06846619149715e-88 -1.51048672777594e-88 -1.10259640578333e-88 -8.04671048332206e-89 -5.87119442515182e-89 -4.28284266128652e-89 -3.12348636878342e-89 -2.27647117848759e-89 -1.65796028543828e-89 -1.20666235860095e-89 -8.78024001089259e-90 -6.38763319586124e-90 -4.64780145515185e-90 -3.37988410276239e-90 -2.4564691926073e-90 -1.78524266035909e-90 -1.29736329319524e-90 -9.42190757329699e-91 -6.83919032868829e-91 -4.96211251517922e-91 -3.59999844681108e-91 -2.61164345289453e-91 -1.89423654838956e-91 -1.37325043164835e-91 -9.95102324024839e-92 -7.2102557573781e-92 -5.22397234763176e-92 -3.78394676672352e-92 -2.7398597341673e-92 -1.98315556182867e-92 -1.43604753847271e-92 -1.04030385290276e-92 -7.53793698439867e-93 -5.46419562890792e-93 -3.96257199775551e-93 -2.87330129580263e-93 -2.08324699164491e-93 -1.51035000500736e-93 -1.09491216259481e-93 -7.93684596819201e-94 -5.7530818024955e-94 -4.17002491858914e-94 -3.02150677646218e-94 -2.18920349122709e-94 -1.5860909046712e-94 -1.14881458402838e-94 -8.31871629864453e-95 -6.02133440662324e-95 -4.3540818073609e-95 -3.14543922348861e-95 -2.27164590904887e-95 -1.64013431289124e-95 -1.18408648273423e-95 -8.55059854842465e-96 -6.1761319938762e-96 -4.46143808529961e-96 -3.22308214214701e-96 -2.32714986004946e-96 -1.67984339322278e-96 -1.21229681566162e-96 -8.74815270589798e-97 -6.31237811695182e-97 -4.55121147522564e-97 -3.28009383514898e-97 -2.36307198061527e-97 -1.70171499569953e-97 -1.22496100292769e-97 -8.81624360378336e-98 -6.34253806089115e-98 -4.56107458287235e-98 -3.27769481140874e-98 -2.3538401754873e-98 -1.68970551914725e-98 -1.21212051019537e-98 -8.6894267277736e-99 -6.22578625987189e-99 -4.4582382551706e-99 -3.19098033431089e-99 -2.28336685622853e-99 -1.6335122556965e-99 -1.16854889165433e-99 -8.35893681739743e-100 -5.97748481641265e-100 -4.27241324873174e-100 -3.05226866779559e-100 -2.18017874197092e-100 -1.55698651693743e-100 -1.11178867319856e-100 -7.93936916919939e-101 -5.66991469261183e-101 -4.04846199173809e-101 -2.89021436368992e-101 -2.06319950105732e-101 -1.47309922970458e-101 -1.05196473250705e-101 -7.50812250333635e-102 -5.35587683796911e-102 -3.81858181955706e-102 -2.72099643190647e-102 -1.93783363546622e-102 -1.37981753741517e-102 -9.82306716980677e-103 -6.99196135527698e-103 -4.97463195660991e-103 -3.53785176268005e-103 -2.51544095143159e-103 -1.78808714614718e-103 -1.27080739158689e-103 -9.02831628637332e-104 -6.41173770666913e-104 -4.55525087367282e-104 -3.23752082135152e-104 -2.30114843040874e-104 -1.6358878624493e-104 -1.16315632552686e-104 -8.26643792162726e-105 -5.8722092119955e-105 -4.17057418864849e-105 -2.96105271463606e-105 -2.10163693571554e-105 -1.49080646433381e-105 -1.05692739634413e-105 -7.4896117176218e-106 -5.30550021708576e-106 -3.75709085306766e-106 -2.66056503388381e-106 -1.88405731158175e-106 -1.33400469982513e-106 -9.44734930913337e-107 -6.69191465839065e-107 -4.73804616238218e-107 -3.35322977139575e-107 -2.37232832855368e-107 -1.67785259886125e-107 -1.1863294687493e-107 -8.39099085716433e-108 -5.93709500583869e-108 -4.19908517047316e-108 -2.96931798643673e-108 -2.09934319709762e-108 -1.48393886923852e-108 -1.04871679301041e-108 -7.41289701839961e-109 -5.23986510916708e-109 -3.70386881882562e-109 -2.61701412980352e-109 -1.84832324262024e-109 -1.30557581386041e-109 -9.22324579409651e-110 -6.51661822133596e-110 -4.60072602802961e-110 -3.24568742298757e-110 -2.28868757916603e-110 -1.61292968802172e-110 -1.13606133360446e-110 -7.99911374951917e-111 -5.63042342460536e-111 -3.96170134621329e-111 -2.78599789817476e-111 -1.95815154021765e-111 -1.37566254834832e-111 -9.66016500058718e-112 -6.78357561737643e-112 -4.76199726708643e-112 -3.34180621621541e-112 -2.34428392745325e-112 -1.64392445242037e-112 -1.15269118309575e-112 -8.08479494913189e-113 -5.67214519126712e-113 -3.9790573791073e-113 -2.79106532150105e-113 -1.95775935918604e-113 -1.37280933206399e-113 -9.62338439323799e-114 -6.74414454178874e-114 -4.72510921480704e-114 -3.30950235968519e-114 -2.31680950563006e-114 -1.62107196213828e-114 -1.13430451120302e-114 -7.93730431818553e-115 -5.5526632389644e-115 -3.88431072433042e-115 -2.71714258922749e-115 -1.89976959964296e-115 -1.3276592556523e-115 -9.27887223580031e-116 -6.48649570288376e-116 -4.53554312453463e-116 -3.16874641928909e-116 -2.21205582360529e-116 -1.54372601456866e-116 -1.07700562801781e-116 -7.51180120995785e-117 -5.23787057438138e-117 -3.65135818300393e-117 -2.54398719744871e-117 -1.77175953270922e-117 -1.23347418493249e-117 -8.58630788786129e-118 -5.97635623694521e-118 -4.15777624855569e-118 -2.89051866865554e-118 -2.00812392071262e-118 -1.39489808523836e-118 -9.68801159337348e-119 -6.72702645625162e-119 -4.67193603703366e-119 -3.24529714513262e-119 -2.25410693398927e-119 -1.56552208001978e-119 -1.08701688405366e-119 -7.54438911215556e-120 -5.2339447966639e-120 -3.63052071183602e-120 -2.51794597573137e-120 -1.74630546866593e-120 -1.21090219592468e-120 -8.39491914614617e-121 -5.81779720531031e-121 -4.03033481426739e-121 -2.79155019522608e-121 -1.93292315192808e-121 -1.33799220540546e-121 -9.25948600939117e-122 -6.4064677129595e-122 -4.42989609490848e-122 -3.06127098391015e-122 -2.11422964004647e-122 -1.45984778212712e-122 -1.00779433811965e-122 -6.95418983721709e-123 -4.79462348972107e-123 -3.30299161287711e-123 -2.27395329368404e-123 -1.56453742103973e-123 -1.07648739759429e-123 -7.40582995499123e-124 -5.09428449777801e-124 -3.50205436327291e-124 -2.40603411757695e-124 -1.65267240725047e-124 -1.13517830687799e-124 -7.7971360642112e-125 -5.35242759044128e-125 -3.672144194278e-125 -2.51933354451007e-125 -1.72899551584713e-125 -1.1869740919992e-125 -8.14720252487984e-126 -5.59112452298193e-126 -3.83551370618845e-126 -2.63111080591733e-126 -1.80487588853709e-126 -1.2380101209659e-126 -8.49125180368472e-127 -5.81905380596316e-127 -3.98522116138163e-127 -2.72760280650724e-127 -1.86608043885625e-127 -1.27616404827414e-127 -8.72770340933741e-128 -5.96973639716129e-128 -4.08386464573995e-128 -2.79329723339164e-128 -1.91027447461602e-128 -1.30640107445401e-128 -8.92969345300577e-129 -6.10075172079083e-129 -4.16854107106213e-129 -2.84864449138889e-129 -1.94619978220205e-129 -1.32909966520825e-129 -9.0730844162063e-130 -6.19214879864831e-130 -4.22494621537723e-130 -2.88117209846212e-130 -1.96398915703765e-130 -1.33824965065632e-130 -9.11976632871622e-131 -6.215534322776e-131 -4.2322935083465e-131 -2.8792584030636e-131 -1.95706589030482e-131 -1.32986066424634e-131 -9.0341547919778e-132 -6.13529720976994e-132 -4.16531679989927e-132 -2.82702705929868e-132 -1.91747427582551e-132 -1.29973894619922e-132 -8.80788029316706e-133 -5.96661096083878e-133 -4.04046109656944e-133 -2.73471748189576e-133 -1.85003521063803e-133 -1.25110351734018e-133 -8.45641497065191e-134 -5.71303342486999e-134 -3.86043500939924e-134 -2.60911558399167e-134 -1.76228589869544e-134 -1.18987999400598e-134 -8.03118261742498e-135 -5.42262344155577e-135 -3.66260107349756e-135 -2.47309050437115e-135 -1.66961825187898e-135 -1.1270014272823e-135 -7.60755093989542e-136 -5.13545784367343e-136 -3.4653754970927e-136 -2.33749250075076e-136 -1.57610482974569e-136 -1.06236228337892e-136 -7.15843883603917e-137 -4.8216700822488e-137 -3.24474972437591e-137 -2.18163447053986e-137 -1.46620759022795e-137 -9.84982056405534e-138 -6.61728180873572e-138 -4.4474593333976e-138 -2.99034413251204e-138 -2.00959390888243e-138 -1.34983603397252e-138 -9.06200215611362e-139 -6.07921463622388e-139 -4.0753170163307e-139 -2.72887489512425e-139 -1.82527965847242e-139 -1.22056757320389e-139 -8.15484113410199e-140 -5.44380588589966e-140 -3.63432959149732e-140 -2.4265031227779e-140 -1.61985707603547e-140 -1.0810562650737e-140 -7.21274533926211e-141 -4.81049363176261e-141 -3.20716649724122e-141 -2.1378916876615e-141 -1.42500708391844e-141 -9.4976845910212e-142 -6.32799459796449e-142 -4.21471129260106e-142 -2.80635411245556e-142 -1.86927363219913e-142 -1.24553426465672e-142 -8.30159422204991e-143 -5.53462116579546e-143 -3.6889165814671e-143 -2.458655470984e-143 -1.63864910649148e-143 -1.09119564952486e-143 -7.26038262701111e-144 -4.82857989661866e-144 -3.21108885816767e-144 -2.13530648617419e-144 -1.41892460149483e-144 -9.42236117448488e-145 -6.25474176746065e-145 -4.14883414865306e-145 -2.7499237955617e-145 -1.82186103591084e-145 -1.20647116002541e-145 -7.98686742259844e-146 -5.28611244344985e-146 -3.49784792895896e-146 -2.31409649766682e-146 -1.5306706756396e-146 -1.01220898154647e-146 -6.69717572632995e-147 -4.43343690275585e-147 -2.9326447954962e-147 -1.93847056592061e-147 -1.28030568827531e-147 -8.45133846778222e-148 -5.57574610189832e-148 -3.67688772505742e-148 -2.42362126352595e-148 -1.5974065569734e-148 -1.05289725735241e-148 -6.94028075028907e-149 -4.57241756504861e-149 -3.01092723239103e-149 -1.98121500577936e-149 -1.30275894637999e-149 -8.56066652626652e-150 -5.62421068257256e-150 -3.69428184874405e-150 -2.42530407129039e-150 -1.59127380872079e-150 -1.04345802453283e-150 -6.84078808052147e-151 -4.48376282576094e-151 -2.93748117254309e-151 -1.92360925847301e-151 -1.25914241586317e-151 -8.23981653633253e-152 -5.39075605407803e-152 -3.52546608139062e-152 -2.30406756471686e-152 -1.50485755329455e-152 -9.82769743423296e-153 -6.41751724580652e-153 -4.19119067138696e-153 -2.73674514650603e-153 -1.78674006536142e-153 -1.16616596780769e-153 -7.60915459763069e-154 -4.965048642071e-154 -3.23987905648791e-154 -2.1142340465043e-154 -1.37935458524531e-154 -8.99708146404869e-155 -5.86840804980961e-155 -3.82661918637241e-155 -2.49454517999704e-155 -1.62545489690812e-155 -1.05869965886198e-155 -6.89507148325155e-156 -4.49155170798094e-156 -2.92647086362396e-156 -1.90582362539655e-156 -1.24056418077007e-156 -8.07039056743147e-157 -5.24703588189036e-157 -3.4094660781809e-157 -2.21435682307326e-157 -1.43749110936168e-157 -9.32893032576515e-158 -6.05045070897297e-158 -3.92176850063905e-158 -2.54189886904639e-158 -1.64747381924304e-158 -1.06731475065777e-158 -6.9093716333423e-159 -4.46958727950029e-159 -2.8912859877186e-159 -1.87029859057704e-159 -1.20970026805585e-159 -7.82457392408679e-160 -5.0612820955262e-160 -3.27364000345383e-160 -2.11725893524931e-160 -1.36942890255037e-160 -8.85685860507317e-161 -5.72791590282036e-161 -3.70316345105214e-161 -2.39339184222028e-161 -1.54618622569098e-161 -9.98631158915935e-162 -6.44834192312942e-162 -4.16239956715173e-162 -2.68594911740107e-162 -1.73307427306466e-162 -1.11805701897001e-162 -7.21176339654802e-163 -4.65307605363816e-163 -3.00301564569614e-163 -1.93712564773744e-163 -1.24922681441669e-163 -8.05402023054852e-164 -5.19249110256613e-164 -3.34758689753402e-164 -2.15742435889821e-164 -1.39022944386019e-164 -8.95750977401961e-165 -5.76609399002278e-165 -3.70836581770628e-165 -2.38425239342153e-165 -1.53276081107102e-165 -9.85261841108849e-166 -6.33319284311572e-166 -4.07088569539484e-166 -2.61503484106092e-166 -1.67907334369743e-166 -1.07763673043104e-166 -6.91418692017075e-167 -4.43487092594282e-167 -2.84270025657423e-167 -1.82105446263502e-167 -1.16591072267495e-167 -7.45999446253491e-168 -4.77036498659028e-168 -3.0488284122047e-168 -1.94703823447499e-168 -1.24247364554382e-168 -7.92875702511795e-169 -5.05975410275595e-169 -3.22994449980965e-169 -2.06261515309974e-169 -1.31763579990576e-169 -8.41541743216101e-170 -5.37357231234456e-170 -3.43065427592549e-170 -2.18959758154555e-170 -1.39710824221905e-170 -8.91276897923019e-171 -5.68480713805411e-171 -3.62562416639413e-171 -2.31213562198514e-171 -1.47438045232861e-171 -9.39878141462472e-172 -5.98969012358461e-172 -3.81563474043128e-172 -2.42914710779416e-172 -1.54551984234078e-172 -9.83015454691568e-173 -6.25052162054771e-173 -3.97360021486537e-173 -2.52499237989165e-173 -1.60380207706455e-173 -1.01861485250198e-173 -6.46904119149387e-174 -4.10597236427462e-174 -2.60478560557688e-174 -1.65164012121707e-174 -1.0467067264883e-174 -6.62992771103162e-175 -4.1997759194685e-175 -2.65977133974148e-175 -1.68409851553914e-175 -1.0664421574037e-175 -6.75388377154442e-176 -4.27578529765057e-176 -2.70617143290248e-176 -1.7122873154741e-176 -1.0829401338219e-176 -6.84613688957465e-177 -4.32851558252062e-177 -2.73526442787431e-177 -1.72756561363974e-177 -1.09065356205432e-177 -6.88276102221657e-178 -4.34151069463623e-178 -2.7371879916693e-178 -1.724890097713e-178 -1.08636918958707e-178 -6.83850104743621e-179 -4.30396385849067e-179 -2.70888142679449e-179 -1.70500603827393e-179 -1.07242131940324e-179 -6.74090751220085e-180 -4.23507978602193e-180 -2.66039809866813e-180 -1.67100003697304e-180 -1.04870728881695e-180 -6.57645000476178e-181 -4.12456257973347e-181 -2.58664385612572e-181 -1.62207098971673e-181 -1.01692900506093e-181 -6.37387514954995e-182 -3.99431185617861e-182 -2.50196402883542e-182 -1.56649097932337e-182 -9.80296915932238e-183 -6.1316572658701e-183 -3.83285906096997e-183 -2.39383808375133e-183 -1.4938454936194e-183 -9.31920257583769e-184 -5.81191654371431e-184 -3.6230494649328e-184 -2.25804903561754e-184 -1.40702190065697e-184 -8.76404679744378e-185 -5.45696277934292e-185 -3.39834480434021e-185 -2.11710577777684e-185 -1.31938916452182e-185 -8.21698115894669e-186 -5.11411390834898e-186 -3.18080136135631e-186 -1.97706777264295e-186 -1.22810328925807e-186 -7.62947945358447e-187 -4.74025343773118e-187 -2.94481357300974e-187 -1.82944377677173e-187 -1.13654464634147e-187 -7.05380661707654e-188 -4.37364799336243e-188 -2.71023458640094e-188 -1.67885830052419e-188 -1.0396118399046e-188 -6.43624620888177e-189 -3.98384569970491e-189 -2.46420280195264e-189 -1.52305350698326e-189 -9.40653527330661e-190 -5.80725430076903e-190 -3.58381095490442e-190 -2.21134261392318e-190 -1.36362291732509e-190 -8.40367336632712e-191 -5.17876881119659e-191 -3.19130496657567e-191 -1.96555846597694e-191 -1.20963623249623e-191 -7.43851475869399e-192 -4.57389315374622e-192 -2.8122668644487e-192 -1.72920057376268e-192 -1.06317138621603e-192 -6.53630906819012e-193 -4.01977933113622e-193 -2.47291601573194e-193 -1.52139267476702e-193 -9.35995722403412e-194 -5.75848570174436e-194 -3.54169132299494e-194 -2.17764091346859e-194 -1.33906315577097e-194 -8.23367886085409e-195 -5.06252027268038e-195 -3.11273237586042e-195 -1.91390388888746e-195 -1.1770821590746e-195 -7.23950384802847e-196 -4.452736050366e-196 -2.73673328682358e-196 -1.68087564741966e-196 -1.03210538956615e-196 -6.33424903577868e-197 -3.885584880193e-197 -2.38306145720729e-197 -1.46128629133925e-197 -8.95463310610582e-198 -5.48181060897467e-198 -3.35256905899895e-198 -2.05119147628358e-198 -1.25546753465533e-198 -7.68051505481179e-199 -4.69885085846869e-199 -2.8748169271635e-199 -1.75772575892126e-199 -1.07404801859333e-199 -6.56102120758101e-200 -4.00491200774463e-200 -2.44286227193483e-200 -1.49018745555162e-200 -9.09115272338747e-201 -5.54713224347327e-201 -3.38374933531344e-201 -2.06353906093349e-201 -1.25896143638818e-201 -7.6841008029615e-202 -4.6883717129163e-202 -2.8595222688843e-202 -1.74346476909343e-202 -1.06237901904462e-202 -6.46995039673087e-203 -3.93772888622245e-203 -2.394358815027e-203 -1.45460130556811e-203 -8.83804890952125e-204 -5.37064046820015e-204 -3.26303555044588e-204 -1.98149641877426e-204 -1.20267505630047e-204 -7.29449887452475e-205 -4.42124855711109e-205 -2.67869900053916e-205 -1.62192058125293e-205 -9.8145672825097e-206 -5.936755534251e-206 -3.58979548789992e-206 -2.17022652955637e-206 -1.31162331914957e-206 -7.92477720977231e-207 -4.7866687116552e-207 -2.89036859832165e-207 -1.74461242009124e-207 -1.05244824462106e-207 -6.34551688129392e-208 -3.82649702321672e-208 -2.30782666963006e-208 -1.39112635750929e-208 -8.38398889531947e-209 -5.05195166408577e-209 -3.04402411408159e-209 -1.83408425711557e-209 -1.10450699212566e-209 -6.64717214432634e-210 -3.99791975759617e-210 -2.40302131294959e-210 -1.44350015217601e-210 -8.66601922232746e-211 -5.20118923938227e-211 -3.12083442801588e-211 -1.87203411812584e-211 -1.12263030598902e-211 -6.73037656974068e-212 -4.03330915576714e-212 -2.41607171502439e-212 -1.44708061926635e-212 -8.66589683184383e-213 -5.18950298007583e-213 -3.10719316809331e-213 -1.86013457408111e-213 -1.11337238742452e-213 -6.66285199724846e-214 -3.98625393977263e-214 -2.38403326985308e-214 -1.42530603734408e-214 -8.52037398547415e-215 -5.09291651231445e-215 -3.04368161032831e-215 -1.8180098054029e-215 -1.08533971120825e-215 -6.47904368193075e-216 -3.86753180026747e-216 -2.30743778506589e-216 -1.37561866672907e-216 -8.19499786597027e-217 -4.87993767999629e-217 -2.90469875648633e-217 -1.72871169794392e-217 -1.02863756282337e-217 -6.11961722066142e-218 -3.6399946083831e-218 -2.16468977790525e-218 -1.28758034207228e-218 -7.6594068605516e-219 -4.55678054069287e-219 -2.71104727288066e-219 -1.61299438395507e-219 -9.59458409633221e-220 -5.70575029938616e-220 -3.39232185379161e-220 -2.01629560101635e-220 -1.19808923808196e-220 -7.11974011523651e-221 -4.23270956460152e-221 -2.51737537894431e-221 -1.49633778916794e-221 -8.88938692807573e-222 -5.2810022549471e-222 -3.13722794262489e-222 -1.86364237820738e-222 -1.10693877755208e-222 -6.5740336730682e-223 -3.90025590004564e-223 -2.31130371729487e-223 -1.36816666034625e-223 -8.09276379106023e-224 -4.7834495695614e-224 -2.82566692470333e-224 -1.66804114643127e-224 -9.84030056328262e-225 -5.80146019375949e-225 -3.4182423479387e-225 -2.0129289678096e-225 -1.18546506247616e-225 -6.98206854491528e-226 -4.10960771777617e-226 -2.4173913021495e-226 -1.42164131341596e-226 -8.36262418623218e-227 -4.92042559032745e-227 -2.89293133073953e-227 -1.69965050212108e-227 -9.98286292372232e-228 -5.85809060389387e-228 -3.43459260391878e-228 -2.01267162037794e-228 -1.17884578953388e-228 -6.90341766792218e-229 -4.04147817752722e-229 -2.36532323423971e-229 -1.38441731295899e-229 -8.10345858308548e-230 -4.74399160641945e-230 -2.7775317007142e-230 -1.62635688535281e-230 -9.51878795485114e-231 -5.56882150218252e-231 -3.25784413494852e-231 -1.9053963190644e-231 -1.11412250318681e-231 -6.51265481416241e-232 -3.80597158537844e-232 -2.22277413867192e-232 -1.29700210846133e-232 -7.56160434200195e-233 -4.40735389505427e-233 -2.56824929405319e-233 -1.49600929104841e-233 -8.71188911032092e-234 -5.07196410637903e-234 -2.95295481319439e-234 -1.71931352727504e-234 -1.00087358894355e-234 -5.82752577092336e-235 -3.39366452845227e-235 -1.97643309276921e-235 -1.15112968478502e-235 -6.70223197646194e-236 -3.90020294809853e-236 -2.26848214559562e-236 -1.31902816551173e-236 -7.66740456452377e-237 -4.45327125904044e-237 -2.58438688480387e-237 -1.4986318726388e-237 -8.6859954604701e-238 -5.03198058219869e-238 -2.91330113055726e-238 -1.68618864844003e-238 -9.75677640506218e-239 -5.64246511525953e-239 -3.26138466255807e-239 -1.88416781388087e-239 -1.08752828121687e-239 -6.27159107902639e-240 -3.61663241355454e-240 -2.08555770530986e-240 -1.20225625897321e-240 -6.93096433931804e-241 -3.99588354994865e-241 -2.30378396325419e-241 -1.32825521204434e-241 -7.65791112321666e-242 -4.41683845276133e-242 -2.5484802272364e-242 -1.4695333318673e-242 -8.46866944323854e-243 -4.87908331390307e-243 -2.80908341208497e-243 -1.61623409348786e-243 -9.29035481584846e-244 -5.33533735220767e-244 -3.06466504111859e-244 -1.76159945259656e-244 -1.01327312882159e-244 -5.82296757253302e-245 -3.34328579706625e-245 -1.91911939967586e-245 -1.10084222007503e-245 -6.31034215255803e-246 -3.61549580102591e-246 -2.07051078300034e-246 -1.18510921702266e-246 -6.78096824367913e-247 -3.87867322572245e-247 -2.21834412047714e-247 -1.26862018340892e-247 -7.25023032513905e-248 -4.14132206615301e-248 -2.36429346033354e-248 -1.34902939073695e-248 -7.6932090045173e-249 -4.38597246365949e-249 -2.4998495219473e-249 -1.42447910764195e-249 -8.11187761659386e-250 -4.61656782913807e-250 -2.62702486850639e-250 -1.49414330940312e-250 -8.49397889490337e-251 -4.82687149863317e-251 -2.74196671784288e-251 -1.55589585898459e-251 -8.82248473879724e-252 -4.99923708280186e-252 -2.83264478840825e-252 -1.60493812695678e-252 -9.08492992351119e-253 -5.1371889284273e-253 -2.90191574898323e-253 -1.63757978885126e-253 -9.23193511385095e-254 -5.20136334942737e-254 -2.92825610832578e-254 -1.64732605259423e-254 -9.26406422907188e-255 -5.20812057780018e-255 -2.92689134279617e-255 -1.6438254338141e-255 -9.22652122803335e-256 -5.17682996017291e-256 -2.90361946938239e-256 -1.62876210335531e-256 -9.13812066326359e-257 -5.12786558007282e-257 -2.87694569093921e-257 -1.6137864885693e-257 -9.04861224527625e-258 -5.07254461337844e-258 -2.84303403329586e-258 -1.592245004444e-258 -8.91087676481315e-259 -4.98518327363307e-259 -2.78847504902914e-259 -1.5594848284567e-259 -8.71624060825333e-260 -4.86878103008362e-260 -2.71953904968626e-260 -1.51902418980379e-260 -8.48457669715539e-261 -4.73799035073978e-261 -2.64521641028079e-261 -1.47598665800316e-261 -8.22866032432321e-262 -4.58367339607217e-262 -2.55351757053155e-262 -1.42267300867239e-262 -7.92752857727849e-263 -4.42000230050126e-263 -2.46577290729615e-263 -1.37550543417047e-263 -7.67277200503669e-264 -4.27810187926503e-264 -2.38462868187423e-264 -1.32882088783046e-264 -7.40324376995329e-265 -4.12374366400936e-265 -2.29669583567873e-265 -1.27919605206175e-265 -7.12513866191848e-266 -3.96766010756382e-266 -2.20884527114327e-266 -1.22924223831218e-266 -6.83730506499724e-267 -3.80115578121925e-267 -2.11273222523226e-267 -1.17402059268509e-267 -6.52199352255757e-268 -3.62374204889119e-268 -2.01375063247542e-268 -1.11851910720703e-268 -6.20980427693185e-269 -3.44500695337403e-269 -1.91022427751837e-269 -1.05868903714005e-269 -5.86313575775684e-270 -3.24473833129604e-270 -1.79645199516879e-270 -9.95063311813191e-271 -5.51417297618067e-271 -3.05637392744002e-271 -1.69444498587507e-271 -9.39105327970829e-272 -5.20341674140558e-272 -2.88240482055737e-272 -1.59558485020081e-272 -8.82659925621082e-273 -4.87770532913072e-273 -2.69325474621635e-273 -1.48590402636126e-273 -8.19438170496346e-274 -4.51710934945645e-274 -2.48816596005561e-274 -1.3695946889966e-274 -7.53371239598702e-275 -4.14320401290198e-275 -2.27812732718254e-275 -1.25183828767752e-275 -6.87577631559954e-276 -3.77490216725418e-276 -2.07169960273889e-276 -1.13655697120182e-276 -6.23566883869868e-277 -3.42283869995392e-277 -1.87973433203194e-277 -1.03146242629855e-277 -5.65547125551284e-278 -3.10250338976914e-278 -1.70295298143698e-278 -9.35263322557239e-279 -5.13349038283066e-279 -2.81609848039124e-279 -1.54407876380257e-279 -8.45992212197081e-280 -4.63179469380964e-280 -2.53604941509102e-280 -1.3886481258505e-280 -7.59937299896023e-281 -4.15640958181438e-281 -2.27207367973407e-281 -1.24161589727388e-281 -6.78294586007129e-282 -3.70285119620203e-282 -2.01978758510529e-282 -1.10087523394172e-282 -6.0000828958326e-283 -3.27012960280917e-283 -1.78189647576772e-283 -9.70593414140779e-284 -5.28488733580973e-284 -2.87673263651996e-284 -1.56543120678238e-284 -8.52143314040527e-285 -4.6415210329187e-285 -2.5297073336653e-285 -1.37788184791833e-285 -7.50057381780907e-286 -4.08138178394784e-286 -2.22031161486893e-286 -1.20758871573862e-286 -6.5627805615521e-287 -3.56394882064898e-287 -1.93408110649712e-287 -1.04912428899636e-287 -5.68846625486017e-288 -3.0822292093128e-288 -1.66896103149677e-288 -9.03276511846157e-289 -4.88500137656344e-289 -2.63990970884161e-289 -1.42584222613621e-289 -7.69698026989105e-290 -4.15319916038862e-290 -2.24073609741368e-290 -1.20878012763166e-290 -6.51501555911665e-291 -3.50838922299027e-291 -1.88868429279851e-291 -1.01599134243151e-291 -5.46148148775006e-292 -2.93470411369763e-292 -1.57636935025978e-292 -8.4633667195848e-293 -4.54109331765921e-293 -2.43511287479553e-293 -1.30541180875972e-293 -6.99602123916625e-294 -3.74928656493042e-294 -2.00864919615675e-294 -1.07577934311784e-294 -5.7621511931605e-295 -3.08665945489244e-295 -1.6530857500423e-295 -8.84721463233677e-296 -4.73186452850491e-296 -2.52983359612055e-296 -1.35204733755292e-296 -7.22709099256322e-297 -3.86271389901649e-297 -2.0643423177834e-297 -1.10268305572325e-297 -5.88718100664296e-298 -3.14054879328544e-298 -1.67470423919107e-298 -8.92712189948023e-299 -4.75830742461394e-299 -2.53608428410263e-299 -1.3517065975269e-299 -7.20109116009931e-300 -3.83458792447378e-300 -2.04101140634636e-300 -1.08588952207613e-300 -5.77488558385282e-301 -3.06961535549411e-301 -1.63085438818901e-301 -8.66267492120776e-302 -4.6004333101844e-302 -2.44322130458477e-302 -1.29724771926923e-302 -6.88626296209776e-303 -3.6555574368791e-303 -1.94059154894853e-303 -1.02989391170613e-303 -5.46245088817947e-304 -2.89553206292429e-304 -1.53450124205301e-304 -8.13033791760223e-305 -4.30622224414658e-305 -2.28113792315039e-305 -1.20857431149639e-305 -6.39936085588442e-306 -3.38649298900586e-306 -1.79090228149934e-306 -9.46153225157634e-307 -4.99381858115272e-307 -2.63379294850599e-307 -1.38809407719451e-307 -7.31194013371331e-308 -3.84994396524479e-308 -2.02624233607336e-308 -1.06583598813093e-308 -5.60350627618205e-309 -2.94480882044733e-309 -1.54800575813914e-309 -8.13962326444285e-310 -4.27913649918687e-310 -2.24922002102561e-310 -1.18201653692394e-310 -6.20981162043418e-311 -3.26138487683209e-311 -1.71240413344539e-311 -8.98868291714956e-312 -4.71784468158147e-312 -2.47748791128151e-312 -1.30165119200026e-312 -6.83591196803156e-313 -3.58858932641026e-313 -1.88397409697329e-313 -9.88425291275026e-314 -5.18250939236017e-314 -2.71516660817802e-314 -1.42142590509198e-314 -7.43634378770839e-315 -3.88798442774835e-315 -2.0315555893327e-315 -1.06093282308455e-315 -5.5374606837913e-316 -2.88911976247687e-316 -1.50587226683306e-316 -7.84137663522086e-317 -4.07999558555395e-317 -2.12129654183298e-317 -1.10270807934695e-317 -5.73043027460261e-318 -2.97705677755039e-318 -1.54608950684393e-318 -8.02668929546606e-319 -4.16373823032711e-319 -2.15901746576166e-319 -1.11910809439501e-319 -5.79489596007198e-320 -2.99799033896468e-320 -1.54988393100399e-320 -8.00880411908661e-321 -4.13038879923282e-321 -2.13436359003419e-321 -1.10176639022598e-321 -5.68175492717434e-322 -2.96439387504748e-322 -1.53160350210786e-322 -7.90505033345994e-323 -4.44659081257122e-323 -1.97626258336499e-323 -1.48219693752374e-323 -9.88131291682493e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -4.94065645841247e-324 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 diff --git a/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_references_Gemini_Portugal_October_2023.csv b/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_references_Gemini_Portugal_October_2023.csv deleted file mode 100644 index 884dc978a7239a3442b3c1fab1e22e0bbb93ae28..0000000000000000000000000000000000000000 --- a/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_references_Gemini_Portugal_October_2023.csv +++ /dev/null @@ -1,302 +0,0 @@ -Heights,Vz_closed_m26,Vz_closed_m26_4,Vz_closed_m26_8,Vz_closed_m27_2,Vz_closed_m27_6,Vz_closed_m28,Vz_closed_m28_4,Vz_closed_m28_8,Vz_closed_m29_2,Vz_closed_m29_6,Vz_closed_m30,Vz_open_m26,Vz_open_m26_4,Vz_open_m26_8,Vz_open_m27_2,Vz_open_m27_6,Vz_open_m28,Vz_open_m28_4,Vz_open_m28_8,Vz_open_m29_2,Vz_open_m29_6,Vz_open_m30 -0,291.697688278318,290.829077875845,289.990532647539,289.182107830101,288.400431198465,287.645068077735,286.914805317672,286.207536847051,285.523113265711,284.860132271709,284.217060865029,521.120565192786,516.075462318736,510.438944020476,505.673314279408,501.011831601148,495.893395461229,491.462437549768,486.660814948149,482.432419304485,478.278547728422,473.862370607181 -10,290.984535447996,290.122172054902,289.290629334632,288.487638116439,287.711921016228,286.962205130311,286.236902974706,285.535077414886,284.855479592315,284.196954575389,283.558695560262,518.991801421389,513.951767963176,508.336075559748,503.571309337535,498.910275275413,493.810993067849,489.379712617304,484.596148511444,480.366734302352,476.211500029465,471.812107673286 -20,290.272554676878,289.417015425694,288.591524150995,287.794369522951,287.024564629671,286.280179676493,285.560162939834,284.863437411843,284.188599955009,283.534777036889,282.901066213715,516.856699928473,511.816892070643,506.224157422375,501.462198249855,496.80313301355,491.723623806074,487.292182881464,482.52584171389,478.294316452994,474.136178146084,469.75170401644 -30,289.561766863639,288.712681652409,287.893139205481,287.102211933116,286.337866313319,285.598860517744,284.884210042744,284.192348384917,283.522319891926,282.873243011805,282.2438920452,514.721598435556,509.681943626028,504.109073957462,499.346984013761,494.687649597284,489.627258378458,485.195308275166,480.447515471832,476.215266067988,472.056290888838,467.689754885253 -40,288.852030395801,288.009090411237,287.195935188177,286.410695187298,285.65181294685,284.918429532041,284.208788843333,283.521838698171,282.856738052227,282.212144989553,281.5871507165,512.572518503631,507.538901983707,501.990078128675,497.231073804537,492.572166181019,487.530892950843,483.098433668869,478.369038909708,474.134094650682,469.971428207939,465.618663319797 -50,288.143059351263,287.306575566213,286.499447145895,285.719817704691,284.966768428709,284.238547504384,283.533915417412,282.852094250836,282.191606926307,281.551479416948,280.931064826739,510.418971229153,505.385455032326,499.856819982617,495.097632729956,490.439757552511,485.418249444041,480.985124362365,476.273006098312,472.037285712667,467.873729866974,463.539204598359 -60,287.435031702346,286.604955600667,285.80361876589,285.029943027159,284.282290678797,283.559211689187,282.859888206836,282.182815728898,281.526922993916,280.891503985271,280.275356468001,508.26164242241,503.232008080945,497.723561836559,492.964191655374,488.305994721969,483.303921136716,478.870234647171,474.176973286915,469.940476774652,465.776031526009,461.456156906346 -70,286.728110939376,285.904016310454,285.108716919421,284.340728032277,283.598377146192,282.880732817141,282.186342646755,281.513999670143,280.862927897498,280.231924382733,279.62002174664,506.089240058818,501.061378463031,495.576998381722,490.820229779375,486.163323016975,481.180740058117,476.745950078586,472.06956262566,467.829882625219,463.661251221006,459.358814578742 -80,286.021892458837,285.203904889002,284.414616111409,283.65209586107,282.915280133241,282.202794897937,281.513275361756,280.845863306509,280.199370408337,279.572731784548,278.965182967075,503.916837695226,498.889022744504,493.425166355719,488.668161661023,484.010879516332,479.04805822962,474.612653518557,469.95544171111,465.714932467905,461.545357958572,457.261472251139 -90,285.316377182964,284.504762210305,283.72111733734,282.964224486183,282.232818502879,281.525351622756,280.840869547869,280.178216402721,279.53621377455,278.914036336609,278.310782098687,501.731504222196,496.708796715245,491.268700955086,486.513850709671,481.857405085496,476.913799276504,472.476838243683,467.836248290991,463.592104004629,459.417885897606,455.147626991193 -100,284.612028614926,283.806241375245,283.028305908279,282.277101384937,281.550868454993,280.848541071326,280.169016519694,279.510984706648,278.873549246532,278.255813506923,277.656712203669,499.539825001482,494.517109465635,489.0978837954,484.342743242901,479.685867513483,474.762361567924,470.324731338337,465.703646383332,461.458618557657,457.283402422459,453.032015978972 -110,283.908322286167,283.108339356948,282.336376766393,281.590507383385,280.869510195808,280.172359709641,279.49759356929,278.844232814604,278.211400254819,277.597934213897,277.00297036531,497.344824136831,492.325422216025,486.927066635715,482.171635776131,477.51432994147,472.610923859345,468.172624432992,463.571044475673,459.322957317805,455.142624434551,450.904644445322 -120,283.205255534554,282.411426891841,281.644994825122,280.904450122347,280.188872452093,279.496623828556,278.826629706472,278.178048720745,277.54960782467,276.940393608758,276.349727053556,495.133433312379,490.115298470141,484.740754672874,479.986959956721,475.329965091921,470.445848776917,466.005468776384,461.420599655275,457.170530643401,452.989143536112,448.770368161546 -130,282.50308711451,281.715105784861,280.95415627984,280.219221744867,279.50869613773,278.821328872096,278.156296544326,277.512234691857,276.888167092974,276.28336107756,275.696773837399,492.922042487927,487.903843901604,482.550528573838,477.796388238276,473.138907400239,468.275240632425,463.834135778838,459.269112047477,455.018103968997,450.834414906302,446.628828002124 -140,281.801667911645,281.019347001664,280.264118377312,279.534471301906,278.828976782997,278.146715039818,277.486347445279,276.846785866913,276.22723524485,275.626643954136,275.044105740489,490.696668629275,485.682577838891,480.352778261895,475.599793412978,470.942135968601,466.097495740579,461.65382405153,457.105272345394,452.849622088485,448.661516964976,444.475477882792 -150,281.1008305958,280.324320518395,279.574653525184,278.850194443121,278.149911832688,277.472512081307,276.8167775692,276.181840948142,275.566652746908,274.970223737409,274.391774243689,488.46511793058,483.450906592059,478.142706343131,473.389319415815,468.731118934247,463.907289903251,459.462836461792,454.93448202887,450.677835894419,446.48861902365,442.319095057522 -160,280.400637653825,279.629993971235,278.885679483621,278.166533743119,277.47133057719,276.798702896296,276.147699848122,275.517287020983,274.906379396659,274.314141418251,273.739797150309,486.228493346599,481.217891298104,475.932634424368,471.178845418652,466.520101899893,461.716234446234,457.268710736369,452.756591610395,448.494801852423,444.299413213795,440.146250068972 -170,279.701294671578,278.936176071407,278.197269942942,277.483443750756,276.793158194143,276.125366203722,275.479063571649,274.853054954324,274.246440631504,273.658443168417,273.088065832102,483.976320405152,478.965539865484,473.702542206166,468.949353115059,464.289869645841,459.505990427636,455.057626768234,450.566068765502,446.303224979792,442.106665685941,437.97340508042 -180,279.002478787265,278.242861849887,277.509534392015,276.800778293557,276.11542941738,275.452531494382,274.810762358349,274.189148746781,273.586921896077,273.003001790553,272.436574703862,481.724147463705,476.713188432863,471.472173962392,466.718525135607,462.05844031572,457.295746409038,452.846542800098,448.373438683061,444.104932186964,439.901675280017,435.781543214765 -190,278.304185227024,277.550330696212,276.822239615796,276.118531957525,275.438274708529,274.780045558337,274.14279057589,273.525705734919,272.927671562415,272.347811650729,271.785394728316,479.454551687215,474.446625985688,469.228932180325,464.475366110723,459.814016802862,455.070214214563,450.617359442783,446.162740143029,441.893120071231,437.688632156,433.588769335547 -200,277.606610031429,276.858263577897,276.135380289327,275.436914717286,274.761483007308,274.107902768587,273.47529612968,272.862543105237,272.268683957444,271.69293681138,271.134468161814,477.181279431688,472.173116104199,466.977802902002,462.223718186821,457.561707908902,452.839477736434,448.385723462656,443.952041602997,439.678826185846,435.467096158021,431.380166966152 -210,276.909620330855,276.166648858561,275.449113629437,274.755690398112,274.085048710897,273.436225799665,272.808113150259,272.199655156462,271.610012172191,271.038339781219,270.483743941939,474.898664539356,469.892997363922,464.72072358017,459.966185642958,455.302367289329,450.598784057996,446.140837174581,441.723315153173,437.446320289432,433.233297391626,429.167016641793 -220,276.213100610647,275.475577471328,274.763323659928,274.074838303812,273.409061175978,272.764909414153,272.141217284644,271.537079223044,270.951647780515,270.383955506719,269.83321602705,472.603800558107,467.597835374581,462.448353743114,457.693236940578,453.028696632207,448.347086464256,443.888179110438,439.491983839771,435.213814393017,430.994416183029,426.940879549478 -230,275.517059820918,274.785082243284,274.077921314087,273.394405066399,272.733493015012,272.093893075098,271.474624506282,270.874846244708,270.29350697632,269.729777886714,269.182951775553,470.307460055081,465.30267338524,460.175983906057,455.420288238199,450.753674889665,446.090470909099,441.626809920875,437.246561303749,432.961572391933,428.739387090409,424.706891118391 -240,274.82171272541,274.094990631664,273.392900446543,272.714461114381,272.058238351673,271.423170548129,270.808417127517,270.212848126684,269.63558360616,269.075869958168,268.532870144488,467.990495923824,462.986110026064,457.882607021545,453.125840917815,448.458144689095,443.81732854626,439.352644639431,434.994125632891,430.707899606545,426.482320202574,422.4623850352 -250,274.126785845519,273.405296556451,272.708449809811,272.034844647825,271.38329094514,270.752872388411,270.14245634132,269.551078671541,268.977933131465,268.422165010115,267.88294840627,465.673531792567,460.668786198653,455.588501643493,450.831095084557,446.162614488526,441.543991076714,437.073972055534,432.731191860915,428.437567964323,424.205570828753,420.207082123903 -260,273.43227319665,272.716137305278,272.024342074227,271.355549436037,270.708756326526,270.082838729061,269.476735915803,268.889581885578,268.320510263718,267.768629714238,267.233180175921,463.340095398418,458.336647684613,453.279288483466,448.5202339146,443.848733603067,439.248904640641,434.777798705549,430.457165116247,426.162239981063,421.928821454933,417.943330423789 -270,272.738247390128,272.027402462398,271.340570164451,270.676648132464,270.034534437161,269.41305761704,268.811283804856,268.228342295024,267.663267218803,267.115257619198,266.583615875424,461.000505970764,455.996635505007,450.962936445422,446.203178397754,441.530829812458,436.953818204568,432.480959329006,428.175862910846,423.872940427329,419.63045901318,415.666221309441 -280,272.044742814953,271.339018608207,270.657164681517,269.998117180636,269.360577790603,268.743535533207,268.146124234358,267.567293127746,267.006197484494,266.462096652855,265.934182915387,458.65127057735,453.648096700647,448.63706607167,443.875060932814,439.199085091469,434.640457089716,430.162260648487,425.879742583239,421.575453072472,417.331483463991,413.382302540208 -290,271.351605000273,270.650979032165,269.974198011273,269.31986469574,268.686879681535,268.074347999303,267.481166136238,266.906427816928,266.349343914107,265.809084279181,265.284868387449,456.288513235716,451.284852118303,446.297939401685,441.535166259644,436.858276674566,432.322910936517,427.843561967967,423.579170226921,419.26626184561,415.012599629394,411.08287947831 -300,270.658827282562,269.963428352593,269.291523580107,268.641883957194,268.013536529709,267.405373454689,266.816402896338,266.245781008459,265.692659694764,265.156199485578,264.635665645574,453.922631510944,448.919042817371,443.954546708919,439.188904903967,434.507757728438,429.990566697908,425.504587209956,421.26043731761,416.946094379777,412.690875366555,408.777824722146 -310,269.966503330181,269.276199688281,268.609134666897,267.964246231187,267.340433023407,266.736605246243,266.15185718636,265.585328430802,265.036112602816,264.503435555533,263.986602948067,451.536145375146,446.532003450262,441.592099825793,436.825623921675,432.143495895401,427.650028116558,423.162828794852,418.93964592728,414.616039522768,410.350474773329,406.455563237102 -320,269.274581563642,268.58927089732,267.927069649664,267.286895934092,266.66754782805,266.068049577673,265.487535410947,264.925022945688,264.37969585541,263.850819531513,263.337630898988,449.149659239347,444.144964083153,439.229652942667,434.460283189767,429.773243380208,425.297749292189,420.803269030112,416.597764212217,412.272653901052,408.005461870203,404.128353285884 -330,268.582974629793,267.902638402271,267.245349080588,266.609776440362,265.994873900041,265.399753173828,264.823371130067,264.2648577087,263.723433254483,263.198309001446,262.688736784896,446.741928299143,441.736589903981,436.843941776459,432.073050262396,427.38496078036,422.933667736322,418.437898561902,414.25575490623,409.920712365718,405.64249694696,401.782711421941 -340,267.891675380714,267.216418064091,266.563872345745,265.932880673336,265.322484013229,264.731625122843,264.159357443263,263.604850764564,263.06729386886,262.545884979851,262.039913756836,444.331133389775,439.32517419807,434.457610690628,429.685817335024,424.993963394525,420.560452047679,416.056726904515,411.890170159039,407.553552456125,403.273637302319,399.432273752213 -350,267.200770381043,266.530455149956,265.882632346677,265.256262317718,264.650282362245,264.06365847463,263.495503556897,262.94498818147,262.411249952544,261.89354054497,261.391169480478,441.904318252896,436.897041016659,432.051920339639,427.275874000826,422.581073262788,418.172258323749,413.667173333887,409.524585411847,405.178647000026,400.887005100071,397.062691282078 -360,266.510185961775,265.844742552838,265.201657131346,264.579872075959,263.978253406401,263.395849868737,262.831819227989,262.2852304342,261.755294514099,261.241283035297,260.74247824232,439.468614606361,434.460647356738,429.641121808321,424.864104160132,420.16818313105,415.777049559525,411.263307782365,407.136030192172,402.787137757371,398.493721607004,394.68789681321 -370,265.819866035091,265.159274959654,264.520957818512,263.903666326736,263.30638985346,262.728240782365,262.168249526081,261.625570465259,261.099432998246,260.589091520446,260.093825341646,437.021697763097,432.011711330841,427.214417651668,422.432449645892,417.73015977797,413.36415496834,408.848980465945,404.746169362869,400.388133616109,396.082260397478,392.293794401449 -380,265.129803108316,264.474140252046,263.840455322292,263.227637732365,262.634735152878,262.060756558422,261.504787331837,260.966009817216,260.443652786982,259.936946376295,259.445203765819,434.560464494884,429.549717099335,424.778548285076,419.995537692997,415.292055031762,410.945839640421,406.421280484921,402.333643363933,397.971680208288,393.663956064328,389.893454018892 -390,264.440060197535,263.789215233555,263.160142268207,262.551815422004,261.96322912017,261.393390020641,260.841427770469,260.30654862979,259.787927355261,259.28484051619,258.79660792686,432.092371295971,427.078875971681,422.329738642242,417.541053160247,412.830466845898,408.507635068793,403.981568271791,399.918913710364,395.547381524325,391.226441689245,387.474232336979 -400,263.750580678499,263.104492503099,262.480027897729,261.876175277844,261.291851422255,260.726133749202,260.178189234804,259.647151024477,259.13224954476,258.632768650923,258.14802421407,429.604965608517,424.590636551708,419.868173957427,415.07837271459,410.366519129002,406.065038821181,401.528831121062,397.481228332273,393.105368407635,388.782498709209,385.047093160835 -410,263.061316875416,262.419964350752,261.800136004061,261.200674608831,260.620594579627,260.059010182716,259.515023496369,258.987809774023,258.476613175241,257.980720350232,257.499440052208,427.114560602746,422.096725905539,417.396106474007,412.599877314747,407.880156338589,403.600893780176,399.063101385507,395.041016500959,390.654514394909,386.317640659335,382.602131950451 -420,262.372261048453,261.735687838805,261.120395239726,260.525305881423,259.949474410455,259.391976029199,258.851923262196,258.328517454817,257.821013728907,257.328679124255,256.850848289447,424.600316733894,419.58157362422,414.90819989261,410.110779806595,405.389715008208,401.132777529652,396.584058174739,392.576918635716,388.186304334802,383.847419425095,380.146873327645 -430,261.683445809333,261.051584197904,260.440798023814,259.850074355068,259.278466969676,258.725016965189,258.188881037529,257.66927530953,257.165429245428,256.676637746542,256.202241613688,422.086072865043,417.06336285287,412.411657653271,407.607026707573,402.877300405396,398.64203913562,394.091655791379,390.110589688523,385.707565156403,381.353856625769,377.675530408554 -440,260.994850482844,260.367636256453,259.761336527479,259.174983876365,258.607544660365,258.058125427881,257.525898672682,257.010057634902,256.50985242548,256.024588827252,255.553598892973,419.544627833795,414.520605860541,409.89673943913,405.090840310015,400.359691458295,396.147094920836,391.584967236608,387.618757629711,383.212498189762,378.856694685211,375.190759604773 -450,260.306423575181,259.683836135295,259.082045843505,258.499989049415,257.936699855327,257.391301739614,256.862953907957,256.35085582331,255.854275802825,255.372515718959,254.904916872003,417.002855941526,411.976793825682,407.374436783869,402.560512419461,397.819876027173,393.629086815097,389.06521349376,385.125252606899,380.704470523691,376.332990962789,372.692369823294 -460,259.618157164805,259.000206047323,258.402864059875,257.825082186983,257.265928649302,256.724531778613,256.20003360898,255.691662333739,255.198686644694,254.720409509474,254.256189042771,414.435914616953,409.405714906275,404.831812916119,400.016540915465,395.274400960464,391.105933328478,386.529465349485,382.604693055793,378.181862858394,373.805968806575,370.176617388514 -470,258.93005453962,258.316717367152,257.723781206795,257.150255398236,256.595230918324,256.0577953091,255.537130161908,255.032467437014,254.543071820487,254.068264458153,253.60740798483,411.865899595707,406.834635986868,402.282390933487,397.458246273671,392.705759167282,388.559954531165,383.981656796214,380.081292831057,375.643065123916,371.252841112584,367.650491502265 -480,258.242133161705,257.633339113222,257.04478933079,256.475518987411,255.924576148272,255.391084646739,254.874235538139,254.373255928457,253.887425475764,253.416073066936,252.958559143628,409.27209270257,404.234780564351,399.711341910368,394.885767853424,390.131693769013,386.00713230542,381.415354934194,377.53257121215,373.092207971077,368.693298395491,365.10220628103 -490,257.554334259916,256.950063274559,256.365893858026,255.800839060547,255.253956587112,254.724391940888,254.21133541338,253.71402059337,253.2317400358,252.763825413684,252.309617722723,406.673092926047,401.634635871822,397.133363578656,392.29803466624,387.532718484226,383.432455998614,378.838762156147,374.977746614056,370.521075185409,366.111094150961,362.547629775254 -500,256.866649771936,256.266886049725,255.687076890643,255.126204212873,254.583364311473,254.057706940469,253.548419547377,253.054753781532,252.576007788054,252.111490530356,251.660592879102,404.050971343853,399.005574400743,394.533143146876,389.696300649536,384.929311548516,380.84842221676,376.240327259089,372.400130691078,367.941233519292,363.517366273052,359.96517352999 -510,256.179071425476,255.583814805828,255.008315364283,254.451606451008,253.912792037851,253.391014925052,252.885480215848,252.395447701914,251.920198781337,251.45907873107,251.011477083801,401.422217328759,396.375592115945,391.925088091255,387.077571928537,382.298408567138,378.244294451611,373.634193577772,369.812265520399,365.336111751268,360.905319867744,357.455093724086 -520,255.491612941993,254.900809880192,254.329601218851,253.777039039285,253.242223924358,252.724307867906,252.222509550343,251.736079910209,251.264317636031,250.80658240923,250.362262686695,398.770246671263,393.715752860396,389.294921895265,384.445805406555,379.664821172904,375.627417346211,371.001955412785,367.204995645349,362.725790765554,358.562139740762,355.348197134573 -530,254.80424221825,254.217863149985,253.650926225461,253.102490277219,252.571649626302,252.0575778245,251.559491897477,251.076643495073,250.60835874226,250.15399383501,249.7129267839,396.110939655939,391.054941904306,386.655180725547,381.794433180289,377.000362651398,372.99305566828,368.365288319669,364.582380820962,360.085663375322,356.417404465994,353.252393456111 -540,254.116941049339,253.534966317164,252.972286353988,252.427944642911,251.901061124742,251.390814826726,250.896410543287,250.417136468119,249.952314290874,249.501298073655,249.063448120732,393.427494412086,388.36284984906,383.99426487059,379.131827570564,374.332214511475,370.341608472009,365.697686735469,361.944668541655,357.553510846317,354.296432124676,351.175078400194 -550,253.429701072041,252.852115469077,252.293660416161,251.753394045062,251.230450259334,250.723994890922,250.233266095005,249.757550941413,249.296176354702,248.8484607203,248.413841239794,390.736804843449,385.668696431895,381.321133060532,376.446066626894,371.635984767183,367.676200458531,363.024425049035,359.285495776845,355.399919575575,352.182400328728,349.115878760635 -560,252.742514410224,252.169295073575,251.615039235209,251.078830246711,250.559796205452,250.057119779301,249.570050586632,249.097878906633,248.639900564981,248.195501137233,247.764098384764,388.020162038425,382.944268732136,378.628632582783,373.751784134747,368.931415986492,364.988354864159,360.324834659557,356.616522355015,353.259978150606,350.098117929582,347.068068456201 -570,252.055379875809,251.486489660126,250.936414499555,250.404239549638,249.889092990303,249.390181448748,248.906755929144,248.438087341157,247.983507836944,247.542411488323,247.114211692327,385.297227960018,380.214935999433,375.920303847669,371.029785250003,366.202541268844,362.29105656638,357.808821406912,354.399260232196,351.137314015269,348.021765758857,345.045800289188 -580,251.368271078778,250.803690845035,250.257777392541,249.729606329369,249.218334819605,248.723171730173,248.243360191519,247.778177597475,247.326991286202,246.889183828715,246.464161165948,382.545560290619,377.457273696392,373.195351084157,368.302955229069,363.4595798983,359.564875649757,355.603230874743,352.240015989844,349.035622353165,345.967569559375,343.031547422433 -590,250.681179566394,250.120890099958,249.579107520317,249.054926860967,248.54751344508,248.056079187464,247.579845928393,247.118150626477,246.67034288633,246.235809161444,245.813910110824,379.789485623912,374.690812395256,370.449910208707,365.54275783492,360.697151687422,356.877812546097,353.416686222753,350.108572817777,346.943812828319,343.929185229801,341.042113320263 -600,249.99409673583,249.438073589924,248.900400574317,248.380192818114,247.876620497016,247.388869047185,246.916221403899,246.457998320241,246.013554505713,245.582231345332,245.16348601726,377.000854017401,371.898980414652,367.691603059037,362.776676556562,358.238591938618,354.660563862069,351.24346987129,347.988707954534,344.880724895773,341.904841222673,339.065240520618 -610,249.307013259786,248.755227958891,248.221648151675,247.705395749725,247.205625469229,246.721556001355,246.252478428827,245.797712463687,245.356581559388,244.928485971925,244.51288090731,374.208242129888,369.093320764613,364.907018122424,359.981999272286,355.9749349171,352.453533239782,349.096897323424,345.888757179014,342.826004985817,339.904516207286,337.104510448929 -620,248.619912378961,248.072346441901,247.54284172103,247.030517745045,246.534528863012,246.054131779844,245.588608704626,245.137263245373,244.699436329154,244.274564981276,243.86208670485,371.383052267733,366.266345946983,362.114418193569,357.375927861028,353.739140244251,350.269419346282,346.958552408028,343.808587335196,340.795244480765,337.913030082638,335.16489310986 -630,247.932785721418,247.389420428771,246.863972630215,246.355538213215,245.863328766793,245.386588000762,244.924597299995,244.476636255167,244.042121205665,243.620460213729,243.211095239261,368.5502399551,363.419288809556,359.288532132394,355.098049957626,351.511215449331,348.103545396908,344.849789732894,341.739888168349,338.779602829698,335.947352483533,333.234438315107 -640,247.245624600031,246.706441184727,246.185007937019,245.680463309527,245.192016715646,244.718916175861,244.260403121697,243.815845437621,243.384627945387,242.966163413684,242.559851903875,365.688997562073,360.556157804582,356.539105670124,352.840476297135,349.315389753838,345.952455029112,342.752264375336,339.699514299151,336.778853448289,333.994057160077,331.329820650795 -650,246.558420198845,246.023389640157,245.505954714799,245.005284486521,244.520584135817,244.051073881721,243.596051541959,243.154882465053,242.726948207252,242.31163651172,241.908378169887,362.813701394117,358.07750540975,354.246008711818,350.597362638867,347.129845272164,343.828092339714,340.675343241069,337.668349362137,334.802152841558,332.057057505269,329.436465099355 -660,245.871163580697,245.340249714397,244.826806064946,244.329993085172,243.849006570674,243.383072751928,242.931534148769,242.493738910504,242.069061291831,241.656870199237,241.256678187504,359.915354262726,355.73159501216,351.966178869211,348.382804137875,344.967758823777,341.712919882817,338.618689890455,335.661060592562,332.835028657664,330.141626498005,327.559156619376 -670,245.183824700715,244.657023333154,244.147553243614,243.654580340112,243.177263154125,242.714912529256,242.266842428939,241.832406251286,241.410925613854,241.001882535127,240.604743656787,357.32260718315,353.420537615106,349.708700394863,346.1771986137,342.824909685462,339.62705603907,336.573222940984,333.669826368116,330.892917978247,328.235987061237,325.702428142714 -680,244.496407515798,243.973701668469,243.468187397823,242.97899931081,242.505367764573,242.046584614037,241.60196777175,241.170827012,240.752573795882,240.34666513352,239.95256618696,354.958253640362,351.117950070915,347.473166984683,344.003243299432,340.696271806021,337.553860465795,334.557297568576,331.692546673794,328.964554963966,326.354774939281,323.85557052489 -690,243.808904442685,243.290275780156,242.788682034575,242.303272242708,241.833311715744,241.378080307108,240.936874187598,240.509031356764,240.093997365522,239.69120951633,239.300137298627,352.623468030845,348.845037965951,345.251178625487,341.841552086956,338.596190366938,335.50000019761,332.551327106871,329.740890301969,327.050964496887,324.486565633175,322.03120515252 -700,243.121306454657,242.606736620884,242.109022336875,241.627391969393,241.161086219717,240.709385427713,240.271551608894,239.847016545368,239.435187756668,239.035507115515,238.647387836907,350.297592787733,346.588068491621,343.060313750778,339.701723077021,336.506167422886,333.468581549406,330.567304717794,327.799442690578,325.160850064674,322.632388337983,320.22034174233 -710,242.433604414687,241.923040328153,241.429217331709,240.951349614003,240.488682390396,240.040449230509,239.606015679217,239.184773923019,238.776136311819,238.379510576256,237.994361642452,348.008085164846,344.351469128974,340.879398952424,337.583968436858,334.443147221629,331.447650000944,328.601864352275,325.880507175304,323.281048259448,320.800978853921,318.42156035764 -720,241.745776514132,241.23920538233,240.749258053238,240.275136199286,239.816058586825,239.371305855379,238.940257654473,238.522294741972,238.116818638694,237.723222254929,237.341055048766,345.729189579957,342.14045224522,338.727451423805,335.4778183136,332.395975857659,329.456195105124,326.647713871543,323.978161400915,321.42270538191,318.979858035,316.645977843989 -730,241.057801409348,240.555224440028,240.069135432812,239.598735259265,239.143217628455,238.701946468383,238.274268695939,237.859570163593,237.457193427333,237.066657841556,236.687459423309,343.476843175116,339.939902913167,336.591674009833,333.403801552188,330.364962052424,327.476765906696,324.72225219659,322.087479895422,319.580459832752,317.177903945648,314.880556091739 -740,240.369689078822,239.871088341122,239.388840302282,238.922102531394,238.470167128845,238.032362139138,237.608039872387,237.196538574956,236.797296735251,236.409808613365,236.033566045058,341.245222151474,337.774834895347,334.474051997262,331.340592496704,328.360206325315,325.515599925019,322.807515758115,320.223555536362,317.748982703256,315.39272865858,313.131088455255 -750,239.681430271073,239.186787823495,238.708334729357,238.245267141656,237.796898065338,237.362543843013,236.941537147562,236.53323204497,236.137119748541,235.752665757752,235.379366105661,339.029661821691,335.620656133682,332.383155307184,329.300125888697,326.366558674982,323.577059166331,320.911194954742,318.370351952941,315.943331810125,313.618163296168,311.399977152901 -760,238.993015629897,238.502312831033,238.027616389498,237.568219974598,237.123401319153,236.692482463019,236.274739935903,235.86965006035,235.476653562034,235.095220373467,234.724813395315,336.845324052314,333.490583670304,330.303595206886,327.280369776211,324.397651900161,321.649748978644,319.035686994102,316.53420424058,314.148472022709,311.865872492707,309.679234135061 -770,238.30443569757,237.817608922812,237.346693489852,236.89095181662,236.44966767735,236.022113617346,235.607672446967,235.205783622386,234.815889180508,234.437453344742,234.069902825872,334.672333471892,331.382458545804,328.252807850172,325.272246784855,322.445820880983,319.747133871286,317.171380787399,314.718495753322,312.368171217432,310.126201386254,307.976559372075 -780,237.61566492373,237.132708127409,236.665556721415,236.213453358014,235.775664645354,235.351476653399,234.940325587566,234.541623640825,234.154817519677,233.779307397293,233.414656510954,332.52875604073,329.286751272891,326.217762523003,323.294824353252,320.506930200583,317.859873109628,315.330158137077,312.913838302188,310.60904621147,308.397764262136,306.289002002157 -790,236.926679238592,236.447601039962,235.984196676983,235.535715194701,235.101370558986,234.680565756963,234.272690171371,233.877160934885,233.493381841834,233.120829410333,232.759065459875,330.403023144118,327.224163668299,324.199360394516,321.329465581858,318.5961219278,315.985467757623,313.504066141523,311.129488975498,308.860727503621,306.692075701567,304.611889946481 -800,236.237495318523,235.762278155135,235.302603852965,234.857681583719,234.426808353039,234.009371644625,233.604756919973,233.212371072885,232.831599648341,232.462010298004,232.10312059237,328.29446065421,325.173510509683,322.208111931427,319.382469066472,316.696914239036,314.137366949025,311.689474913661,309.361191045715,307.129105042963,304.996879116948,302.953480918199 -810,235.548103559551,235.076729869037,234.620758226245,234.179376911183,233.751968646039,233.337884939232,232.93651646371,232.547209145732,232.169480232087,231.802840883498,231.44681273902,326.215403681309,323.144389118234,320.22895960087,317.459015297307,314.815842006258,312.300733409882,309.900502040529,307.604115421654,305.415307677264,303.314191679415,301.30831584618 -820,234.858494256803,234.39094648083,233.938615799731,233.500800847528,233.076841961013,232.666096170764,232.267914564727,231.881714206485,231.5070143185,231.143311899487,230.790132641501,324.148792210556,321.138552238337,318.273049531377,315.54763991517,312.95656788272,310.480540575317,308.122902829243,305.868779915492,303.712384189747,301.651720428767,299.673558817451 -830,234.16865760621,233.704891884481,233.256208509574,232.821943814915,232.401418726393,231.993988417772,231.598965730603,231.215876881588,230.844192541051,230.483413988376,230.13304067002,322.107979412238,319.145310388317,316.33670341381,313.659176913637,311.109209852234,308.681845346624,306.358974339333,304.146769553572,302.026749556044,299.999726346608,298.056926497617 -840,233.478583705918,233.018554126146,232.573526676086,232.142796139083,231.725689276717,231.321503974306,230.929678946613,230.549687704021,230.181005441523,229.823137702427,229.475516977617,320.087229071478,317.179625528437,314.412911349317,311.788523402819,309.282908838304,306.894793272802,304.617335759212,302.436010374018,300.357015948813,298.360209912748,296.452799902787 -850,232.788224228347,232.331948690626,231.890560521205,231.463348050087,231.049614962792,230.648686359201,230.260044643951,229.883137113579,229.517443470133,229.162409488717,228.817591327444,318.079569910648,315.23011166703,312.516289135939,309.930231687277,307.474172518963,305.125836379044,302.886986586766,300.74691901707,298.698102828426,296.739598904127,294.858947677273 -860,232.097591757854,231.645065695013,231.207300169286,230.783589682829,230.373181617153,229.975525900583,229.590053159058,229.216215457004,228.853472035346,228.501277556995,228.159254242639,316.103191352049,313.294896069763,310.63402346781,308.097131859418,305.67749167396,303.375332776532,301.170997114872,299.069818245982,297.055811835381,295.12934855463,293.281672151523 -870,231.406688953627,230.957895156788,230.523735647671,230.103465159568,229.696410463845,229.302012830173,228.919694733762,228.548912987966,228.189063405612,227.839737074187,227.500496153216,314.140204405162,311.388026542861,308.765811320178,306.278157727583,303.902881242454,301.636496455236,299.475179912819,297.40387571384,295.428678110227,293.530491690323,291.717086660583 -880,230.715505725166,230.270426994446,229.839856776478,229.422995047235,229.019291628508,228.628137283441,228.248959515272,227.881170177789,227.524249386891,227.177778366591,226.841307395835,312.194737518311,309.49388803068,306.92393229391,304.471646851342,302.143346032911,299.915817905577,297.790586310029,295.758318910417,293.812210186811,291.950229677145,290.162563165204 -890,230.024031880883,229.582651027917,229.155595480256,228.742182562763,228.341815138819,227.95388929962,227.577832685076,227.213009628583,226.859020200281,226.515391665711,226.181678213455,310.275270850366,307.617051528777,305.094497766026,302.690724470728,300.395850866721,298.212022324272,296.119719419639,294.124555340981,292.210697767046,290.380128186566,288.622314355422 -900,229.332257128576,228.894548232979,228.470997524063,228.061017624598,227.66397092451,227.279258821564,226.906249585546,226.544437261333,226.193365970585,225.852567107906,225.521598754892,308.368969789847,305.76405865343,303.280627612389,300.921967185769,298.669885607527,296.519788693651,294.468148168004,292.501756649291,290.624552800927,288.820350627951,287.095672187055 -910,228.640171075695,228.206068791782,227.786052715702,227.379490051459,226.985748817252,226.604215383972,226.234258327656,225.875443092577,225.527276725961,225.189294733942,224.861044764806,306.482665571424,303.923914343046,301.490000887359,299.16595290998,296.957948004568,294.844499327861,292.827627756767,290.897115535511,289.048836953628,287.277976945634,285.578817365454 -920,227.94775068442,227.517248524449,227.10075076137,226.697589562234,226.307138550401,225.928726336818,225.561848818101,225.206017040653,224.860742397472,224.52556448845,224.199967444365,304.61828770851,302.102036253489,299.711806392195,297.433737908412,295.257905001225,293.18572430559,291.199156396652,289.304977213173,287.485638719373,285.746337475045,284.073367989725 -930,227.254954930989,226.828077023166,226.415081265576,226.015305775741,225.62809946443,225.25282291406,224.889010863751,224.53614892524,224.193752818536,223.861332381098,223.538409189616,302.767156573424,300.301366608351,297.949012715548,295.71347196902,293.577622035441,291.538299698869,289.590103474277,287.723530368441,285.938770588338,284.224713492855,282.583007864105 -940,226.561814303897,226.138543776481,225.729033730923,225.332628210357,224.948620192505,224.576494809445,224.215734171201,223.865828466811,223.526297724289,223.196590127606,222.876359887027,300.936474144206,298.513494384318,296.207928073765,294.005427518377,291.911481016706,289.905611954089,287.991842642884,286.157296490286,284.402030655887,282.717148462183,281.102112770061 -950,225.868318174168,225.448638169104,225.04259755775,224.64951167313,224.268720345345,223.899731614758,223.542008346217,223.195045285985,222.858319459937,222.531358831378,222.21380932328,299.125501207428,296.743208344859,294.479124224312,292.319552990522,290.256984049878,288.290025587958,286.404529551622,284.604979378008,282.875528100405,281.222229413559,279.630758236028 -960,225.174455806958,224.758349481575,224.355762043657,223.965954940055,223.588389398183,223.22252281927,222.867822893085,222.523788902802,222.189838287004,221.865628165727,221.550747184522,297.327684699286,294.993026758467,292.76423248221,290.645862433995,288.61953416604,286.685493997892,284.834787639717,283.063018684483,281.365431448771,279.736972575034,278.173573340556 -970,224.480216361252,224.0676668898,223.668483317803,223.281971459366,222.90761672199,222.544857809092,222.193167213885,221.851994318651,221.520859897277,221.199387701887,220.887163055561,295.549153942853,293.255451626422,291.070770062134,288.984103702291,286.997252614701,285.092742847463,283.276889858344,281.532805518535,279.865845567304,278.262073646057,276.726908807597 -980,223.785588889414,223.376579464479,222.980758770208,222.597550481904,222.226391582827,221.866725866438,221.518030607672,221.179697872664,220.851373745248,220.532626908188,220.223046418979,293.78962393444,291.533496983133,289.389324677751,287.341321696607,285.38628259194,283.518420003648,281.729570741622,280.018453229286,278.376113045761,276.802109176751,275.289399903134 -990,223.090562336636,222.685050692273,222.292601340314,221.912681151786,221.544703141109,221.188116168805,220.842347295988,220.506895974739,220.181369180901,219.86533514917,219.5583866542,292.043019854867,289.831765152282,287.720093128336,285.712163318988,283.788949355392,281.954792051268,280.195925471571,278.514076613715,276.898681542691,275.351421485093,273.861933024617 -1000,222.395125540258,221.993064690274,221.604000048377,221.227352505668,220.862540450785,220.509017788083,220.166156741913,219.833577854602,219.510835448812,219.197501684629,218.893173036488,290.313291077487,288.142337500014,286.071382921106,284.094567452432,282.208506220077,280.401959270446,278.676451184232,277.019738746315,275.43441238126,273.910047568257,272.447772545876 -1010,221.699255543157,221.300639720334,220.914943805308,220.541553471925,220.179892458441,219.829370965822,219.489452444678,219.15973263491,218.839761687189,218.529115668609,218.227394735901,288.603045890991,286.465592126747,284.435145861461,282.492108564521,280.638980549451,278.864411855548,277.167143793967,275.539361250464,273.979583400678,272.480388665787,271.042363211029 -1020,221.002910978018,220.607764565613,220.225421411858,219.855272869754,219.496748002327,219.149204865238,218.812223403018,218.485349330272,218.168136926844,217.86016614834,217.560986376641,286.905386012368,284.810137342228,282.810716702151,280.905364872013,279.080461072082,277.339664710456,275.668055063775,274.070660114859,272.534220866898,271.062482861403,269.645713857881 -1030,220.306121420704,219.914427897154,219.535421557711,219.168499408195,218.813060371453,218.468516679728,218.134458505901,217.810416846222,217.495950090128,217.190642063122,216.893988829051,285.221260980693,283.166599236242,281.202564909554,279.329755666396,277.538523754555,275.82527021877,274.184304743214,272.611557127073,271.101990660837,269.653462081901,268.259416145023 -1040,219.60887541045,219.220618272985,218.844932820517,218.481221685092,218.128834552168,217.787295170526,217.456146531482,217.134923978131,216.823189989797,216.520487434659,216.226394059999,283.558017060944,281.535109007165,279.609321683532,277.765358455558,276.008336180711,274.321595674167,272.71102938647,271.162068089096,269.680217618205,268.253325414814,266.884388927358 -1050,218.911161371448,218.526324137143,218.15394366484,217.793413282696,217.444078261782,217.10552898627,216.777276146008,216.458859410067,216.149845327839,215.849726555463,215.558190914844,281.906934764266,279.92067141799,278.027424637499,276.218524384088,274.488681825754,272.833704738262,271.247505003057,269.726876316377,268.267458376922,266.864743598368,265.517689457257 -1060,218.212967611875,217.831533818629,217.462442441048,217.105040699245,216.758780017229,216.423206661892,216.097835902671,215.782211713609,215.475877416546,215.178357982363,214.889368126915,280.268135081471,278.320710759617,276.457167388104,274.682711941348,272.980703685605,271.355697852343,269.794379637349,268.301100607484,266.863702540813,265.486307834605,264.159297075147 -1070,217.514282322845,217.136235530293,216.770417384147,216.416129220919,216.072928219891,215.740316617464,215.417814240403,215.104969346617,214.80127836353,214.506370319467,214.219914316298,278.646790967731,276.732302864371,274.904682120259,273.157608372656,271.487755526576,269.887589924874,268.355181814537,266.884462673618,265.472477601669,264.116303320306,262.810401456445 -1080,216.8150935773,216.440417367657,216.077821062503,215.726667113262,215.386511154428,215.056847156983,214.737199482634,214.427119075252,214.126061010631,213.833752055933,213.549817988594,277.039875858583,275.155978122154,273.363043341617,271.64484237367,270.004844640325,268.430679185858,266.925254447926,265.477019365918,264.09050330695,262.754700911756,261.471973382954 -1090,216.115389328827,215.744067307687,215.384664298062,215.036642523188,214.699516987561,214.372786467116,214.055979836004,213.748604677677,213.450213713862,213.160491564705,212.879067533634,275.444715192965,273.597271552795,271.832284460829,270.146653824708,268.531976160512,266.987042898227,265.504584331959,264.082706095692,262.717059300963,261.403407410393,260.141407378488 -1100,215.415157410421,215.0471732075,214.690948191719,214.346043477744,214.011933766801,213.688122615898,213.37414338903,213.069461242472,212.773724711259,212.486577101214,212.207651224154,273.861733860144,272.04958778684,270.314227414656,268.658651194353,267.070842427118,265.552801260825,264.093762465101,262.697051061193,261.352108217842,260.061814759537,258.818661167124 -1110,214.714385533196,214.349681234015,213.996660628405,213.654857882841,213.323749419139,213.002843551388,212.691666599875,212.389676870454,212.09658212156,211.811996802043,211.535557214442,272.296574550798,270.512950582499,268.810599641995,267.180830182683,265.62259556837,264.127932156465,262.695515003384,261.320021188148,259.998076662371,258.728161864122,257.50374196031 -1120,214.013061285041,213.651617827089,213.301789369925,212.963073521924,212.634951749688,212.316937100288,212.008517344608,211.709239541317,211.418773942857,211.13673868355,210.862773538947,270.742609805965,268.989078767115,267.317302133533,265.71502038601,264.18386335563,262.713333334318,261.306024771372,259.951571152876,258.653182809509,257.402399165612,256.19938316929 -1130,213.311172129224,212.952973951545,212.606322053624,212.270678054611,211.945528440289,211.630390966522,211.324716022633,211.02813711227,210.740288051206,210.460790640468,210.189288110859,269.19985418361,267.479797155222,265.834321515683,264.261976788164,262.754615067255,261.310988794171,259.925250701435,258.594452650838,257.316302548955,256.084953948957,254.902397498311 -1140,212.608673742036,212.25373709601,211.910246191012,211.577659015282,211.255467048075,210.943188669665,210.640250347823,210.346357316634,210.061112199208,209.784140444462,209.515088720655,267.66962154525,265.980986119023,264.363365842169,262.818563921565,261.335828177703,259.917496619146,258.553139777871,257.246109934625,255.987379283775,254.777597184355,253.612727313536 -1150,211.905576887698,211.553894621211,211.213549166341,210.884003811634,210.564755004007,210.255287974639,209.955107908266,209.663887762403,209.381234014553,209.106775742663,208.840163034618,266.154455581122,264.49262359021,262.905325188571,261.38474277624,259.929211048086,258.532808025578,257.192576013266,255.905851075749,254.667085321076,253.477669500875,252.330307574502 -1160,211.201877731975,210.853433758546,210.516218235156,210.189699723196,209.873379611363,209.566711388752,209.269276164814,208.980715930775,208.700640998534,208.428684056169,208.164498593327,264.64989672029,263.01603403852,261.457027720216,259.961342931237,258.531537843023,257.156862572419,255.840625720184,254.573612681246,253.356588638433,252.185107069754,251.055901535551 -1170,210.497563350611,210.152341608619,209.818240522791,209.494733899818,209.181328044208,208.877446223105,208.582742449591,208.29682917465,208.019320524532,207.749852778514,207.488082810117,263.155914598756,261.552781767992,260.018426463953,258.550265015189,257.142752342932,255.792485031092,254.496826251001,253.250139342003,252.053573705757,250.899838946819,249.790004566058 -1180,209.792620686413,209.450605139728,209.119603022842,208.799093360109,208.488577492694,208.187479658105,207.895493964482,207.612214717099,207.33725983647,207.070269174113,206.810902969514,261.673183373565,260.099381772819,258.589973825141,257.148219282345,255.762786948742,254.436757364152,253.161107656844,251.93635082744,250.757970719773,249.622722774112,248.530914611193 -1190,209.087036547734,208.748211186327,208.420292595602,208.102764989864,207.795104219395,207.496798741929,207.207517779582,206.926859649795,206.654446047238,206.389920376677,206.13292457024,260.204490577437,258.655779451436,257.174234164876,255.755142360112,254.39421606484,253.08924445696,251.834115762726,250.630093692621,249.469703043619,248.353968216479,247.278557822622 -1200,208.380797606912,208.045146447444,207.720295966463,207.405735540444,207.100917295221,206.805390388963,206.518800831614,206.24075093143,205.970866137089,205.7087933876,205.454153880327,258.745756034462,257.221906135797,255.767611911171,254.370959759411,253.034530095862,251.749870042421,250.516873518626,249.331292376066,248.189575128404,247.092053232479,246.032855218356 -1210,207.673890398689,207.341397485074,207.019599724287,206.707991627129,206.406003476037,206.113241378201,205.829329922323,205.553875386086,205.286506952009,205.026875074322,204.774582485683,257.296917860176,255.801202718471,254.370036824462,252.997803975035,251.683120052634,250.419011150129,249.207209492411,248.039864754323,246.917814074136,245.836898993923,244.79409852499 -1220,206.966301318579,206.63695072253,206.318190319742,206.009519727452,205.710349380257,205.42033835162,205.139091716833,204.86621970159,204.601355202063,204.34415216866,204.094197244072,255.857900297539,254.389787356041,252.981427794748,251.633967580259,250.339903585138,249.098143264294,247.90504257648,246.756416471113,245.65292254615,244.588421789969,243.563189267312 -1230,206.258016621218,205.931792442771,205.616054063619,205.310303799033,205.013941487196,204.726667812527,204.448072741985,204.177770427837,203.915397459701,203.660611265117,203.412984876468,254.43125615693,252.987495024856,251.603282523696,250.278465760067,249.004819199555,247.784897883706,246.610285361939,245.481491213966,244.394816921711,243.346763457361,242.338504308903 -1240,205.549022418667,205.225908786697,204.913177125106,204.610315296992,204.316766135399,204.032216123872,203.75625938464,203.488513975084,203.228620158054,202.976238819165,202.730931965383,253.014818390154,251.594238264859,250.235092302875,248.931210314696,247.680143697496,246.479188562563,245.323200473145,244.213463050712,243.14340893698,242.113049645146,241.119960447176 -1250,204.839304678699,204.519285751413,204.209545530044,203.909559678483,203.618809520941,203.336969506533,203.063637889953,202.798436612221,202.541009589193,202.291019684537,202.048024953167,251.607577269978,250.210684749988,248.875293031428,247.592105538553,246.363132670705,245.180922802817,244.044944484838,242.952243743747,241.898606215616,240.885574207344,239.907471011398 -1260,204.128849223041,203.811909188463,203.505145159153,203.208022969636,202.920057695692,202.640914037577,202.370194359624,202.107524465007,201.852551902359,201.604934397644,201.364250140279,250.209439259995,248.837925929596,247.523790891387,246.262855805616,245.053694539157,243.890002741704,242.773610988068,241.697740646122,240.661893975167,239.664249970017,238.700946270742 -1270,203.417641725602,203.103764802039,202.799961746222,202.505691050197,202.220496565557,201.944035648488,201.675914750119,201.415763514292,201.163233102175,200.917978945247,200.679593683532,248.820301546194,247.473612391355,246.180484793705,244.941884938995,243.751731907328,242.608114697835,241.509107304524,240.44985722207,239.431472135603,238.44898649968,237.500795833456 -1280,202.705667710654,202.39483814716,202.093980876282,201.802549651752,201.520111888687,201.246320123365,200.980784870864,200.723139594193,200.473039046825,200.230139317258,199.994041594307,247.44248963384,246.117644929749,244.846258176969,243.628521911628,242.457142246331,241.333298514383,240.251336568219,239.209632109046,238.207209705201,237.23969050265,236.307150610324 -1290,201.992912551,201.685114627816,201.387187983746,201.098584355917,200.81888927366,200.5477530971,200.284790382407,200.02963839026,199.781955446206,199.541401356063,199.307579736745,246.073433747702,244.769917286544,243.521123284475,242.322664617964,241.170938789962,240.065331308404,239.00019823826,237.976100333045,236.989012631021,236.036397006985,235.11906179317 -1300,201.279361466101,200.974579495099,200.679568350519,200.393780592496,200.116814177633,199.848320053519,199.587916794558,199.335245437603,199.089967860053,198.851750754696,198.620193825903,244.712771291403,243.430327214359,242.203629496326,241.024206038033,239.892453846147,238.804112153356,237.756168981327,236.748734462669,235.776784191496,234.839931940379,233.936439330976 -1310,200.564999520181,200.263217845284,199.971107104085,199.688123637622,199.413871904466,199.148006323497,198.890149464494,198.639946118996,198.397061696035,198.161173054968,197.931869425885,243.360391050712,242.100814009726,240.893670180688,239.733349959227,238.62083544771,237.54953665173,236.519356079147,235.52743696283,234.57042535596,233.649019685451,232.7591912061 -1320,199.849811620298,199.551014617905,199.261789215561,198.981598611851,198.710047602816,198.446797083045,198.191473594843,197.94372566295,197.703222207824,197.469651093697,197.242591947943,242.016175807355,240.778973698845,239.591133997306,238.451001377562,237.355978760764,236.301497399213,235.28871404392,234.312107813031,233.370641788231,232.463567205621,231.587223712272 -1330,199.133782514392,198.83795459378,198.551599497726,198.274190478238,198.005326264198,197.744677351369,197.491874231731,197.246569141756,197.008434493137,196.777161436794,196.552346648553,240.680921280826,239.464695304326,238.295905515086,237.175535502023,236.097775674215,235.061131748147,234.064141989958,233.102644858798,232.176745727493,231.283479659242,230.420441709896 -1340,198.416896789296,198.124022393023,197.840522603016,197.56588404038,197.299692721025,197.041631988893,196.791336262803,196.548461469503,196.31268349174,196.083696748141,195.861118627451,239.354508653423,238.157863332843,237.008861764547,235.906843739737,234.846115256769,233.827033279834,232.845536720993,231.899148143101,230.988301496816,230.108660669765,229.259148539798 -1350,197.699138868718,197.409202473016,197.128543021498,196.856663940426,196.593131644607,196.337645695257,196.089844415215,195.849387400059,195.615953983432,195.389241832702,195.168892825646,238.03568428165,236.858358388465,235.729343404159,234.64481440398,233.601314833465,232.599005165637,231.632793073893,230.70210125475,229.8052115384,228.939012573411,228.103232170912 -1360,196.980493011203,196.693479126357,196.415645078801,196.146514657056,195.885627543123,195.632703007283,195.38738325359,195.149331525026,194.918230585992,194.693781333652,194.475654023398,236.724328683521,235.566057733331,234.456610477226,233.389333164586,232.36357203808,231.376941151161,230.425804233165,229.510497033724,228.627376906451,227.774436645889,226.952123313007 -1370,196.260943308046,195.976836478773,195.701812934028,195.435420503433,195.177164759563,194.92678829691,194.683937177948,194.448278271663,194.219497753096,193.997299730282,193.781386838169,235.420318649447,234.282167267295,233.190547854754,232.140283459408,231.131898891793,230.160733174253,229.224941876566,228.32423530846,227.454697507523,226.615445809232,225.805729230627 -1380,195.540473681187,195.259258487002,194.987030577632,194.723365625114,194.467727469639,194.219885769091,193.9794904216,193.746211900774,193.5197397722,193.299781335887,193.086060382431,234.123527798845,233.005178406709,231.931037931043,230.898205196113,229.906186194541,228.950271672266,228.030002854653,227.143214659562,226.287072320119,225.461388458994,224.663956382881 -1390,194.819067881072,194.540728936648,194.271281829256,194.010308695131,193.757299679654,193.511979459665,193.274027049011,193.043116504565,192.818940762392,192.601210295605,192.389651884636,232.833911366531,231.734866945997,230.677961028943,229.662690474805,228.686323089591,227.745445862251,226.840393574009,225.967332653146,225.12439959503,224.31202484224,223.526710593903 -1400,194.096709484473,193.821231439988,193.554550335542,193.296252909082,193.045865224347,192.80305323319,192.567530953627,192.338976004467,192.117084672212,191.901570584236,191.692163493074,231.552442971861,230.471112123031,229.431195768794,228.43313173581,227.472197364003,226.546662123896,225.656010232137,224.796486053632,223.967199778985,223.167259415197,222.393897208411 -1410,193.373381892281,193.100749433768,192.836819567913,192.581183606465,192.333407764698,192.093090780743,191.859985855669,191.633774148922,191.41415527743,191.200846004012,190.993579035609,230.277658448206,229.213791255182,228.191242042023,227.20941542742,226.263695722108,225.35352298062,224.476748138883,223.6305710175,222.814701736747,222.026996108553,221.265421233403 -1420,192.649068327263,192.379266176939,192.118072820307,191.865084115041,191.6199107857,191.382075617684,191.151375299892,190.927494511136,190.710136178793,190.499020182346,190.293882165467,229.009433992513,227.962780102539,226.957632352407,225.991426778439,225.060704034019,224.165593878836,223.302501922764,222.469483269394,221.666778010186,220.891138477002,220.141187467015 -1430,191.923751831781,191.656764748376,191.398293206884,191.147937583066,190.905322780246,190.669991081381,190.4416826533,190.220120486794,190.005010799738,189.79607656953,189.593056358935,227.747644022401,226.717953197416,225.72985735465,224.779050065385,223.86345408056,222.982767951493,222.133165718442,221.313573631851,220.52333070547,219.759589835196,219.021233023768 -1440,191.197415265473,190.933228044551,190.677463659694,190.429726976956,190.189647107171,189.956820328903,189.730891102839,189.511635291736,189.298762384061,189.091998436406,188.891084913025,226.492161534326,225.47953716872,224.507799806885,223.572168854832,222.671789655937,221.804937764672,220.968633336768,220.162320333145,219.384261651317,218.632253381067,217.905588185767 -1450,190.470041302905,190.20863877717,189.955566926305,189.710435078906,189.472876527352,189.242546334669,189.018983653031,188.802021959599,188.591373993548,188.38676887199,188.187950943096,225.242858427892,224.247490434176,223.291341638293,222.370666222793,221.485209770253,220.631995499108,219.808798418717,219.015517101023,218.249472529422,217.509032307502,216.793848586491 -1460,189.741612431169,189.482979470771,189.232585567395,188.990044484474,188.754993670017,188.527092475612,188.305943123588,188.09126333941,187.882828505574,187.680370781063,187.483637380433,223.999605798976,223.021150580813,222.080364185713,221.174424952934,220.303604996177,219.463833114491,218.653687783351,217.873064097935,217.118864992508,216.389829903194,215.685923056781 -1470,189.012110947453,188.756232460279,188.508501954297,188.268537600125,188.035980975529,187.810495305715,187.59175214697,187.379342093148,187.173108610646,186.972786881714,186.778126969793,222.762274204143,221.800397266915,220.874748407395,219.983884761016,219.126865624062,218.300342497839,217.503351156827,216.734861427814,215.992340770928,215.274735584944,214.581720479421 -1480,188.281518956566,188.028379888526,187.783298266512,187.545896640728,187.315820692875,187.092737497607,186.876333937809,186.666240693258,186.462196809922,186.263999702848,186.071402266903,221.531307239179,220.585109669361,219.67437507571,218.798308392023,217.954881820805,217.141415597213,216.357336236767,215.600809249083,214.869801768683,214.163565474396,213.481149872129 -1490,187.549818368419,187.299403703721,187.056956489174,186.822103627015,186.59449487712,186.373801139469,186.159712888558,185.951938744363,185.75007541267,185.553991581642,185.363445635912,220.30603760666,219.375166692189,218.479124950493,217.617574583726,216.787543772977,215.98694454189,215.215541600524,214.470807876416,213.751150149674,213.056083062091,212.384120462279 -1500,186.816952567424,186.569285656882,186.329458410464,186.097140382996,185.871985386811,185.653668123152,185.441882635579,185.236340898261,185.036726533696,184.842744660964,184.654239246804,219.086218595482,218.170447154204,217.28887893458,216.441571764602,215.624741815463,214.83686129325,214.077865959229,213.344757872134,212.636288414936,211.952196148293,211.290541753955 -1510,186.082905678569,185.838007299214,185.600785618995,185.370988533322,185.148273881338,184.932320141534,184.722824904041,184.519503476129,184.322087607605,184.130240886744,183.943765072763,217.871727115404,216.970829957341,216.103913811166,215.270188470366,214.466366546774,213.691290814749,212.944208254951,212.222560128032,211.525119471543,210.851812805912,210.20032358792 -1520,185.347689154617,185.105507192333,184.870919501133,184.643629500611,184.423341818247,184.209738685825,184.002521217607,183.801408032926,183.606133997179,183.416449069571,183.232004887492,216.662440085799,215.776194237339,214.923688046284,214.103313467832,213.312308932085,212.549807517293,211.814467747675,211.104115938381,210.417733039504,209.754841443641,209.113376195043 -1530,184.611283957458,184.371765601887,184.139841238284,183.915044502719,183.697170450505,183.485905042824,183.280952895687,183.0820359195,182.888892075563,182.701274237962,182.518940262478,215.458234599419,214.5864194982,213.74805545381,212.940835865621,212.162460394984,211.41230900981,210.688544092908,209.989327064803,209.3138269912,208.661190862187,208.029610243676 -1540,183.873670839394,183.636801220906,183.407455774352,183.185214549962,182.969740823718,182.760800292131,182.558101050634,182.361368279781,182.170343017133,181.984781033213,181.804451801445,214.25898806858,213.401385731773,212.576903274009,211.782645212761,211.016712898867,210.278693285792,209.566337410641,208.878095793658,208.213293837029,207.570770304126,206.94893688144 -1550,183.134830340299,182.900594630179,182.673796287573,182.454087620405,182.241033773288,182.034405303298,181.833946584902,181.639386047927,181.450467786611,181.266950449524,181.088606222286,213.064578355244,212.220973523707,211.410119162983,210.628631586183,209.874959018799,209.148858796874,208.447748346367,207.770324986526,207.116041366406,206.483489497888,205.871267771864 -1560,182.394742784713,182.163126195348,181.938860700964,181.721602774448,181.511029901333,181.306700732938,181.108470188136,180.916069945412,180.729247136151,180.54776326863,180.371393223427,211.874883886333,211.045276051436,210.247591287103,209.478685668018,208.737188389876,208.022704517951,207.332678124779,206.665918124355,206.021977859575,205.399258696307,204.796515126263 -1570,181.653388278888,181.424376063945,181.202629201723,180.987808302819,180.779594730267,180.577667021772,180.381652334217,180.191400478062,180.006661602364,179.82720005682,179.652793399783,210.689783755549,209.873975026309,209.089208406473,208.332698813533,207.603252874027,206.900130004505,206.221028596742,205.564779345768,204.931012128332,204.317988710172,203.724591731232 -1580,180.910746707778,180.684324162368,180.46508175607,180.252684210011,180.046816739329,179.847183515782,179.653473278254,179.46535793304,179.282691503298,179.105241161914,178.932787127878,209.509157812835,208.706899596091,207.934859948354,207.190563110497,206.472960694832,205.781035442789,205.112702280078,204.466813479996,203.84305355147,203.239590937173,202.655410972087 -1590,180.166797731971,179.942950192808,179.726198106159,179.516210276581,179.312675745994,179.115302276004,178.923814964305,178.737922375765,178.557316935352,178.381866710166,178.211354562753,208.332886742547,207.543937230756,206.784436071385,206.052171430675,205.346210340825,204.66532169343,204.007602394669,203.371926074892,202.758012105371,202.16397738659,201.588886852589 -1600,179.421520784558,179.200233630109,178.985957766931,178.778366055993,178.577151340754,178.382024949056,178.192715327339,178.008966793815,177.830517770135,177.657056603121,177.48847563481,207.160852131313,206.384976126029,205.637827721367,204.917417474135,204.222900980061,203.552890329003,202.90563289234,202.280052476617,201.675798390122,201.091060700075,200.524934011226 -1610,178.674808817941,178.456153718572,178.244340022909,178.039130871408,177.840222883898,177.647330930922,177.460186785632,177.278537893074,177.102146245149,176.930787350821,176.764130046598,205.992936526466,205.22990526409,204.494926679339,203.786195806947,203.102932500515,202.443643666062,201.806698481948,201.191064672811,200.59632365152,200.020754168828,199.463467734333 -1620,177.926676784425,177.710613893524,177.50132392493,177.298483812401,177.101869502225,176.911199384181,176.72620853617,176.546647509496,176.372281218417,176.20288792369,176.038258301008,204.82902348589,204.078614465974,203.355625602584,202.658401892867,201.986205544577,201.337484792092,200.710704650078,200.104859932958,199.519499799284,198.952971747463,198.404403966303 -1630,177.177146378547,176.963598576561,176.756810850301,176.556403731627,176.362070085694,176.173609234648,175.990759539246,175.813274636538,175.640922343904,175.47348365584,175.310751824504,203.66899762003,202.930994436394,202.219818059186,201.533932119493,200.872621538143,200.234317587797,199.617557677701,199.021348750639,198.445239421789,197.887628064821,197.347659317119 -1640,176.426195929864,176.215148726596,176.010779537374,175.812777108933,175.620803284013,175.434539167953,175.253818515026,175.078398027584,174.908048406959,174.742553363391,174.581708708596,202.512744626749,201.78693680162,201.087398556683,200.412683819386,199.762082714757,199.134046745126,198.527164653146,197.940442312883,197.373455797593,196.824638431975,196.293151067417 -1650,175.67380352185,175.465242470346,175.26327789023,175.067602452673,174.877927579264,174.693967626053,174.515363940055,174.341996192443,174.173637949395,174.010075618963,173.851107555573,201.360151319693,200.646334141034,199.958262565336,199.29455528659,198.654492135217,198.036577781376,197.439433481671,196.86205562593,196.304062904022,195.763918847664,195.240797171292 -1660,174.919946988324,174.713857684942,174.514283827528,174.320921985024,174.13348723214,173.951711763561,173.775343630487,173.604047393776,173.437669265913,173.27602874809,173.118926720661,200.211105650727,199.509080012902,198.832306536475,198.179445788942,197.549753703022,196.941817049718,196.354272891944,195.786137099552,195.23697542306,194.705386001358,194.190516257014 -1670,174.164603909805,173.96097199428,173.763775014745,173.572713411345,173.387505887092,173.207888040727,173.033611120216,172.864440884697,172.700120400445,172.540390825568,172.385144308363,199.065496726992,198.375068974869,197.70942791636,197.067255576555,196.447772176024,195.849671746449,195.271592439683,194.712569311271,194.172108744745,193.648957274144,193.142227625834 -1680,173.407715382908,173.206562765285,173.011728860433,172.822954180107,172.639961030897,172.46248839248,172.290290687958,172.123136661147,171.960808350156,171.803100147764,171.649738168726,197.923214823063,197.244196599655,196.58952515595,195.957885886803,195.348453174605,194.760049915236,194.191302508698,193.641264899292,193.109378968298,192.594550737615,192.095851249037 -1690,172.649146178947,172.4505311038,172.258122512408,172.071621479073,171.89082988964,171.715490081693,171.545359631917,171.380210248617,171.219826759187,171.064006183184,170.912556882719,196.784151388666,196.116359486365,195.472497716944,194.851238946121,194.251703186674,193.672860448629,193.113314309558,192.572137303969,192.048702901159,191.542085150937,191.051307763377 -1700,171.889013057377,171.692810521247,171.502802299328,171.318692231397,171.140089424815,170.966870106656,170.798794985717,170.635638714677,170.477188891358,170.323245144399,170.173618295166,195.648199052364,194.991455267815,194.358246074434,193.747217968909,193.157429569767,192.588013087064,192.0375398761,191.505100762284,190.989998056105,190.491479956223,190.008518465042 -1710,171.127292370435,170.933488157364,170.745799826362,170.563943004238,170.387650638499,170.216605197079,170.050573514399,169.889398858312,169.73287157828,169.580793894391,169.432979070706,194.515251621588,193.869382614221,193.246671716465,192.645727153797,192.065540550495,191.505418415587,190.963892059942,190.440070300606,189.933182646619,189.442655272378,188.967405302252 -1720,170.363960195215,170.172540133522,169.987158029808,169.807533251097,169.633402250696,169.46451729046,169.300645275722,169.141467205827,168.986851378867,168.836629023431,168.690615829777,193.385204079349,192.750041233603,192.137677140792,191.546671677518,190.975952359583,190.424987858486,189.892284523207,189.376961725873,188.878198737529,188.395531887526,187.927890866627 -1730,169.598992329481,169.409942291753,169.226852794084,169.049446917602,168.877464597034,168.710661360815,168.548807182271,168.391685430626,168.23909191192,168.090726844893,167.946504915895,192.257952577966,191.633331869182,191.031165849091,190.449957686602,189.888656627771,189.346633672029,188.82263172959,188.315691615355,187.825008931333,187.350031250149,186.889898383407 -1740,168.832310429993,168.64567019047,168.464859719965,168.289659645109,168.119813357763,167.95507963025,167.795231482643,167.640055148469,167.48934912901,167.3429233275,167.200598255468,191.133394430078,190.51915629406,189.927042338851,189.355492287093,188.803476744573,188.270268935464,187.754848933928,187.256177305101,186.773465699824,186.306075459043,185.853351700636 -1750,168.063764499078,167.879554206843,167.701148737858,167.528146786912,167.36042392504,167.197747528185,167.039893642019,166.886651344555,166.737821813749,166.593217473833,166.452661212771,190.011428097218,189.407417303433,188.825212093178,188.263183532489,187.720323218041,187.195807540446,186.688852170404,186.198336877204,185.723489081294,185.263587252192,184.818175277385 -1760,167.293498806744,167.111614131452,166.935458415675,166.764765718723,166.599271398437,166.438640191411,166.282768832897,166.131449225666,165.984485205846,165.84169170131,165.702893960156,188.891953176176,188.298062371199,187.725581568693,187.172940410045,186.639107449743,186.123164179032,185.62455823951,185.142089145986,184.674999812504,184.22257834641,183.784294171116 -1770,166.521487795767,166.34191476266,166.167995325343,165.999467153305,165.836083865085,165.677613836988,165.52383193051,165.374423701256,165.229314247626,165.088320983845,164.951271501907,187.774870383385,187.191030802736,186.628058181715,186.08467282563,185.559741718621,185.052358205946,184.561884693882,184.0873536432,183.627919313434,183.182884088986,182.751634024235 -1780,165.747705604384,165.570430283399,165.398733692557,165.232357085834,165.071057442012,164.914606290587,164.762788641066,164.615402005244,164.472255503174,164.333079993209,164.197768540106,186.660081537517,186.086149070392,185.532550292897,184.998291587248,184.482139163723,183.983204984588,183.500749823105,183.034050602341,182.582169671262,182.144423437366,181.720168609434 -1790,164.972080733082,164.797134567163,164.627647433495,164.463409473346,164.30418100186,164.149736679401,163.999864456367,163.854364609601,163.713048861259,163.575739572046,163.442269001612,185.547489540483,184.983322842924,184.438967190454,183.913708387371,183.406213765911,182.915613568121,182.441092124742,181.982100942149,181.537673623624,181.107120862674,180.689812288416 -1800,164.194399148115,164.021816777897,163.854662367914,163.692597958339,163.535428226177,163.382978722402,163.235040317509,163.091416033914,162.951920177622,162.816377543151,162.684622684623,184.436998356994,183.882458800182,183.347316657309,182.830835784199,182.331880328657,181.849500894911,181.382898598308,180.931426249375,180.494354541248,180.070901435236,179.66044924951 -1810,163.414856083536,163.244527411786,163.079553375224,162.919685838993,162.764691737369,162.614305818787,162.468289659485,162.326529747521,162.18884295457,162.055056491904,161.925007192098,183.328512992838,182.783464610757,182.257440514159,181.749587181951,181.259054458001,180.784784663588,180.325995390523,179.881952264116,179.452136409997,179.035690806653,178.632006730962 -1820,162.633424199322,162.465335453913,162.302528510133,162.14475871462,161.991796265612,161.843425105075,161.699441908338,161.559655161383,161.423790369185,161.291749626964,161.163395763042,182.221939472019,181.686248908668,181.169215924193,180.669899537425,180.187652541783,179.721383312216,179.270302887053,178.833692019705,178.410943812389,178.001415191414,177.604412501373 -1830,161.850075822372,161.684213275933,161.523560187086,161.36787535874,161.216932229542,161.070517782534,160.928431549823,160.790484703573,160.656499224743,160.526307141909,160.399749833423,181.117184812867,180.590721269201,180.082554885517,179.591764558373,179.1175917282,178.659215996897,178.21574215079,177.786465792625,177.370725174022,176.968001348094,176.57759484109 -1840,161.064556645122,160.901044112436,160.742620481751,160.589007887833,160.44007178471,160.29560217459,160.155401425857,160.019283377664,159.88707252106,159.758603249157,159.63371916964,180.014157003249,179.496792183993,178.997370261122,178.514989633085,178.04880639304,177.598202569869,177.162234900164,176.740197073365,176.331440980936,175.935376560164,175.55148252326 -1850,160.276961344482,160.115645042362,159.959392392691,159.807969061943,159.661154930748,159.518650129482,159.380323420431,159.246023101928,159.115576157201,158.988819327081,158.865598432802,178.912876309929,178.404373035445,177.913575753458,177.439490660505,176.981291691348,176.538263557143,176.109703487055,175.69480994722,175.29294821838,174.903521457037,174.526004794586 -1860,159.487352451706,159.328218769358,159.174077919573,159.024698948165,158.879864904239,158.73937179666,158.603027642284,158.470651596697,158.341981733516,158.216927007504,158.095359284961,177.813165516071,177.313376070553,176.831085878528,176.365184304181,175.91486278596,175.479363769597,175.058070874361,174.650229072231,174.255173153992,173.872318583998,173.501115239535 -1870,158.695700675387,158.53873604667,158.386693913255,158.239346675455,158.096480527657,157.957894430793,157.823399175132,157.692816524291,157.565978432388,157.442726327146,157.322910452589,176.714900564586,176.223810878003,175.749815939547,175.291987966354,174.849439065793,174.421427705209,174.007260613263,173.606379656859,173.218042569694,172.841676899671,172.476743847208 -1880,157.901720616709,157.747046321975,157.597210803919,157.451882714642,157.310972310723,157.174281483588,157.041623776734,156.912823542905,156.787715173247,156.666142391393,156.547957606193,175.617992382794,175.135518140618,174.669686983332,174.219819761737,173.784940586438,173.364318661386,172.957273278608,172.563187437423,172.181483739586,171.8115251387,171.452783953506 -1890,157.105519268063,156.952984241906,156.805229841621,156.662035140382,156.523192595656,156.388503129619,156.257671657196,156.130642896707,156.007253658688,155.887349946125,155.770786317144,174.522352762002,174.048376618935,173.590716357941,173.148598491027,172.721288044253,172.307959128872,171.907945437882,171.520621497372,171.145424407669,170.781792472125,170.429166085466 -1900,156.307171866083,156.15676266115,156.011065255406,155.86986200023,155.732948427036,155.600132266168,155.471232551976,155.346078805411,155.224510286424,155.106318920254,154.991366544342,173.427894326819,172.962301175474,172.512702209773,172.078298555941,171.658402750259,171.252272170697,170.85919970078,170.478573071639,170.109817008199,169.75240848545,169.405821153207 -1910,155.506626385401,155.358350584961,155.214697246271,155.075472960758,154.940476310972,154.80951789124,154.682419426835,154.559012969409,154.439140161109,154.322651560624,154.209406025209,172.334530504245,171.877207420869,171.435562209799,171.008813308556,170.596229150332,170.197181396571,169.810961296547,169.43694699576,169.074575339921,168.723316718141,168.382680428381 -1920,154.703483224839,154.557416650126,154.415922921581,154.278790922891,154.145744978267,154.016632695386,153.891324261923,153.769654241633,153.651466641418,153.536614247997,153.424958019643,171.242235376914,170.793011683607,170.35921469624,169.940019947379,169.534711685655,169.142619283827,168.763155936466,168.39567047863,168.03960330826,167.694435952139,167.359680378797 -1930,153.89808575136,153.754102012342,153.614623793633,153.479443181285,153.348364840947,153.22120508215,153.097791004735,152.977959719172,152.861458193193,152.74823186829,152.638155124884,170.15090643089,169.709650613285,169.283578645068,168.871839298533,168.473712703709,168.088542697927,167.715713881046,167.354671149829,167.004829928339,166.665678587122,166.336739340616 -1940,153.090401455257,152.948487268968,152.811011747412,152.67777015486,152.548570137481,152.423230802707,152.301581879404,152.183462950703,152.068722752288,151.957218529703,151.848815449002,169.060400475654,168.627087534098,168.208576248062,167.804192750189,167.413155296663,167.034819310001,166.668582634656,166.313879971939,165.970184577777,165.636975283328,165.31378142889 -1950,152.280087885851,152.140359660956,152.005000931991,151.873739038617,151.746405439504,151.622875024949,151.502980133226,151.386562801754,151.273474076715,151.163573380709,151.056727932878,167.9706333759,167.545158183061,167.134187663271,166.737002223853,166.352963047292,165.981374273152,165.621646744611,165.273227305364,164.935596157115,164.608257008322,164.290738799321 -1960,151.467267063182,151.329578949268,151.196194495543,151.066915305604,150.941554975928,150.819938204493,150.70189997761,150.587226180988,150.475778547396,150.367471324249,150.262173768664,166.881521654137,166.463781035553,166.060252977035,165.67023275995,165.293060696756,164.928133163716,164.57483323541,164.232618979775,163.900981744439,163.579443098681,163.267543862616 -1970,150.652044175097,150.516383010107,150.384960134497,150.257580255098,150.134059878806,150.01422643591,149.897917480305,149.784979958864,149.675269543101,149.568650017007,149.464992715667,165.79298977618,165.382875141106,164.98669303105,164.603746993282,164.233391851482,163.875023027652,163.528069491258,163.191983715932,162.866266920333,162.550450918036,162.244094930694 -1980,149.834109418323,149.700589632649,149.57124041917,149.445770622936,149.324078400722,149.206016883473,149.091426173304,148.980155614003,148.872063133736,148.767014642972,148.664883482326,164.705000214645,164.30236536343,163.91342916273,163.537466894326,163.173842348616,162.82196422019,162.48127784464,162.151250534376,161.831381939927,161.52121932179,161.220331329289 -1990,149.013471914356,148.881949787186,148.754533875081,148.631035081752,148.511275730857,148.39508871791,148.282316736548,148.172777074918,148.066292236779,147.962804812621,147.862190133666,163.617399304431,163.222195645432,162.840387580692,162.471315868705,162.114337106978,161.768868610692,161.434367871891,161.110325488039,160.796257301571,160.491679949716,160.196194585778 -2000,148.190311224522,148.060773715051,147.935278523036,147.813639581047,147.695682053642,147.581241503595,147.4701631312,147.362301079301,147.25751779753,147.15568345995,147.056675430956,162.530105500651,162.142236964217,161.767489743081,161.405215889623,161.054801398575,160.715662863601,160.387271536359,160.069129163946,159.760767437266,159.461745815048,159.171617585945 -2010,147.364252189324,147.23681120013,147.113346278167,146.993647022485,146.877479624742,146.764774235666,146.655378543097,146.549149029904,146.445950348983,146.345654750718,146.248141557878,161.4430377559,161.062409998055,160.69463366266,160.339075352706,159.995142022085,159.66227393177,159.339917073519,159.027602941595,158.724873467251,158.431297695513,158.14646984128 -2020,146.535383279066,146.409897777274,146.288325452034,146.170486289793,146.056211137843,145.94534089845,145.837725793591,145.733224693201,145.631694684321,145.532927941512,145.436900007296,160.356121815525,159.982635842776,159.62174201671,159.272814889976,158.935274713262,158.608578090986,158.292215230168,157.985676466675,157.688511580146,157.400316749897,157.1206950169 -2030,145.703863786175,145.580320852129,145.460628658026,145.344610145469,145.232098933755,145.122938527948,145.016981596303,144.914089310072,144.81413073952,144.716982300626,144.622527247612,159.2692565601,158.902821053688,158.5487342576,158.206358972611,157.87513272378,157.554527852596,157.244045923679,156.943218845248,156.651606632146,156.368734921188,156.094257982536 -2040,144.869143927633,144.747652426745,144.629946895004,144.515853279567,144.405208023058,144.297787439618,144.193477848436,144.092183894461,143.993776798312,143.898135002593,143.80514367317,158.182354078541,157.822878454364,157.475493937166,157.139606146026,156.814642130798,156.500054501047,156.195382174117,155.900167480302,155.61398018234,155.336415481238,155.067091728417 -2050,144.031606027675,143.912028131551,143.796174767656,143.683874788175,143.574967360873,143.46930120438,143.366733890421,143.267131206262,143.170366571422,143.076320503308,142.984880127093,157.095334648252,156.74273093052,156.401964751756,156.07245530354,155.753658689766,155.445065091192,155.146152651484,154.856483100845,154.575656235319,154.303276223903,154.038970284744 -2060,143.191114848679,143.073559183707,142.959592799733,142.849074531548,142.741893413172,142.637900702192,142.536956356811,142.438928409549,142.343692394227,142.251130820992,142.161132694795,156.008081048174,155.662293848312,155.328070245315,155.004860322057,154.692139345057,154.389409065964,154.096201957997,153.812078919316,153.536565658177,153.26930941469,153.009962311022 -2070,142.347330408586,142.231659479903,142.119588813678,142.010953079031,141.905596904374,141.803374139476,141.704147182096,141.607786362709,141.514102806064,141.423015983168,141.334450663163,154.920518336546,154.581422101799,154.253687199598,153.936746267285,153.630026810156,153.333088921158,153.045475682509,152.76675790669,152.49653209329,152.234418560403,151.980000993778 -2080,141.500661472084,141.386862559265,141.276603912625,141.169723033753,141.066067208368,140.965492781696,140.867864497212,140.773054892413,140.680943745961,140.59141757117,140.50436915139,153.832576317611,153.500087477817,153.178717897483,152.867923580772,152.567195060339,152.276032204878,151.993945974813,151.72056936332,151.455507984514,151.198390692574,150.94886791541 -2090,140.650526550284,140.538704393667,140.430360174269,140.325334283944,140.223476723442,140.124626254003,140.028585967836,139.935317247214,139.844701933015,139.75662848236,139.670991512361,152.744142735198,152.418212441148,152.103129720852,151.798396561662,151.503515288,151.218019301767,150.941470727309,150.673442925454,150.413485421677,150.161306216899,149.916563606587 -2100,139.797269614436,139.687290783155,139.580730880441,139.477433081159,139.377249997122,139.280042978536,139.18568147652,139.094042460563,139.005009885509,138.918474203177,138.834331914379,151.655084007351,151.335617084348,151.026811696914,150.728100784551,150.438996176293,150.159076943771,149.887915298549,149.625109367937,149.37028128537,149.12307544443,148.883079016713 -2110,138.940659933022,138.832628253849,138.727954136291,138.626464065991,138.527944110655,138.432349435245,138.339551777773,138.249430259597,138.161870862199,138.076765947777,137.994013819464,150.565382905551,150.252270147482,149.949587798145,149.656827143468,149.373511699917,149.099154970456,148.833316488452,148.575655930408,148.325804102124,148.083413521095,147.848156860492 -2120,138.08056305132,137.974346110366,137.871428705336,137.771659590004,137.67489661382,137.581006048985,137.489861976331,137.401345724098,137.315345354401,137.231755192692,137.150475396111,149.47492700139,149.168123874255,148.871489883762,148.584561974873,148.306874865985,148.037992273448,147.777504714374,147.525027091347,147.280093676593,147.042462786841,146.811814586722 -2130,137.217170605551,137.112871033484,137.011737812166,136.913658444504,136.81853288239,136.726229787813,136.636625488319,136.549603426327,136.46505365521,136.382872377543,136.302961521506,148.383524606988,148.082960464206,147.792387256151,147.51127620845,147.239150148223,146.975637471456,146.720338285409,146.472876870746,146.232899901482,146.000074817725,145.774061504007 -2140,136.349970986925,136.247457672887,136.148126450635,136.051831558164,135.95843599383,135.867810868594,135.779834814848,135.694393446138,135.61137886277,135.530689198789,135.452153761484,147.291215147378,146.996762701771,146.712080470218,146.436693490123,146.170156824464,145.912053252946,145.661885388165,145.419381345343,145.184199881882,144.956016169875,144.734524178334 -2150,135.479471796961,135.378777012577,135.281162988202,135.186531341384,135.094747569336,135.005685130171,134.919224863046,134.835254458212,134.753667972044,134.674365382645,134.597252182141,146.197840193004,145.909504427634,145.630642008614,145.360868823331,145.099750576168,144.846879976045,144.601874691968,144.364375488945,144.134028009305,143.910432507446,143.693383873525 -2160,134.604895213864,134.506027212234,134.410225809084,134.317350631723,134.22726973848,134.139858995665,134.055001508926,133.972587103533,133.892511848776,133.814641738985,133.738867122969,145.103232347324,144.820868170309,144.547852610447,144.283731915086,144.028004564788,143.780305379313,143.540297849069,143.307631266869,143.08197577587,142.86302085654,142.650473942006 -2170,133.726945074672,133.629822593518,133.535711065008,133.444472731043,133.355978103545,133.270105353598,133.186739753902,133.105773169177,133.027103589809,132.950634704476,132.876275508058,144.007450084582,143.730965319885,143.46361833659,143.204966416396,142.954594757833,142.712114332152,142.477159931246,142.249297524064,142.028263812445,141.813783074681,141.605569649245 -2180,132.844708576594,132.74942754111,132.65709956286,132.567589563416,132.480770572025,132.396523126834,132.314734728343,132.235299339883,132.158116930458,132.08307195848,132.010030322447,142.910205735737,142.639636591109,142.377991171378,142.124743024093,141.879588351799,141.642147562469,141.41206426564,141.189003542312,140.97265036563,140.762708157439,140.558850193436 -2190,131.958955479211,131.865407817577,131.774742497623,131.686843041269,131.601584886375,131.518850833749,131.438530511481,131.360519885334,131.284720810643,131.211040621662,131.139391754783,141.811513658577,141.546670023277,141.290559988109,141.042761130079,140.802877638679,140.570525911569,140.345257222658,140.126853059969,139.915005993894,139.709426568294,139.509842015929 -2200,131.068753317653,130.977000888017,130.888089926654,130.801890554278,130.718280681949,130.63714543608,130.558376633597,130.481872302199,130.407536241305,130.335277619677,130.26499103446,140.711292709606,140.452189079909,140.20153430118,139.95899973215,139.724199334209,139.496770987418,139.276374682147,139.062690870546,138.855418961864,138.654204582747,138.458798527447 -2210,130.174816309537,130.084860666808,129.997586473053,129.912971447264,129.830897081207,129.751250722126,129.673926275328,129.598823734166,129.52584874985,129.454912237195,129.38593001286,139.60925748977,139.355768958293,139.110620635151,138.873409848003,138.643740504799,138.421166027237,138.205462328844,137.996317707886,137.793438922855,137.596549855736,137.405390288739 -2220,129.27633929721,129.188057115323,129.102506764339,129.019563468995,128.939109933057,128.861035787662,128.785237087734,128.711615851671,128.640079640029,128.570541169391,128.502917958065,138.505582028893,138.257602236553,138.017767318833,137.785684728609,137.560986576288,137.343327739557,137.132384142624,136.927851187692,136.72938857102,136.53670532252,136.349620653461 -2230,128.373820743973,128.287304916148,128.203465468637,128.122154035541,128.043210776131,127.96660110763,127.892223134406,127.819980803974,127.749783494374,127.681545635994,127.615186364543,137.39979176046,137.157375967441,136.922917706154,136.696033503369,136.476245193123,136.26331632478,136.056946192636,135.856837786742,135.662711664391,135.474304678838,135.29136881595 -2240,127.466742075516,127.381871800353,127.299625668779,127.219883914503,127.142533944956,127.067469812509,126.994591731729,126.923805638098,126.855022784092,126.788159368973,126.723136199075,136.292130696626,136.055079320287,135.825796075724,135.603907271519,135.389062658967,135.18093363586,134.979211611432,134.783606516015,134.593727140872,134.409420927981,134.230458681574 -2250,126.555223090573,126.472088647913,126.391523900619,126.313411598424,126.237641512498,126.164109917979,126.092682146911,126.023252162767,125.955786120814,125.890201902086,125.826421900187,135.182188878635,134.950567388492,134.726531358393,134.509676297611,134.299600378242,134.096080328852,133.898815397383,133.707522851733,133.521936658692,133.341806276512,133.166895549986 -2260,125.639200846806,125.557684168049,125.478685893337,125.402091170407,125.327792021431,125.255686836633,125.185679911972,125.117681026501,125.051605055493,124.987371615836,124.924904740617,134.070082184691,133.843684316085,133.624688265252,133.412738653818,133.207502365147,133.008666839912,132.815938524625,132.629041457479,132.447585887956,132.271453577915,132.100417427986 -2270,124.71823997185,124.638428526806,124.561082042761,124.48608813533,124.413341145268,124.342741643179,124.274195977326,124.207615860236,124.142917990285,124.080023704841,124.01885866196,132.955482203964,132.734380690456,132.520503033195,132.313458237307,132.112867704636,131.918522966773,131.730138048489,131.547444083197,131.370188059917,131.198131677988,131.031050298988 -2280,123.792752260635,123.714631056739,123.638888122458,123.565385958573,123.494084919109,123.424887648915,123.35770244723,123.292442863301,123.229027326204,123.167378805519,123.107424499922,131.838456624828,131.622441342454,131.413471860235,131.211210571734,131.015340985864,130.825566111821,130.641606988911,130.46320134647,130.290024994876,130.121866247956,129.958562568277 -2290,122.862047991453,122.785501210383,122.711316602962,122.639386555774,122.569609890261,122.501891389149,122.436141364042,122.372275260105,122.31021329417,122.249880122997,122.191204538836,130.718664344809,130.507812699109,130.303833617324,130.106397911041,129.915068276456,129.729668710133,129.549941866577,129.375632335805,129.206499745392,129.04231767556,128.882872666284 -2300,121.926390385521,121.851503075104,121.778925986366,121.708553902917,121.6402878983,121.574034873178,121.50970713276,121.447222000453,121.38644954933,121.327340922214,121.269855490042,129.596232286281,129.390332758933,129.19113315951,128.998313116614,128.811572262761,128.630628706097,128.455217639162,128.285090070687,128.120011668018,127.959680582777,127.803918477935 -2310,120.985781216501,120.912440830451,120.841361773559,120.77244110872,120.705582049405,120.640693507332,120.577689679439,120.516489670244,120.457017146129,120.399200018403,120.342970152429,128.47068504852,128.269817431044,128.075481226642,127.887364251613,127.70517381454,127.528499364839,127.357211939182,127.191075855452,127.029863000871,126.873358481043,126.721359680572 -2320,120.039447022012,119.967735287543,119.898233943148,119.83084240012,119.76546607844,119.702015964978,119.640408210082,119.580563758719,119.522408012795,119.465870521575,119.410884697565,127.342320573594,127.146296883748,126.956614457742,126.772992401749,126.595145976192,126.422807924827,126.255727160004,126.093667564109,125.936406895458,125.783735788258,125.635456837382 -2330,119.087894481187,119.017796100875,118.949857663134,118.883980904618,118.820073430179,118.758048281497,118.697823543189,118.639321982649,118.582418839063,118.527072728175,118.473244881224,126.210448699626,126.019303548196,125.834358621532,125.65531820751,125.481905023643,125.31385881044,125.15088813489,124.992717666221,124.839223882823,124.690203065621,124.545463115329 -2340,118.130967276745,118.062388321257,117.995906426099,117.931440972961,117.868901639836,117.808203416895,117.749266221815,117.692014548037,117.636377142724,117.582286711512,117.529679647516,125.07542124522,124.889118314658,124.708811346036,124.534147829708,124.364965182652,124.201010328155,124.042045471977,123.887846971164,123.738204301365,123.592919112812,123.451804366283 -2350,117.167913449536,117.100901468559,117.035952554308,116.972972927859,116.911874406278,116.852573991573,116.794993495322,116.739059195442,116.68470152192,116.631854768689,116.580456829175,123.936811433677,123.755131438307,123.579330257577,123.409128126869,123.24426268382,123.084487642166,122.929571584419,122.779296861176,122.633458586322,122.491752178433,122.354086491803 -2360,116.199153768707,116.133708726001,116.07027781758,116.008769517596,115.949097760183,115.891181538506,115.834944538596,115.780314804533,115.727224431874,115.675609286581,115.625408747032,122.794476554548,122.617509321186,122.446263721663,122.280467626596,122.119865829321,121.964092598988,121.813032577904,121.666491476579,121.524270121248,121.386180834529,121.252046620846 -2370,115.224530490338,115.160636824536,115.098708862294,115.0386573072,114.980359684919,114.92373303021,114.868747393219,114.815332489566,114.763421990318,114.712953247704,114.663867043354,121.648502556774,121.476109920764,121.309208969182,121.147610681928,120.991067137268,120.839345574661,120.692227258067,120.549506439508,120.410989412811,120.276493648523,120.145847002057 -2380,114.243642807481,114.181194958593,114.120667320821,114.061972709715,114.005029137626,113.949759432374,113.896090888978,113.843954951181,113.79328691982,113.744025685441,113.696113482846,120.498256924178,120.330373689998,120.167904923082,120.010593690396,119.858199003943,119.710494607687,119.567267873082,119.428318792048,119.293417062541,119.162336533532,119.035001936047 -2390,113.256236854829,113.195309277643,113.136254502301,113.07898752469,113.023428406018,112.969501901223,112.917137119608,112.866267214492,112.816829099011,112.76876318555,112.722013146543,119.34392487721,119.180566676227,119.022472433814,118.869392522116,118.721083276317,118.577200943165,118.437673700185,118.30230731804,118.170918912305,118.043336129891,117.919396404239 -2400,112.262428217485,112.203005205245,112.145408092451,112.089554031402,112.035365109698,111.9827679883,111.931693570957,111.882076701886,111.833855888938,111.786973049757,111.741373278759,118.185388743453,118.026428598958,117.872498486347,117.723442785128,117.57903425801,117.43905953008,117.30331805144,117.171621151242,117.043791173909,116.919660689373,116.799071770053 -2410,111.262017430573,111.204083201297,111.147928478732,111.093472547498,111.040639498985,110.989357878944,110.939538519951,110.891088942265,110.84400191246,110.798220769624,110.753691950393,117.02204647557,116.867398322719,116.717720915557,116.572779083497,116.432352213256,116.29623314359,116.164227158845,116.03615107118,115.911832382551,115.791108518486,115.673701911932 -2420,110.254797311192,110.198295295584,110.143485075267,110.090332102255,110.03876236273,109.988706183813,109.940097920041,109.892875666616,109.846980996819,109.802358721198,109.758956666518,115.854002602854,115.703693208571,115.558210709353,115.417326905112,115.280827714441,115.148512102922,115.02012489874,114.895484945392,114.774496155249,114.657000788222,114.542850038388 -2430,109.240210388553,109.185121788222,109.131723764081,109.079939701269,109.029697543662,108.980929459917,108.933571538425,108.887563508315,108.842848483946,108.799372730605,108.757085449398,114.681125989036,114.535095215592,114.393749564257,114.256776720111,114.124006634284,113.995299524828,113.870472164399,113.749352150098,113.631777118127,113.517594025613,113.406658493024 -2440,108.218359657945,108.164712722323,108.112711507268,108.062281456774,108.013352449616,107.965858474578,107.919737333781,107.874930371337,107.831382224854,107.789040597536,107.747856048974,113.503121022244,113.361155158109,113.223736608425,113.090650907429,112.96169682862,112.836685381886,112.715438900117,112.597790206159,112.483581852022,112.37266542314,112.264900901334 -2450,107.18905886819,107.136837632749,107.086217777984,107.037126782327,106.98949643655,106.943262528051,106.898364552455,106.854745449833,106.812351363113,106.771131416532,106.731037512227,112.319477354966,112.181665877777,112.048264469815,111.919065300544,111.79387336148,111.672505495286,111.554789511499,111.440563380015,111.329674494512,111.221978998853,111.11731252657 -2460,106.152068475589,106.101256915076,106.052002913153,106.004235958171,105.957889729889,105.912901792707,105.869213315446,105.826768815018,105.78551592168,105.745405163731,105.706389769855,111.130302169627,110.996585122804,110.867142984631,110.741774457595,110.62029065528,110.502514162983,110.388278182147,110.277409434154,110.169664062161,110.065017028763,109.963336845355 -2470,105.107139357046,105.057721388591,105.009817676376,104.963359694045,104.918282987238,104.874526875667,104.832034180949,104.790750977653,104.750626365291,104.711612259198,104.673663198538,109.935339654805,109.805656950286,109.680116090926,109.558522208659,109.440692441966,109.326363229242,109.215422632291,109.107763053155,109.003241349627,108.901722568979,108.803079371893 -2480,104.054012347058,104.005971833185,103.95940279472,103.914238665882,103.870416835007,103.827878355339,103.786567680823,103.746432424429,103.707364272066,103.669371974665,103.632416327513,108.734322728103,108.608614188462,108.48691653709,108.368911705953,108.254542272019,108.143654313685,108.036091567496,107.931706963597,107.830361960994,107.731925939518,107.636275642949 -2490,102.992417746795,102.945738498333,102.900488467612,102.856603024624,102.814021377134,102.772677167077,102.732468262517,102.693402849876,102.655432846983,102.618512829381,102.582599849262,107.526972585311,107.405050761812,107.28699308468,107.172637530315,107.061813004956,106.954358774437,106.850123693671,106.748965503704,106.65075018957,106.5553513929,106.462649873934 -2500,101.922074803322,101.876740582235,101.832793845895,101.790171875195,101.74877062261,101.708557360755,101.669503762144,101.631560389923,101.594680577135,101.558820235446,101.523937679523,106.312764906374,106.194675760476,106.080344482169,105.969594867631,105.862261535746,105.758189111665,105.657231483005,105.559251121256,105.464118461849,105.371711337064,105.281914456613 -2510,100.842691156895,100.798685679019,100.756026478954,100.714618329294,100.674404702738,100.635367250582,100.597455128765,100.560620381365,100.524817738453,100.490004430682,100.45614001903,105.091641408405,104.977345526093,104.866683047908,104.759483760812,104.655587898418,104.55484535341,104.457114960015,104.362263839322,104.270166801199,104.18070579714,104.093769419095 -2520,99.753962254038,99.7112691917454,99.6698817276448,99.6296978451342,99.5906811754193,99.552805230541,99.5160207170817,99.4802811406893,99.4455426102373,99.4117636581828,99.3789050756092,103.863309280202,103.752746982078,103.645695718079,103.541991160897,103.441479060529,103.344014485055,103.249461128895,103.157690681642,103.068582251414,102.982021837292,102.897901846072 -2530,98.6555707239711,98.6141737087591,98.5740421405746,98.5351188831332,98.4972858586535,98.4605570804311,98.4248862697143,98.3902283743204,98.3565408636541,98.3237835547576,98.291918452576,102.627441654131,102.520553299366,102.417055702894,102.316790317746,102.219608311681,102.125369835799,102.033943358115,101.945205055464,101.859038257902,101.775332940371,101.693985257039 -2540,97.5471857157151,97.5070683407233,97.4681767910725,97.4304557412904,97.3938531451154,97.3582953162009,97.3237242674834,97.2901345288442,97.257484911913,97.2257365010637,97.1948524988287,101.383697233385,101.280423245652,101.180421833564,101.083540124905,100.989634606426,100.898570419754,100.810220719813,100.724466089362,100.64119400404,100.560298342896,100.481678939984 -2550,96.4284621929983,96.3896080154607,96.3519405719673,96.3154063227267,96.2799549001043,96.2455388771763,96.2121135562458,96.1796367753489,96.1480332193403,96.1172809306365,96.0873656178334,100.13171959447,100.032000485686,99.9354378605575,99.8418844159803,99.7512018588889,99.6632602289389,99.5779372812867,99.4951179233155,99.4146936999291,99.3365623225769,99.2606272377635 -2560,95.2990401838284,95.2614327274642,95.2249734450403,95.1896105572851,95.1552953515873,95.1219819583308,95.0896271465131,95.058190136743,95.0276324299234,94.9979176500855,94.9690114000573,98.8711364376235,98.774912829721,98.6817317002351,98.5914512095855,98.5039381861555,98.4190674752137,98.336721345563,98.2567889480153,98.1791658205251,98.1037534353411,98.030458784094 -2570,94.1585439813332,94.1221667386778,94.0868996417504,94.0526926466147,94.019498672057,93.987273383584,93.9559749960346,93.9255640929727,93.8960034612218,93.8672579390628,93.839294276825,97.601558781944,97.5087714268899,97.4189146265985,97.3318518995843,97.247455097111,97.1656037778128,97.0861846377244,97.0090909900587,96.9342222897745,96.8614836984831,96.7907856857777 -2580,93.0065812921652,92.9714177268462,92.937326811532,92.9042602124198,92.8721724560516,92.8410207208554,92.8107646466441,92.7813661603038,92.7527893160912,92.7250001491128,92.6979665407632,96.3225801016818,96.2331698999251,96.1465804045545,96.0626803870046,95.981346623101,95.9024632928412,95.8259214333161,95.7516184393428,95.6794576070614,95.6093477162258,95.5412026474347 -2590,91.8427423284479,91.8087758774081,91.7758451136384,91.7439033882566,91.7129068119073,91.6828140537279,91.6535861576271,91.6251863741699,91.5975800065485,91.570734269261,91.5446181583213,95.0337753997379,94.9476834172508,94.8643043607048,94.7835121496189,94.7051883863886,94.6292217806866,94.5555076247842,94.4839473145945,94.4144479118905,94.3469217436098,94.28128603465 -2600,90.6665988388753,90.6338129145457,90.6020262481441,90.5711938504912,90.5412733926751,90.512225012325,90.4840111365609,90.4565963199775,90.4299470961985,90.4040318416731,90.3788206505824,93.7347002140031,93.6518676980616,93.5716423872569,93.4939032447719,93.4185366019755,93.345435606903,93.2744997214876,93.2056342625679,93.1387499823229,93.0737626842191,93.0105928710332 -2610,89.4774390540253,89.4458787073954,89.4152799633214,89.3855995405474,89.3567967164087,89.3288057385688,89.3015917045376,89.275148098296,89.2494426653926,89.2244449267843,89.200126058364,92.4248001314896,92.3452579455445,92.2681298741985,92.1933892405828,92.1209270079005,92.0506406716688,91.9824337783719,91.9162154859886,91.8519001622385,91.7894070168044,91.7286597642455 -2620,88.2746396649513,88.2442247651321,88.2147361589403,88.1861321721964,88.1583735932861,88.1314234939478,88.1052470654749,88.0798114688228,88.0550856972589,88.0310404503353,88.0076480181356,91.1033239911738,91.0269579210489,90.9529909579097,90.8813119121372,90.8118163531082,90.7443512624303,90.6788242479101,90.6152055948366,90.5534132120059,90.4933696453812,90.4350017555611 -2630,87.0580281855391,87.0287420336022,87.000347402234,86.9728041990342,86.9460746997048,86.9201233757825,86.8949167371822,86.8704231881022,86.8466128949824,86.8234576653431,86.8009308364979,89.77002096111,89.6967350865243,89.6257488059519,89.5569556622576,89.490255662728,89.4255547962579,89.3627645931361,89.3018017230889,89.2425876277869,89.185048184399,89.1291110869938 -2640,85.8270846882579,85.7989105704131,85.7715937359367,85.7450956489303,85.7193800486954,85.6944127842922,85.670161663317,85.6465963135072,85.6236880559177,85.6014097885444,85.5797358794279,88.4243499314687,88.3540861183212,88.2860244163942,88.2200629981109,88.1561062124945,88.0940641243211,88.0338520938974,87.9753903933219,87.918603855618,87.8634215534808,87.8097765047788 -2650,84.5804379182145,84.5534152660321,84.527214583509,84.5017989338394,84.4771335603578,84.4531857280538,84.4299245787049,84.407320998294,84.3853474955093,84.363978090251,84.3431882112177,87.0657436983054,86.9984440723996,86.9332510923595,86.8700674580021,86.8088017646198,86.7493680635676,86.6916854615471,86.6356777546464,86.5812730936994,86.5284036778613,86.4770054736807 -2660,83.3180612390695,83.2921150807374,83.2669577874919,83.2425539259075,83.2188701530575,83.19587506461,83.1735390559704,83.1518341951938,83.1307341065176,83.1102138634812,83.0902498907466,85.6928954416259,85.6286161640558,85.5663473201793,85.5059961193338,85.4474753898248,85.3907031603099,85.3356022780388,85.2820705869692,85.2300023137453,85.1794017123534,85.1302076335847 -2670,82.0392338060996,82.014401350699,81.9903236346375,81.9669667685812,81.9442988619684,81.922289877814,81.9008809296054,81.8800608690652,81.8598206815153,81.8401364766352,81.8209856585395,84.3056384957582,84.2442030808829,84.1846867699902,84.1270010932271,84.0710629319449,84.0167941204665,83.9641210828783,83.9129745012814,83.8632890123968,83.8150029297168,83.7680579887443 -2680,80.7424991054066,80.7187073523509,80.6956383732317,80.6732597287169,80.6515408918803,80.6304531093402,80.6099692743149,80.5900638104315,80.5707125652386,80.5518927124763,80.5335826622994,82.9033983924275,82.8447847615517,82.7879657500223,82.7328922479654,82.6794850961345,82.6276698469137,82.5773764191885,82.5285387830767,82.4810946715773,82.4349853164742,82.3901552061626 -2690,79.4279821236853,79.4052657110939,79.3832391537127,79.3618642701204,79.3410791988585,79.320897779959,79.301294095063,79.282243688495,79.2637234655312,79.2457115990299,79.2281874436575,81.4843217486486,81.4285079764025,81.3744339597015,81.3220196568161,81.2711898584975,81.221873828954,81.1740049783589,81.127520563678,81.0823614150301,81.0384716850518,80.9957986190593 -2700,78.0935956269846,78.0718839085126,78.0508312241006,78.0304080190454,78.0105864796306,77.9913404068083,77.972645100712,77.9544772549455,77.9368148596952,77.9196371128033,77.9029243380736,80.0487023349478,79.9955555712281,79.9440633148982,79.894149540421,79.8457428067736,79.7987759172389,79.7531856090451,79.7089122698112,79.6658996781679,79.6240947661602,79.5834474013435 -2710,76.7393940987897,76.7187188147948,76.6986708698004,76.6792221405925,76.6603461600492,76.6420179970206,76.6242141465072,76.6069124291296,76.5900918989892,76.573732759094,76.5578162836645,78.5944468068267,78.5440110858705,78.4951440004728,78.4477735322434,78.4018320023688,78.3572557497955,78.3139848376293,78.2719627848807,78.2311363210671,78.1914551614109,78.1528718006597 -2720,75.3636329858332,75.3439262036785,75.3248170873549,75.3062788564618,75.2882863068892,75.2708156965392,75.2538446408375,75.2373520170843,75.2213178767821,75.2057233651619,75.1905506472505,77.1215852209347,77.0737349533772,77.0273345993343,76.9823534941141,76.9387275376952,76.8963964307387,76.8553033971801,76.8153949307389,76.7766205630051,76.7389326509665,76.7022861821182 -2730,73.9651817263447,73.9464719823418,73.9283294471792,73.9107287146203,73.893645873302,73.8770583983956,73.8609450525468,73.8452857951918,73.8300616994356,73.8152548757506,73.8008484018779,75.6276292144849,75.5823276082931,75.5384317464843,75.4958772290697,75.4546035286158,75.4145537036169,75.3756741369541,75.3379142968893,75.3012265183905,75.2655658027758,75.2308896339259 -2740,72.5431290280362,72.5253960116352,72.5082003818366,72.4915180773333,72.4753264520392,72.4596041725589,72.4443311244359,72.4294883263256,72.4150578513234,72.4010227547454,72.3873670077783,74.1123357025503,74.069557449954,74.0281053005299,73.9879185597794,73.9489401797798,73.9111164894967,73.8743969486829,73.8387339229663,73.8040824780579,73.7704001911862,73.7376469781135 -2750,71.0958831964234,71.0790628106865,71.0627519044716,71.0469276770162,71.0315686679998,71.0166546604778,71.0021665921202,70.9880864739511,70.9743973158589,70.9610830582135,70.9481285090389,72.5741737086814,72.5338553726178,72.4946976021054,72.4567313464441,72.419905205717,72.3841686044142,72.3494739135721,72.3157762393546,72.2830332295862,72.2512048964613,72.2202534538853 -2760,69.6212360147459,69.605352224911,69.5899493514023,69.575005880163,69.5605015614551,69.546417318339,69.5327351629805,69.5194381200289,69.5065101563758,69.4939361166712,69.4817016640765,71.0108143169275,70.972800620144,70.9359625270873,70.9002463544824,70.865601637311,70.8319808913,70.7993393961434,70.7676349973495,70.7368279249012,70.7068806270656,70.6777576179105 -2770,68.1180465393934,68.1030785439597,68.088563550995,68.0744813032637,68.0608127335285,68.0475398784428,68.0346457998035,68.0221145124561,68.0099309182002,67.9980807451113,67.9865504917883,69.4210851134829,69.3854050643102,69.3508272707421,69.3173014497324,69.2847803297828,69.2532194288865,69.2225768518375,69.1928131049419,69.1638909264375,69.1357751310688,69.1084324674704 -2780,66.5843147037006,66.5702415163878,66.5565940725129,66.5433533415323,66.5305014103984,66.5180214027292,66.5058974048844,66.4941143982843,66.4826581973602,66.4715153925865,66.4606732981375,67.8030655923401,67.7696549887913,67.7372754058456,67.7058798588637,67.6754241744377,67.6458667832983,67.6171685312658,67.5892925064193,67.5622038809035,67.5358697659312,67.5102590787228 -2790,65.0178549168622,65.0046553770575,64.9918549815491,64.9794358961371,64.9673813334451,64.9556754772321,64.9443034131675,64.9332510654512,64.9225051387046,64.912053064619,64.9018829529339,66.1545480056578,66.1233423531312,66.0930986077318,66.0637729809836,66.0353243017501,66.0077138236099,65.9809050490019,65.9548635684414,65.9295569133427,65.9049544211068,65.8810271113061 -2800,63.4162742978174,63.4039270807116,63.3919530733085,63.3803356072063,63.3690589919956,63.3581084445769,63.3474700245106,63.3371305748235,63.327077667737,63.317299554836,63.3077851212815,64.4731102141604,64.4440447975735,64.415874301262,64.38855803046,64.3620577202878,64.3363373571012,64.3113630153795,64.2871027085788,64.2635262525964,64.2406051406011,64.2183124281507 -2810,61.7767195677176,61.7652383944638,61.7541041282596,61.7433012808369,61.7328152723726,61.7226323658535,61.7127396070419,61.7031247695055,61.6937495738048,61.6846285279769,61.6757533464129,62.7560900611626,62.7291000128289,62.7029400265993,62.6775723989456,62.6529616752113,62.6290744844389,62.60587938855,62.5833467444262,62.5614485776395,62.5401584666845,62.5194514367167 -2820,60.095624802691,60.0849510939485,60.0745997507789,60.0645563868848,60.0548074594194,60.0453402080718,60.0361425993504,60.0272032755617,60.0185115080315,60.0100571541484,60.0018306178938,61.0005451401103,60.9755762587353,60.9513639542653,60.9278841670521,60.9051041567696,60.8829931051843,60.8615219771788,60.8406633936496,60.8203915151314,60.8006819350896,60.7815115819673 -2830,58.3702755230403,58.3603874267216,58.3507978337962,58.3414934287796,58.3324616765179,58.3236907658563,58.3151695581118,58.3068875398862,58.2988347798023,58.2910018887725,58.2833799834912,59.201938261766,59.1789723575138,59.1567112456614,59.1351229781754,59.1141775088849,59.0938465540543,59.074103465051,59.0549231118858,59.0362817765735,59.0181570553473,59.0005277688878 -2840,56.5962574251198,56.5871637456788,56.5783444803655,56.5697873929039,56.5614809638394,56.5534143388102,56.5455772812289,56.5379601289491,56.5305537545326,56.5233495287609,56.5163392871054,57.357500451166,57.3364103021364,57.3159665939673,57.2961400583996,57.2769031675002,57.2582300062206,57.2400961559979,57.2224785882852,57.2053555670495,57.1887065593569,57.1725121532777 -2850,54.7686724086359,54.7603182114602,54.7522159954608,54.7443545298248,54.7367232413618,54.7293121670692,54.7221119107376,54.7151136032121,54.7083088659519,54.7016897775644,54.6952488430528,55.4618551497509,55.4426379416606,55.424009158904,55.4059421861985,55.38841198935,55.3713949995749,55.3548690078386,55.3388130681981,55.3232074092806,55.308033353097,55.2932732404973 -2860,52.8819145270167,52.8743051150524,52.8669251254865,52.8597643370541,52.8528131267647,52.846062426764,52.8395036848696,52.8331288284302,52.8269302311832,52.820900682815,52.8150333609928,53.5101472407736,53.4926702226482,53.4757276711571,53.459295441486,53.4433508214166,53.4278724266371,53.4128401051064,53.3982348495599,53.3840387173703,53.370234757043,53.356806940717 -2870,50.9298307741777,50.9229401999799,50.9162572872799,50.9097727881416,50.9034779957129,50.8973647052268,50.8914251783219,50.8856521103676,50.880038600498,50.8745781240896,50.8692645074718,51.4945963227155,51.4788490429852,51.4635828074135,51.4487759074568,51.4344079213076,51.4204596199541,51.4069128813601,51.3937506119402,51.3809566746338,51.3685158229248,51.3564136402496 -2880,48.9042896236109,48.8980914998915,48.8920800877321,48.8862470757287,48.8805846385624,48.8750854019792,48.8697424107491,48.864549099322,48.8594992649163,48.8545870427998,48.8498068835772,49.4084336376015,49.3943424001609,49.3806811333399,49.3674304546589,49.3545721292828,49.3420889863206,49.329964842355,49.3181844314639,49.3067333411177,49.2955979533709,49.2847653908511 -2890,46.7957762132094,46.7902437443092,46.7848778599192,46.7796711478539,46.7746166292359,46.7697077272905,46.7649382387952,46.7603023079308,46.7557944022989,46.7514092908934,46.7471420238584,47.2421692640004,47.2296596537324,47.2175313092844,47.2057670631994,47.1943507633915,47.1832671991707,47.1725020336528,47.1620417419014,47.1518735542573,47.1419854043448,47.1323658813152 -2900,44.5930868834589,44.5881928976516,44.5834462029579,44.5788402486425,44.5743688667463,44.5700262445342,44.5658068992822,44.5617056551878,44.5577176221904,44.5538381765167,44.5500629428049,44.9833942277677,44.9724378947071,44.9618151377485,44.951510951961,44.9415112190163,44.9318026426547,44.92237268972,44.9132095361844,44.9043020177021,44.8956395842352,44.8872122583775 -2910,42.2799660800708,42.2757031657274,42.2715684944862,42.2675563651644,42.2636614095763,42.2598785685748,42.2562030701249,42.2526304092233,42.2491563294788,42.2457768061917,42.2424880308071,42.6180522003692,42.6085225877237,42.5992827520479,42.5903196745025,42.5816211045782,42.5731755042324,42.5649719968482,42.5570003205028,42.5492507851539,42.5417142333501,42.5343820041368 -2920,39.8388300333339,39.8351667536236,39.8316136279946,39.8281657616084,39.824818545402,39.8215676355347,39.8184089345789,39.8153385742936,39.8123528998214,39.8094484551715,39.8066219698814,40.1266741856633,40.1185344210058,40.1106418853167,40.1029854838136,40.0955547757743,40.0883399270314,40.0813316665653,40.0745212467583,40.0679004069758,40.0614613401445,40.0551966620442 -2930,37.2438952999428,37.2407994157408,37.2377965794946,37.2348826584473,37.2320537610135,37.2293062194413,37.2266365739458,37.2240415581766,37.2215180858861,37.2190632386811,37.2166742547711,37.4847526201682,37.4779176587061,37.4712900421995,37.4648604768426,37.4586202160777,37.4525610208921,37.4466751235382,37.4409551943101,37.4353943110974,37.4299859314421,37.4247238668615 -2940,34.4609033921338,34.4583574305346,34.4558879526583,34.4534915630279,34.4511650642228,34.4489054426478,34.4467098555064,34.4445756188724,34.4425001967444,34.4404811909898,34.4385163321078,34.6569277185914,34.6513439483134,34.6459293664533,34.6406763982697,34.6355779145418,34.6306271992805,34.6258179202231,34.6211441018107,34.6166001004217,34.612180581639,34.607880499359 -2950,31.4390325302813,31.4369990092808,31.4350265460602,31.4331124313534,31.4312541138461,31.4294491888299,31.42769538782,31.4259905690461,31.4243327087247,31.4227198930438,31.421150310798,31.5938499317644,31.5894217580687,31.5851275844203,31.5809614191273,31.5769176224689,31.5729908812172,31.5691761853542,31.5654688067431,31.5618642795822,31.5583583824579,31.554947121852 -2960,28.1028168888058,28.101257203988,28.0997443226259,28.0982761691317,28.0968507888569,28.0954663394126,28.0941210827197,28.0928133777348,28.0915416737693,28.0903045043538,28.0891004816011,28.2196614984515,28.2163166308658,28.2130728448859,28.2099256267369,28.2068707274524,28.2039041437284,28.2010221004294,28.1982210345552,28.195497580552,28.1928485568192,28.1902709533103 -2970,24.3209267802065,24.3198210242276,24.318748429892,24.3177075274654,24.3166969327988,24.3157153411942,24.3147615217758,24.3138343123499,24.3129326146767,24.3120553901285,24.3112016557051,24.4030107389703,24.4006408180068,24.3983424037428,24.3961123079863,24.3939475293035,24.3918452395342,24.3898027714716,24.3878176075679,24.3858873695873,24.384009809099,24.3821827987399 -2980,19.8437772488535,19.8430839205536,19.8424113696207,19.8417586758741,19.8411249726781,19.8405094431073,19.8399113164253,19.8393298648743,19.8387644007151,19.8382142735135,19.83767886765,19.8945111716972,19.8930385895336,19.8916103594115,19.8902245073417,19.8888791747687,19.8875726102464,19.8863031618382,19.8850692701429,19.8838694619109,19.8827023441736,19.8815665988451 -2990,14.0194488542204,14.019128463856,14.018817664886,14.0185160329622,14.0182231684044,14.0179386944373,14.0176622555655,14.0173935160974,14.0171321587863,14.0168778835745,14.016630406453,14.0425210341658,14.0418475561034,14.0411943132275,14.040560407066,14.0399449915658,14.0393472693167,14.0387664881145,14.0382019377923,14.0376529473327,14.0371188822043,14.0365991419119 -3000,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 diff --git a/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_trajectories_Gemini_Portugal_October_2023.csv b/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_trajectories_Gemini_Portugal_October_2023.csv deleted file mode 100644 index 70bf86cd8b292d044b69c5f09b890c5bc572b805..0000000000000000000000000000000000000000 --- a/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_trajectories_Gemini_Portugal_October_2023.csv +++ /dev/null @@ -1,10468 +0,0 @@ -Z,Vz -947.17079006452,266.476582684254 -952.408854755109,267.390293949204 -957.721908885436,268.205331254352 -962.893686678729,268.92992290908 -967.935277028506,269.772339064892 -972.844148838189,270.522823676825 -978.479436281042,271.450397039 -984.045025175857,272.295414904855 -989.46245253301,273.046355493936 -995.143711128882,273.893232597819 -1000.67342406654,274.645884561423 -1006.25242577866,275.498205714394 -1011.81334799653,276.216906970663 -1017.22379404999,276.891713405877 -1022.51943054008,277.52579751581 -1027.670771966,278.040774503981 -1033.29197724209,278.459314995198 -1038.89798695069,278.057511812541 -1044.33037834772,277.641465534316 -1050.05153979635,277.25424378326 -1055.59591896667,276.85171110614 -1060.94032381435,276.432365749117 -1065.93386763748,275.98765403273 -1070.77058949371,275.529780015635 -1076.62925393222,275.16939855015 -1082.30735651391,274.793191513887 -1088.22692878174,274.444078520381 -1094.00424956864,274.082277110944 -1099.6030402781,273.701770075085 -1104.93305454502,273.291748471182 -1110.09622089736,272.86326499749 -1115.26671749867,272.435239262902 -1120.01263822551,271.953843395605 -1124.60651545992,271.453492028799 -1129.95224307411,271.053316610963 -1135.12989361732,270.630175182406 -1140.5674946255,270.244904330076 -1145.85003632654,269.838825456805 -1150.96546303559,269.408444810706 -1156.20616529772,268.998373273651 -1161.28032450466,268.562221942792 -1166.91529391956,268.220135172296 -1172.62817791656,267.893313442038 -1178.16182896958,267.539156564182 -1183.08936596136,267.079693447841 -1187.85674910156,266.591301953876 -1193.29627674572,266.229410577812 -1198.43226033658,265.811829377975 -1203.40195129172,265.362566283556 -1208.59827641953,264.961138908048 -1213.62617541232,264.524840623991 -1218.85869856139,264.133144954174 -1223.81784725423,263.64664447219 -1228.61253205365,263.091024243813 -1233.69168672385,262.568977996779 -1238.60147590676,261.976012803406 -1243.99910587916,261.465840372391 -1249.05301857601,260.841552097905 -1253.93509166301,260.12956458582 -1259.06939518129,259.429768582636 -1264.02725323832,258.64110980737 -1269.2613875289,257.900562904353 -1274.87159197401,257.283585934938 -1280.29184251276,256.616127897196 -1285.30977720806,255.840924080042 -1290.15107269634,255.020603326328 -1295.53806345433,254.359672465593 -1300.71643742905,253.645353769464 -1305.71333430403,252.884967112957 -1310.68584109186,252.124249408025 -1315.4811873631,251.317299338632 -1320.53691846523,250.595236164045 -1325.49895832677,249.852862403312 -1330.28321300215,249.062510025541 -1334.96516833784,248.246753239983 -1339.47550840904,247.383520493442 -1344.86420037651,246.812648420179 -1350.1130434199,246.208406497595 -1355.17586279719,245.554731989405 -1360.2371686881,244.910373822164 -1365.11649481871,244.211812268377 -1369.56512607261,243.373082344124 -1373.59231212678,242.401314819337 -1377.4619835103,241.382235807176 -1382.48855684046,240.784706172528 -1387.33296694049,240.129448661339 -1391.71413197044,239.34362431059 -1396.08897466729,238.5636227275 -1400.29745191136,237.731451096224 -1405.40461633168,237.241331452365 -1410.32698155129,236.691079072619 -1415.17406445563,236.119312625947 -1419.98439076757,235.543869760825 -1424.6165255822,234.908699849353 -1429.08001308644,234.216451269103 -1433.37353412666,233.466432610336 -1438.07363459777,232.882119543187 -1442.28119687775,232.115887771341 -1446.32475073467,231.293939244625 -1451.07421459717,230.763964068696 -1455.64572962625,230.169669111831 -1460.16205117189,229.559358136055 -1464.65336059912,228.946119589297 -1468.97266344417,228.269813643283 -1473.33452218325,227.618113694211 -1477.52735406035,226.903552755013 -1482.14594047398,226.375256096209 -1486.4019234589,225.702753906301 -1490.49119790305,224.9699433228 -1495.3502457647,224.572475316779 -1500.02675111883,224.103717927825 -1504.62968005107,223.610358861961 -1509.53990871022,223.257806108843 -1514.26570460847,222.833655809162 -1518.45214091168,222.181978147471 -1522.47282470694,221.483134831178 -1527.05185121853,221.035062228579 -1531.38477358455,220.488855146953 -1535.54814850649,219.873513648262 -1539.81714994562,219.312884576915 -1543.91809323985,218.685078039959 -1548.16897981314,218.131109870474 -1552.5754651815,217.654084955875 -1556.80996004166,217.108608377501 -1561.43907708571,216.74719761571 -1565.89004787942,216.310129226046 -1570.49646828333,215.949763644722 -1575.16817655143,215.623359676188 -1579.66016500197,215.219348385544 -1583.52378427242,214.5327480803 -1587.22938046199,213.779828909734 -1591.98962045804,213.519251179304 -1596.34131045717,213.074576242816 -1600.52148411533,212.557073186977 -1605.29626319655,212.321261348945 -1609.88778390286,212.004414930222 -1614.29954595305,211.6080174316 -1618.67015406403,211.197830328291 -1622.86830969124,210.712721457324 -1627.44219181469,210.409809656078 -1631.83788510071,210.026543495713 -1635.64519510285,209.371164467417 -1639.59248733011,208.789276680207 -1643.3788308396,208.139255806556 -1647.58009096455,207.692782530493 -1651.61335944194,207.172223973155 -1655.81256287384,206.737392050352 -1660.06150444642,206.332239403162 -1664.14107679413,205.852134975291 -1667.72028534566,205.14012952552 -1671.1489432294,204.374743565481 -1675.76093424598,204.184890713216 -1680.24098823887,203.935528738577 -1684.54539914148,203.607272052945 -1688.37797306469,203.058539125518 -1692.05319659131,202.440738543657 -1696.05435921619,201.986052834148 -1699.92233425771,201.47357875991 -1703.63205844788,200.891550962485 -1707.39969693582,200.344530875702 -1711.01203970798,199.728796531721 -1714.88970529694,199.248616680497 -1719.09068783518,198.933806547177 -1723.12420153355,198.543293837703 -1727.21719545755,198.187305678801 -1731.14584801591,197.756082644485 -1735.32371972469,197.452088541258 -1739.48769152839,197.145583987973 -1743.48533304708,196.761879962407 -1747.52510995084,196.404467429888 -1751.40215649195,195.971260549492 -1755.4899716742,195.645807618213 -1759.31256972496,195.195405162697 -1762.97874123022,194.674542381964 -1766.43589485376,194.056474798424 -1769.74726682433,193.373061277613 -1773.59559253079,192.96064004603 -1777.16811085045,192.42021653734 -1780.59178755274,191.812747591528 -1784.62583846259,191.515395077727 -1788.49791527255,191.140655854833 -1792.59265915776,190.879902185718 -1795.85276555185,190.213411882507 -1798.97340837298,189.485484694979 -1802.61452047815,189.023083003447 -1806.10536127869,188.490799743161 -1809.78274643908,188.056563592372 -1813.51560051358,187.66058491057 -1817.09580933052,187.195296018224 -1821.23519457982,187.015153970679 -1825.21031628544,186.757011964955 -1829.11687550532,186.468418353055 -1832.83984020297,186.097871947803 -1836.41084946474,185.656675632677 -1840.19511909546,185.327110660635 -1843.82578469067,184.92564403236 -1847.50047438638,184.550258298558 -1851.51557660168,184.349405464938 -1855.37051422828,184.071500012552 -1859.31637489215,183.842259005877 -1863.10414331227,183.538488934514 -1866.79528589737,183.190276848762 -1870.17687890634,182.692145905798 -1873.41701672828,182.130216920302 -1877.28182510562,181.883244384448 -1880.99120526961,181.562572094993 -1884.65504488676,181.221963659529 -1887.94441059715,180.700081203246 -1891.09535148667,180.114435066154 -1894.70480871963,179.762623055845 -1898.16663235695,179.342963446418 -1901.90629895165,179.065562500066 -1905.2744832921,178.607440636884 -1908.50232238002,178.084018527728 -1911.93544949554,177.668991241197 -1915.22650173156,177.187878251025 -1918.4741881812,176.691959506009 -1921.71170153553,176.200010746955 -1924.81323794003,175.647402581631 -1928.80895655029,175.547312814555 -1932.64665916169,175.370875579645 -1936.36605539105,175.138546502406 -1939.24251046255,174.487544129218 -1941.99395077855,173.783748287917 -1945.00245105352,173.215787302399 -1947.88236717955,172.590751744426 -1951.14250311489,172.16018940659 -1954.83332837771,171.952008523444 -1958.37583328047,171.674120057079 -1961.95037240243,171.41505609934 -1965.38012846379,171.088187326761 -1968.34501722315,170.533764188381 -1971.2838969679,169.975213439771 -1974.09703001995,169.360600805198 -1977.60445411397,169.098645987566 -1980.96961167134,168.770292196217 -1984.01064134762,168.284447662762 -1986.70369845754,167.631088801088 -1989.27876195345,166.927137499246 -1992.78510358981,166.695366675009 -1996.14975996518,166.396196501602 -1999.99556901717,166.340880992765 -2003.78108630185,166.260214070505 -2007.41688513584,166.107618908114 -2010.89207452378,165.876572760821 -2014.22677359146,165.57883740781 -2018.1135590196,165.560292681796 -2021.87179217672,165.47769795078 -2025.48129826423,165.322155918002 -2029.31234829584,165.278831010553 -2032.99256371763,165.16094114855 -2037.0434653322,165.230306753611 -2040.43762301176,164.968907307267 -2043.69382943777,164.639865719564 -2046.78200555615,164.231130236709 -2049.7413630847,163.761440632148 -2053.19268371133,163.543357754146 -2056.40016405243,163.204099661263 -2059.47548061959,162.803240499724 -2063.11621012781,162.687649092462 -2066.61210788304,162.501494216253 -2070.12868639429,162.327270586354 -2073.54951735892,162.107480999604 -2076.83211001664,161.818830540848 -2080.25765301581,161.605362406061 -2083.54488753143,161.324908150039 -2086.68591383471,160.974566759368 -2090.40884491249,160.919200766538 -2093.98485038973,160.789780846743 -2097.69076168821,160.72881813048 -2101.25029910313,160.594999310732 -2104.1569269912,160.136653265432 -2106.89803405695,159.599104908039 -2109.52138725605,159.008078935012 -2112.91785682154,158.809167280567 -2116.17740665265,158.543778555912 -2119.57616351416,158.349039162955 -2123.05812304967,158.200307197301 -2126.40077099313,157.983408524219 -2129.1636949633,157.480791158475 -2131.80867095637,156.924540423834 -2135.46538862245,156.878981942576 -2139.12559884076,156.837279237036 -2142.64155954476,156.723451874012 -2145.96715788391,156.515977129883 -2149.15842717889,156.24295008854 -2151.98172171716,155.789824119875 -2154.71680753212,155.297137793168 -2157.33521707566,154.749496207448 -2160.64876764554,154.555872725873 -2163.82871948373,154.298194569839 -2166.23463121484,153.656831331652 -2168.74780513155,153.074387763987 -2171.15126941646,152.444537348457 -2174.30334048961,152.197395389005 -2177.32710595972,151.888168527736 -2180.10496009142,151.459278973662 -2182.90706195891,151.048524059457 -2185.5914266191,150.585240932679 -2188.83773505685,150.408772381342 -2191.95339728068,150.168103869915 -2195.17777435756,149.984842247533 -2198.16140087905,149.684381414016 -2201.02229107852,149.327914692572 -2204.12207209801,149.094235474121 -2207.09584583012,148.801663173871 -2210.42546779845,148.69050999007 -2213.5638198412,148.484811165098 -2216.57518804831,148.217094807556 -2219.18520979466,147.751647455675 -2221.68396406919,147.236230105995 -2224.62194291099,146.946002006452 -2227.1845550498,146.472315415113 -2229.63759843181,145.949595534616 -2232.48444045734,145.629667726072 -2235.21352593594,145.254772060207 -2238.49369681459,145.159428318066 -2241.37561850143,144.867220228809 -2244.13893971543,144.521835195341 -2246.57844620078,144.0173706892 -2248.91261572436,143.466357057809 -2252.08813691919,143.341464928344 -2255.78371273649,143.479037338631 -2259.33704779902,143.545365831791 -2262.11853333516,143.225361797791 -2264.78481863715,142.85193736393 -2267.42434225266,142.469510538656 -2269.89294876373,142.006265844827 -2272.25586739799,141.493415991692 -2275.0992726899,141.228088165939 -2277.82609934878,140.90723888622 -2281.01435299164,140.820787772907 -2284.09057098253,140.679155434468 -2287.0434591193,140.47827379963 -2290.08387391172,140.323598348723 -2293.00211121602,140.110151282251 -2296.14967528809,140.012754267931 -2298.85160157739,139.694083510163 -2301.44146866476,139.323368617476 -2303.75550182055,138.818448404347 -2305.96910393169,138.268385508949 -2309.29078923564,138.277610276911 -2312.45471469964,138.209979636957 -2315.49329084729,138.08085128608 -2318.15026317322,137.762821957257 -2320.69694973578,137.39209893987 -2323.70556223707,137.256848934798 -2326.49491200136,137.014449982955 -2329.17023876909,136.716574657072 -2332.36698854852,136.683581392729 -2335.43776608908,136.586902008836 -2338.61440560641,136.544756495175 -2341.74224045916,136.477749221582 -2344.74615082155,136.350027527003 -2347.55942025378,136.127595137361 -2350.25811146585,135.851420666599 -2353.05975088989,135.62811980757 -2356.28961550828,135.621471845765 -2359.3927143386,135.550244365903 -2361.55955693841,135.012720539969 -2363.6311108298,134.431935424518 -2366.77751635662,134.393626634114 -2370.3044712456,134.546060917677 -2373.69606823405,134.629113681547 -2376.15900102422,134.24712925447 -2378.51802451198,133.817391805058 -2381.31108021501,133.609762218816 -2384.14946062174,133.424349268816 -2386.87298817192,133.18397406207 -2389.43001271907,132.862368218142 -2391.88059867044,132.49169856877 -2394.20946541995,132.062726592952 -2396.76252012565,131.750332134919 -2399.20946870234,131.388992765183 -2401.58872628369,130.996658254316 -2403.8671558447,130.55806966717 -2406.46151333049,130.282173832339 -2408.51350239793,129.738856446539 -2410.47459382674,129.15598694849 -2413.5379697863,129.13016404347 -2416.48073686729,129.043527153356 -2418.72147770232,128.60831985866 -2420.83997811773,128.116929109138 -2422.86597072926,127.587657501461 -2425.37598960396,127.304575798782 -2427.78215241187,126.973415854427 -2430.29408509827,126.698155976728 -2432.70314937155,126.375996662294 -2435.01156489161,126.006066696763 -2437.12204590191,125.542703306981 -2439.1408719342,125.036933922536 -2441.53292807925,124.725333096155 -2443.69724103534,124.304295658298 -2445.76860156982,123.842243285924 -2447.953031962,123.441676283637 -2450.0441144574,122.998248407221 -2452.86358177318,122.924520659751 -2455.26164935675,122.6437793314 -2457.56029495973,122.317217940945 -2460.8257936186,122.477041842084 -2463.96632464649,122.57432965888 -2466.51452369305,122.374604463906 -2468.87208548547,122.08298078275 -2471.13160427726,121.745934036957 -2474.18599114685,121.809937998048 -2477.12184651951,121.81401513417 -2479.35739568096,121.468854502991 -2480.90582470082,120.784958465824 -2482.38039848992,120.07001584211 -2485.01411299433,119.941621948477 -2487.54209315068,119.761585257167 -2489.83216621171,119.465108695598 -2491.91339206655,119.068714664966 -2493.90539652001,118.633406234112 -2496.40655203399,118.458506309585 -2498.80627704343,118.233095370993 -2501.39976063809,118.107138891139 -2503.54969324729,117.761829328769 -2505.6086920686,117.373995668817 -2508.52251883406,117.418379298083 -2511.32294804199,117.407125839918 -2513.76242876716,117.216312686133 -2516.18567853138,117.018875453198 -2518.51011927048,116.774587564968 -2521.17016867543,116.69858017984 -2523.72445756584,116.571518796431 -2525.94230887903,116.277888843734 -2528.31447144644,116.063418564012 -2530.58950074909,115.803161964964 -2533.44291952076,115.834777758807 -2536.18506382765,115.811076286768 -2538.28593904597,115.466600361214 -2540.3783435858,115.122123071824 -2542.38208587236,114.737783317338 -2544.3676980125,114.346864529144 -2546.26794278238,113.916912077827 -2548.54523990914,113.68106635838 -2550.97199365453,113.522013215959 -2553.30053843804,113.31692216672 -2556.30261352746,113.449930365486 -2559.18953360892,113.523605393209 -2561.37523401166,113.247256428505 -2563.43099878896,112.908301586925 -2565.39964402066,112.527981147549 -2568.25143103515,112.593935779743 -2570.99266727869,112.603809218447 -2573.70767644965,112.600521673333 -2576.2375458153,112.503514901034 -2578.66635528816,112.357415484611 -2580.63722217122,111.982313535178 -2582.5236037196,111.570686938015 -2584.90581387108,111.410157310508 -2587.04872363125,111.131019676208 -2589.1022463074,110.81129127427 -2591.38559145938,110.609355481192 -2593.57552656742,110.361483030117 -2595.99751620476,110.232957879702 -2598.78883867143,110.290935955901 -2601.4718278243,110.29352702011 -2603.87561728036,110.156882197929 -2606.18252869185,109.972463831807 -2608.46928013766,109.780064995985 -2609.7554354751,109.088959241072 -2610.97788062613,108.372609734671 -2613.05645898762,108.091135037992 -2615.04812775199,107.76947324649 -2616.97581543738,107.417760978484 -2618.8795810833,107.05995922862 -2620.70182482518,106.66515879612 -2622.47423420855,106.24921236584 -2624.16915485111,105.799211521019 -2626.32918507917,105.586468097452 -2628.03297678611,105.149064218366 -2629.66155791788,104.679016228767 -2631.70184644937,104.420622281888 -2633.65717022276,104.121131309518 -2635.71765397545,103.879403738003 -2637.8092507671,103.655206869895 -2639.81452813013,103.392173792497 -2642.2128645132,103.326826203121 -2644.5159066564,103.214821181587 -2646.51785077293,102.953129960591 -2647.82382705225,102.347397220589 -2649.0669564743,101.715982973078 -2651.56690082219,101.718992629461 -2653.96888042505,101.675779524924 -2656.0424373527,101.467029017562 -2658.24027842963,101.323419472161 -2660.34918278977,101.137196098203 -2662.62287417921,101.035903970098 -2664.80546792998,100.890427524668 -2667.56318224657,101.033942785326 -2670.50969774,101.269637838666 -2673.34520970471,101.448128139995 -2675.03429352752,101.05181489398 -2676.64953304464,100.623459968335 -2679.17487958662,100.655522406476 -2681.42726651969,100.549871213547 -2683.58930738962,100.399707926374 -2685.43712012365,100.095203207784 -2687.20662897895,99.7540668893102 -2689.12337277768,99.4909167664042 -2691.09583185306,99.258366823592 -2692.98648234575,98.9878411211222 -2694.46774436138,98.5147782805756 -2695.88183593641,98.0114369728061 -2697.82354657027,97.779068227187 -2699.11459486011,97.2246897943565 -2700.34436842731,96.6438789429192 -2702.06972355932,96.3170987977712 -2703.72114832014,95.9569324783324 -2705.36448811524,95.5956113666568 -2707.20050064971,95.3353864585945 -2708.95952285759,95.0385845157639 -2711.23867617948,95.0053239526811 -2713.42782496511,94.928193451843 -2716.12662338418,95.1060882939866 -2718.66653176398,95.2037282734487 -2721.10872678218,95.2521598797744 -2723.14031732931,95.0944461931517 -2725.08921878637,94.897435986695 -2726.7157363031,94.5404290551435 -2728.91935738338,94.4767042620475 -2731.03535014238,94.3690115444168 -2733.62884712826,94.5013606330114 -2736.12319650833,94.5828717191618 -2737.95161153574,94.3300729179975 -2740.31262426358,94.3452924138484 -2742.58135433342,94.3148644553819 -2744.97330007398,94.3465793135566 -2747.27206724677,94.3316886065264 -2749.2878715088,94.1756959204999 -2750.96332446706,93.8497344957011 -2752.56681944179,93.4917940731241 -2754.2514312414,93.1770958617847 -2755.86394237154,92.829586529465 -2757.59124135304,92.5431335800112 -2759.09153719439,92.1457424127734 -2760.52537036783,91.7181716126892 -2762.56659292299,91.5990220889115 -2764.52548975495,91.4404051997157 -2766.55544655983,91.318184028455 -2768.50648148156,91.1573476867921 -2770.37792588366,90.9582482140398 -2772.0879910836,90.6819125376651 -2773.72569475424,90.3721763727177 -2775.36022111232,90.0639292204852 -2776.68781664245,89.6035730351492 -2777.95451114569,89.1193499983622 -2778.92053358532,88.4883452470664 -2779.83655310016,87.8383998719174 -2781.95795862472,87.7982543096331 -2783.98123402574,87.7090152174134 -2785.92346216141,87.5817725142309 -2787.64449542027,87.345233482214 -2789.29350181686,87.0759602255283 -2791.35375777058,87.0137879764266 -2793.39825552914,86.9451878654145 -2795.36127048959,86.8361332418738 -2796.74575337278,86.4383228653599 -2798.06830654806,86.0152081180571 -2799.5653025229,85.6830871953994 -2801.07599568999,85.3611176643222 -2802.52126779677,85.0114490987418 -2804.36561788987,84.8638889199571 -2806.1348156771,84.6800757798794 -2808.08731988398,84.5900502785703 -2810.23550151951,84.5996880910466 -2812.29963832425,84.5673173949279 -2814.47244993689,84.58947436129 -2816.56049154479,84.5700211544352 -2817.98906053477,84.2216317979912 -2819.65369002807,83.9941245342483 -2821.24867779801,83.7337878178279 -2822.76787462825,83.4384018317591 -2824.22182779399,83.1141448635519 -2825.98146279527,82.9457543793883 -2827.65719906417,82.7380294549197 -2829.26323824729,82.4978053733559 -2830.79976262639,82.2254723362259 -2832.27080690998,81.9223836669853 -2833.67380899532,81.5903479820254 -2834.75514586496,81.0987084175309 -2835.78463635396,80.5861987270007 -2837.76633868861,80.5564633283023 -2839.66976724389,80.4870240405759 -2841.08905395676,80.1753633794578 -2842.81210980276,80.0197766311713 -2844.46461504279,79.8308984148167 -2845.98012649987,79.5745451723882 -2847.43128884081,79.2898272966572 -2849.18781734421,79.1595930184749 -2850.65367651447,78.8850591380056 -2852.0567840752,78.583163270229 -2853.74129817346,78.4252106981808 -2855.35672742326,78.2342287119955 -2857.31174021267,78.2155058493901 -2858.60739916276,77.8666549033344 -2859.84555197828,77.4926799076523 -2861.5061689218,77.3344268988266 -2863.09863224919,77.1433882480107 -2865.10405068042,77.1608996845472 -2866.93380829831,77.0908631568551 -2868.69047545812,76.9851748341988 -2870.65087837773,76.9821683469543 -2872.53435628335,76.9418640449366 -2874.50248809399,76.9422684852047 -2876.89407793169,77.1557343965254 -2879.19599564145,77.3209518833906 -2879.91588543468,76.693548579944 -2880.59549234905,76.0527177613383 -2882.40497468378,75.9838944852106 -2884.30971047097,75.9623785653276 -2886.1393482743,75.9048625087653 -2887.94681498116,75.8348944435087 -2889.6820665702,75.731303578738 -2891.72330218885,75.7813247801115 -2894.09449931335,75.994187059062 -2896.37681230712,76.1605069270788 -2898.14718750475,76.0693442797622 -2899.84639466875,75.9428133060674 -2901.15359909842,75.6215010427768 -2902.28307095406,75.2138120326262 -2903.36042223715,74.7845048959105 -2904.3409075412,74.3119905210663 -2905.27386835214,73.818938641725 -2906.41060399991,73.4329875965437 -2907.757549038,73.1564054992423 -2909.04636572182,72.8536746384381 -2910.59554618905,72.6834574584068 -2912.08071255411,72.482249187341 -2913.76145683974,72.3817172353685 -2915.55585200731,72.3396958759997 -2917.27908160932,72.2614196833217 -2919.1149255353,72.2407717011362 -2920.87838939976,72.1839221049631 -2922.22102659436,71.9171524339765 -2923.84668653921,71.7946822136355 -2925.40625112373,71.6408494556432 -2926.24324582292,71.1257938459917 -2927.03752482022,70.5943983308504 -2928.42248825188,70.3634719239159 -2930.25091547152,70.3577183637683 -2932.00753964634,70.3153318699569 -2933.25429886843,70.0183809340083 -2934.4464666105,69.6982365489506 -2935.53335054906,69.3291197624994 -2936.44144151145,68.8729668757241 -2937.30516095618,68.4008545939305 -2938.80389770931,68.2491122714771 -2940.24095326341,68.0687295238408 -2940.98220808359,67.5423121964146 -2941.51932489694,66.9199817388334 -2942.02342282421,66.2852519699968 -2942.62383525734,65.7055897309683 -2943.1895668922,65.1143486385874 -2944.88088757251,65.0934849819375 -2946.27608972691,64.9240461237512 -2947.61333021252,64.7286528573338 -2949.22402105585,64.6710389466629 -2950.77044974207,64.5834190635453 -2951.73056137715,64.2025408903401 -2952.81230567915,63.8862476450276 -2953.845557045,63.5498261228008 -2955.53350538051,63.5443990598922 -2957.1551651109,63.5054086967667 -2958.18423401226,63.1715262571834 -2959.63017816347,63.0489936991177 -2961.01707239838,62.8996201821272 -2962.02045951847,62.5609793569041 -2962.9779966546,62.2017081803613 -2964.36972883478,62.0624576147537 -2965.6178755154,61.8543702754437 -2966.81308389908,61.622069825104 -2967.79450819778,61.2856094025893 -2968.7309855712,60.9298313904219 -2970.13352807162,60.8106016836719 -2972.04215820079,60.9461451478323 -2973.87855567096,61.043764255119 -2975.10288451499,60.8340647354163 -2976.27517797821,60.6011465670753 -2977.91259703211,60.6036970611355 -2979.17249270136,60.4170175651281 -2980.37940076562,60.2068210184072 -2981.22159160855,59.8148861457609 -2982.02322887286,59.4067033452592 -2983.25511466764,59.2189940458375 -2984.42464779802,59.0004096840173 -2985.5441233538,58.7613838002796 -2986.29336360354,58.3394494892897 -2987.00511839675,57.9030740246797 -2988.05892148788,57.6419416500697 -2988.68142858333,57.1677119629037 -2989.27041452156,56.6825633687735 -2990.62990988325,56.5872678775214 -2991.93426836084,56.4654504453672 -2993.10951304669,56.2793686985126 -2994.77276069785,56.3404488721825 -2996.37196624559,56.3688152686602 -2997.59976724755,56.2114430400157 -2998.77640223651,56.0290753335437 -2999.93422512349,55.8402651894051 -3000.92700131074,55.5710730894023 -3001.87567808078,55.2821003945101 -3003.29974946184,55.2343428126229 -3004.66706541726,55.1578464486232 -3005.99886987759,55.0656765707223 -3007.63471481067,55.1258638106577 -3009.20757494029,55.1532309357078 -3010.41096394482,54.9967484293283 -3011.56416122555,54.8157110721748 -3012.40816311283,54.4821359400817 -3013.06707062232,54.0601749411082 -3013.692034102,53.6262234459994 -3014.43974966044,53.2584960525586 -3015.15108117475,52.8753363657705 -3016.21559825486,52.6727042108761 -3017.26251351608,52.4637718692332 -3018.26436451088,52.2346220634397 -3018.99371636074,51.870141910983 -3019.68746660436,51.4931651633395 -3019.92540350889,50.8917761375481 -3019.82697398589,50.1294706371992 -3019.7177555654,49.368246658046 -3020.746498979,49.1833819153983 -3021.73135312108,48.9788990361431 -3023.33433996583,49.0843744275427 -3024.48132328289,48.9618378032484 -3025.58097883599,48.8173873915754 -3027.38090589964,49.0240925225447 -3029.11422997128,49.1956969119473 -3029.8110018339,48.8480334337921 -3030.2565882088,48.3785529262787 -3030.67568173314,47.8995618095608 -3032.71334221019,48.2349945827644 -3034.67755179186,48.5298357425885 -3035.9930402073,48.4973598407631 -3037.20186890364,48.4127173668465 -3038.3616730501,48.3045971302872 -3039.53896576733,48.2057489402535 -3040.66819748369,48.0835497918967 -3042.03074320941,48.0796297251816 -3043.05402904706,47.9077975822305 -3044.03389003617,47.7144617755823 -3044.92092483077,47.4773578881059 -3045.76862292047,47.2228455609933 -3046.84760245846,47.0863304554252 -3048.14901199207,47.0634807420505 -3049.39895428597,47.0156336455673 -3050.18636838323,46.7368860044774 -3050.93755167708,46.4412929510979 -3051.71173731752,46.1622792110672 -3052.20842050596,45.7456528882406 -3052.67762297737,45.319894196711 -3053.02582345233,44.8377046538697 -3053.35110535582,44.3494445020346 -3054.10003869752,44.0780161062768 -3054.78543167292,43.7765791116795 -3055.43815809087,43.4620196676256 -3056.35671534128,43.283540629855 -3057.23582641729,43.0875697602344 -3058.53082646263,43.1015943455352 -3059.04865317549,42.7277116036445 -3059.53899148759,42.3431514521556 -3060.28538163946,42.089368715466 -3060.99762925421,41.822243266858 -3062.17723920214,41.7917194593385 -3063.58789657247,41.876988226737 -3064.94488068737,41.9341043324333 -3065.84585662803,41.7628299802828 -3066.70821419984,41.5737633164509 -3068.26734449759,41.7359080741757 -3070.16572395692,42.0673536565609 -3071.9960371014,42.3600845564665 -3072.39059453453,41.9328237813953 -3072.76147124385,41.4972765720803 -3072.74316670267,40.8715616515359 -3072.35032446981,40.0646097178926 -3071.95737932136,39.2664947115757 -3073.45436450333,39.4202093549675 -3074.89560676564,39.5465432134344 -3076.30126217597,39.6524035878072 -3077.89506154022,39.8510625681045 -3079.43018554989,40.0189224579171 -3080.54057063346,39.9736868564492 -3081.60654836801,39.9053683509774 -3081.79908345135,39.4026648753855 -3082.30769342036,39.0629682892223 -3082.7898332908,38.7115609466525 -3083.07793413042,38.268150376088 -3083.34621806952,37.8182660110048 -3084.65878093079,37.8959398806946 -3084.68288969189,37.3287359410154 -3084.69515387201,36.7616155262096 -3084.99589736138,36.3447310451696 -3085.27683795301,35.9211459389156 -3086.06476454486,35.756681631052 -3086.47618110007,35.405296523666 -3086.86471389842,35.0464021551523 -3087.69423896759,34.9108179687182 -3088.48863306605,34.758942453439 -3089.10009570373,34.5172825192761 -3090.51881430689,34.681684293676 -3091.88506417851,34.8174420055571 -3093.11659441167,34.8851097226083 -3094.3011367319,34.929374890279 -3095.17461951666,34.8172936441097 -3095.94925479467,34.6582758354154 -3096.69046103047,34.483290039429 -3096.96694006325,34.0775791579256 -3097.22478231537,33.6667323445965 -3097.9481108874,33.4924896283945 -3098.21731586542,33.0931973599631 -3098.46829261668,32.6876850044151 -3099.54661588235,32.700531022566 -3100.5829050252,32.6930811810607 -3101.02316722087,32.3874936890259 -3101.92748500786,32.3168606198713 -3102.79498729541,32.2278622023044 -3103.40586172972,32.0125981851627 -3103.98864735548,31.7855588574184 -3104.68389491527,31.6166579930968 -3105.33140011378,31.4256134551034 -3105.9498456111,31.2211377708479 -3106.68509866235,31.0788486666466 -3107.38878830083,30.9207889551564 -3108.2008624875,30.8183889726031 -3108.75288567976,30.5875861836778 -3109.27882902602,30.3456942115963 -3110.19876445707,30.3042545757921 -3111.08183299732,30.2445550032135 -3111.25259819747,29.8295307096534 -3112.03198046105,29.7228313257875 -3112.77875289395,29.6003661704588 -3113.34144094522,29.3869261580262 -3113.87796462187,29.162383010181 -3115.00540966277,29.2363116600043 -3115.73075504028,29.1088847165727 -3116.42521107244,28.9679405153314 -3116.49721138036,28.5170881443167 -3116.55772507223,28.0637047822295 -3117.26919694124,27.9403014196127 -3118.09944543526,27.878834857105 -3118.89595882269,27.799415730017 -3119.72676057876,27.739134702904 -3120.5238283159,27.6631090264779 -3121.10294405262,27.4778771289218 -3121.02663284958,26.9676290819471 -3120.94350897749,26.4594252840268 -3121.27704760393,26.1644049562222 -3121.5918391553,25.8621776869744 -3121.91708146767,25.5693128946971 -3122.00352006953,25.15969207483 -3122.07869822828,24.7485834424704 -3121.77405977534,24.1516096740907 -3121.46989484239,23.5605902989832 -3121.16259047148,22.9747352244069 -3120.20706415272,22.0693537011474 -3119.2716063131,21.1831462398597 -3119.21171311377,20.7444099056909 -3119.14573765168,20.3064852524472 -3119.40643579064,20.0371403730643 -3118.97828440951,19.4252436647557 -3118.55516272419,18.8222163246356 -3119.45269609697,18.8854331800137 -3120.31625202023,18.9315494039048 -3120.73646217342,18.7558359319548 -3121.28475825075,18.6454268646777 -3121.80943408383,18.5248008211563 -3122.89004089438,18.6830535041089 -3123.93131815012,18.8206826409464 -3124.60221226384,18.771759780767 -3125.29829239195,18.7358366504901 -3125.96638898192,18.684996769567 -3127.13932162854,18.8873577140709 -3128.27015220726,19.066971637012 -3128.21193124868,18.6504714411204 -3127.93191016333,18.1279232637572 -3127.65282750034,17.6124185344249 -3128.60693675411,17.7167605064501 -3129.52564047467,17.8025361083916 -3129.73478968672,17.5334926187923 -3129.99606407773,17.292774376883 -3130.2424683267,17.0472320038272 -3130.67274883056,16.896727375026 -3131.08326600305,16.737937007394 -3131.68647635385,16.6773907291074 -3131.73547595952,16.3398366268603 -3131.7760679219,16.000966020477 -3132.16706300362,15.8410435873525 -3132.53965416157,15.6743086667719 -3132.78714692339,15.4452504573348 -3133.44228447527,15.4232712839973 -3134.07131178849,15.3881014021524 -3134.87543677721,15.441778220303 -3135.64906353226,15.4783943706034 -3136.05941467438,15.3332748673386 -3135.85589075439,14.8822095143528 -3135.65167940877,14.4355023037868 -3136.27138220441,14.4040027770254 -3136.86618121413,14.3617504623303 -3137.54644235993,14.363177439627 -3138.44076430208,14.4710716722933 -3139.30209322628,14.561579988015 -3140.25343699388,14.6969000705624 -3141.17007893198,14.8125165153947 -3141.162563196,14.4653114556344 -3141.24548331195,14.166838399664 -3141.31941673773,13.8674343814508 -3141.75078803696,13.7485762896637 -3142.1629613484,13.6214515445972 -3143.35341960992,13.8860896244735 -3144.55879573667,14.1552070060457 -3145.72208046772,14.3999543229639 -3145.95417612883,14.1759869689987 -3146.17286762533,13.9479090434198 -3146.89655840667,13.9767637070636 -3148.0840395886,14.2361763874168 -3149.22994455056,14.4721582906939 -3149.76034756691,14.3985633981252 -3150.26853933839,14.3144296806441 -3150.16422328694,13.9246400690236 -3150.1433296457,13.5808047256915 -3150.11664817073,13.2373369473936 -3150.36520513833,13.0346003654131 -3150.60012046109,12.8256139376248 -3150.75214369894,12.578141461582 -3151.1251763799,12.4437080622648 -3151.48099923361,12.302455058793 -3151.56609867337,12.0267710282737 -3151.64256388125,11.7494604024121 -3150.92033101695,11.0755214875445 -3150.76891553108,10.692684405942 -3150.61608051295,10.3119121991224 -3150.67829239461,10.0445327687557 -3150.73292704326,9.77497631719318 -3150.95484737497,9.59211361615943 -3151.57934620527,9.61230926102721 -3152.17974656169,9.62058126354256 -3152.57070816148,9.52486556087069 -3152.94450093414,9.42028886890517 -3153.21447121875,9.26606097844087 -3153.88760199507,9.31339169568796 -3154.53524886493,9.34893880844004 -3154.57707201829,9.07971226042799 -3154.61208188521,8.81202934819567 -3155.03671427676,8.73983247754413 -3155.23048180847,8.5543520202545 -3155.41308757502,8.36502165330761 -3156.1450095113,8.45207821381442 -3156.84990570835,8.52513225332668 -3156.64975055684,8.14412679235841 -3157.39107614109,8.23815037576654 -3158.10514114676,8.31897392638998 -3157.85516045996,7.91628518992463 -3157.60724350911,7.51764369771958 -3157.23641740464,7.06217913216146 -3156.5429764307,6.45081184039942 -3155.86497730954,5.85291597418293 -3155.98375817709,5.65930128096262 -3156.09416119476,5.46356025254737 -3156.18685323438,5.26115558456209 -3156.25306101024,5.04680459491839 -3156.31255385839,4.83160816088346 -3155.876750041,4.37167208456845 -3155.44919601618,3.9193937467055 -3156.08684703555,4.00426174725056 -3156.63171802769,4.04215253009582 -3157.15595277339,4.06957792704173 -3157.19114332131,3.85254124505725 -3157.22078351683,3.63388339887206 -3156.97160848291,3.27849597748623 -3156.43952545213,2.78554891891389 -3155.91883298174,2.30270679352607 -3156.06135478228,2.15695635139844 -3156.19548760281,2.00797838546289 -3156.6172480479,2.00437479646114 -3157.2906727002,2.12654842627508 -3157.94004008975,2.23629403335296 -3157.17912530058,1.63927111649427 -3156.43657364578,1.05801976638727 -3156.39718097321,0.834381644992282 -3156.62972873529,0.749088682596929 -3156.8515193455,0.65952760556496 -3157.01105094938,0.538340881758933 -3157.16199863174,0.41535109884722 -3157.35525313472,0.313592498194398 -3157.24515810982,0.06164108256535 -3157.13453845366,-0.188288095286523 -3157.28792365829,-0.304286206176356 -3157.43306564457,-0.423601938927873 -3157.9096209744,-0.374120647841716 -3158.01529139573,-0.494838039320958 -3158.11449880682,-0.616866426563526 -3158.09112447221,-0.797679560030436 -3158.06519217409,-0.975022627592876 -3157.28717272737,-1.52669138672963 -3156.76901844029,-1.81216795742781 -3156.26569528039,-2.08854775404469 -3155.53013562913,-2.48031646088273 -3154.81588906346,-2.85994197664494 -3154.60225652379,-2.98690657453829 -3154.55303871474,-3.03184520798868 -3154.50488720021,-3.07794500694665 -3154.050079339,-3.32910808092407 -3153.60827815802,-3.57171466427549 -3153.63080188837,-3.58278474002501 -3153.37312776167,-3.73505749403104 -3153.12263097393,-3.88273962094187 -3152.86413181258,-4.03445429477127 -3152.61285306369,-4.18197598536947 -3152.6157720724,-4.20332535550905 -3152.98221311274,-4.04342735773381 -3153.33735859728,-3.89184736383458 -3153.22191415624,-3.97761939753901 -3153.10934810416,-4.06180707974986 -3152.97010072762,-4.15931313076643 -3153.45471778522,-3.94559924929841 -3153.92443973013,-3.74327529256797 -3153.81921586488,-3.82897150717271 -3153.71647109754,-3.91387108772526 -3153.31163741444,-4.14983843313723 -3152.8292762851,-4.42529668130529 -3152.36053534618,-4.68999408218555 -3153.57074959386,-4.11366754578023 -3154.74458601366,-3.56054053518197 -3154.60357856273,-3.67257466041014 -3154.14297370759,-3.94214939403837 -3153.69524903754,-4.20400459784716 -3154.14022624048,-4.01834933360937 -3154.57132343746,-3.84209748243061 -3154.02771277748,-4.15527074033687 -3153.22025628467,-4.59914670843869 -3152.43593066408,-5.02706529374566 -3153.23555141093,-4.65745561914125 -3154.01092143816,-4.30523323319183 -3153.78185648598,-4.45845011154943 -3153.50971167422,-4.63183524172526 -3153.2449059046,-4.80078950484394 -3153.30486760518,-4.8052360043812 -3153.36239276921,-4.81305965452069 -3152.72028173785,-5.16996116361885 -3151.70757293592,-5.70837070995 -3150.72422639443,-6.22702460084556 -3150.22423840345,-6.49962051286669 -3149.73861675282,-6.76219729955815 -3149.90569648303,-6.69649557780741 -3149.38386016765,-6.97526409661242 -3148.87712825208,-7.24408201734183 -3148.73604953863,-7.32689771695639 -3148.59891114024,-7.40819107423969 -3148.03100602288,-7.70424832660606 -3147.39473675615,-8.03231656024652 -3146.77711146261,-8.34667814033497 -3147.15798533959,-8.16030079204079 -3147.52750657234,-7.98113156973792 -3147.44749127852,-8.02823562976374 -3147.31090669548,-8.10281311720785 -3147.17824451686,-8.17503094019435 -3146.73794537669,-8.39978396298633 -3146.31059152125,-8.61594929605051 -3145.86602836452,-8.8401262067003 -3146.56661501604,-8.4873836539811 -3147.24650995167,-8.14987989611548 -3147.31887684175,-8.11746551107857 -3147.38902910021,-8.088872192774 -3146.51093879541,-8.53427845925119 -3146.34290588094,-8.61880529841828 -3146.17983727269,-8.70028702925468 -3145.71726716464,-8.93088501235762 -3145.2684032686,-9.15322176904833 -3144.48159519849,-9.54156882926694 -3143.43401509649,-10.0566244872762 -3142.41761331952,-10.5509697476678 -3142.2282031609,-10.6256218317633 -3142.04478525988,-10.6970837256205 -3141.4472790981,-10.9760091522663 -3140.32498840438,-11.5119776496377 -3139.23640357507,-12.0267859853424 -3139.20003776694,-12.0093394066973 -3139.16543310925,-11.9926573028743 -3139.33746056292,-11.8723360686009 -3140.01284843075,-11.5006962455348 -3140.66889575119,-11.1426219747199 -3140.45621842224,-11.2221313104653 -3140.25035231881,-11.2975251337094 -3139.97986214415,-11.4029555856429 -3139.40939461904,-11.6581193165943 -3138.85639190452,-11.9030157197629 -3138.67913329963,-11.9555327928974 -3138.50781583285,-12.0059454202956 -3138.24654090734,-12.0996204479647 -3138.00655324206,-12.181132395714 -3137.77440915661,-12.2592426712786 -3137.22754696333,-12.4925980379846 -3136.69764308267,-12.7155810650999 -3136.1469862453,-12.9455535173255 -3135.85537118054,-13.0437093101595 -3135.573304177,-13.1358724541146 -3135.44638130729,-13.1500028188581 -3135.3241635469,-13.1605432399275 -3135.02041093661,-13.2630931940854 -3135.0443486048,-13.1980049126208 -3135.06859840243,-13.1330483267263 -3135.39625374687,-12.9177279852729 -3135.71519930432,-12.7088891770362 -3134.31407529685,-13.3616372358297 -3133.16016084625,-13.8839159556602 -3132.04145528509,-14.3819620005554 -3131.32028740897,-14.6773191575152 -3130.62172094331,-14.9582991845529 -3130.57655523871,-14.9097226971059 -3130.56278184158,-14.8458168941919 -3130.55077649949,-14.7805525225598 -3129.9290008877,-15.0211683809055 -3129.32698142154,-15.2501712789114 -3128.66485628622,-15.5055386749357 -3128.02070728752,-15.7482984181 -3127.39715049669,-15.9790143233488 -3127.09410809863,-16.0463466947012 -3126.80165412337,-16.1065757409596 -3126.48314966032,-16.1798894452793 -3125.7817491856,-16.443693746931 -3125.1027813565,-16.6922949316324 -3123.49052840455,-17.4058610561889 -3121.92778001736,-18.0861983587094 -3121.10447335484,-18.3913134019555 -3120.98627421255,-18.3396938004988 -3120.87370156124,-18.2848068006975 -3120.3212901306,-18.450493980884 -3119.78735489617,-18.6053462825035 -3119.33794609142,-18.7161352763817 -3118.65395507432,-18.9434180639812 -3117.99241586956,-19.1563898766876 -3117.88163353899,-19.0912147109207 -3117.77644736783,-19.0248418123882 -3117.43194863881,-19.077237263037 -3117.76942850018,-18.7879394865576 -3118.09923489174,-18.5060155111938 -3117.68876676374,-18.596421257373 -3117.29265583946,-18.6784044816305 -3116.78022781385,-18.8171814775022 -3116.49531329206,-18.8402212854594 -3116.22112751759,-18.8572037472211 -3115.84165622055,-18.9261900266318 -3115.4757383362,-18.9877603684622 -3114.77855780193,-19.2130259136792 -3114.0708578959,-19.4423283525318 -3113.38650061665,-19.6578255173699 -3113.37483501805,-19.533401022694 -3113.36601774305,-19.4094221129591 -3113.79644066395,-19.0662012903225 -3114.20669495561,-18.7361578033279 -3114.60720525933,-18.4143724117114 -3114.45849276557,-18.369234031982 -3114.316478647,-18.3214320237814 -3114.63696958588,-18.0428526590691 -3114.78290790723,-17.8534574118646 -3114.92676338012,-17.667307600342 -3114.64555491822,-17.6952759310338 -3114.37483518381,-17.7179699834557 -3113.96996879094,-17.8059382680514 -3112.357518309,-18.4973642154475 -3110.7950055782,-19.1567922774287 -3110.8827133338,-18.9838796398193 -3110.97030473022,-18.812152315742 -3110.52833142373,-18.9072644396232 -3109.91609663654,-19.086244524773 -3109.3244282808,-19.2536888909884 -3108.12289815151,-19.7231814292223 -3106.95945824742,-20.1701300727385 -3106.2156218318,-20.4005577497077 -3105.5864860413,-20.5720160327059 -3104.97872390669,-20.730180024773 -3104.46565630487,-20.8384925480355 -3103.97062473089,-20.9373186904111 -3103.11057745213,-21.2166839209922 -3102.22638216084,-21.5059393618484 -3101.37129782133,-21.7774025570677 -3101.04642375998,-21.7805825056912 -3100.73422687944,-21.7780811232609 -3100.96033638167,-21.5050120946303 -3101.40074964475,-21.128276600197 -3101.83113361338,-20.758956534892 -3100.30718042378,-21.37146247426 -3098.83121152476,-21.9530819549573 -3098.92321495841,-21.7437463138841 -3099.07824841697,-21.5055888418855 -3099.23177941271,-21.2706405783359 -3098.82141021597,-21.3191203415589 -3098.42619998524,-21.3590205994284 -3098.0384098387,-21.3956732931115 -3097.37926537879,-21.5668857055677 -3096.74267593691,-21.7240208100825 -3095.78207531573,-22.0431901546468 -3094.8530066736,-22.3427103969384 -3093.71821487921,-22.740946384048 -3092.93564341491,-22.9582561144938 -3092.17958073473,-23.1618984199712 -3092.47262521481,-22.837780158124 -3092.76040763639,-22.5194043765835 -3092.5293632706,-22.4636765187719 -3092.02233513243,-22.5462996586616 -3091.5335998573,-22.6191537356365 -3091.57033752645,-22.4277989396269 -3091.6093117503,-22.237243862805 -3091.59578990583,-22.0747401912477 -3092.03993988229,-21.6850289663544 -3092.47416338713,-21.3033920616207 -3092.52638430191,-21.1164620467394 -3092.58014964886,-20.9301566279483 -3091.94895953007,-21.0893488150921 -3091.08145325529,-21.3644611168193 -3090.24267532905,-21.6222058020978 -3090.06706312563,-21.5460409809686 -3089.89980023081,-21.4677410448472 -3089.68452886644,-21.410529681721 -3090.13907512424,-21.0211344455262 -3090.58328120108,-20.6393501160995 -3090.58255018019,-20.4849043114315 -3090.58481562252,-20.329592845371 -3090.42494228593,-20.2567830946647 -3091.24565152083,-19.6943878079047 -3092.04498768824,-19.1488930574883 -3091.95818947444,-19.0515441040374 -3091.87666524986,-18.9522224671918 -3091.54810077361,-18.9760089292416 -3090.76295757048,-19.2289020217713 -3090.00374022631,-19.4656057616704 -3089.06005287814,-19.7923972653835 -3088.14708787503,-20.1009823599733 -3087.83093622093,-20.1073925228264 -3087.2567778206,-20.2415027459328 -3086.70255508997,-20.3660303620869 -3085.50924026009,-20.8092160329651 -3084.35419904173,-21.2274870082831 -3084.534152027,-20.9742813002485 -3084.70624711289,-20.7277032887576 -3084.87633255831,-20.4839786901543 -3084.19515646668,-20.6686987319414 -3083.53713969166,-20.8393960609903 -3083.4252857457,-20.735439692476 -3083.69791632781,-20.4413901127869 -3083.96550748489,-20.1505121984134 -3083.86663308347,-20.0461762101106 -3083.77364043911,-19.9398443873748 -3082.96823040514,-20.1906300599133 -3082.00640555462,-20.5177080730863 -3081.07600871367,-20.8252777497794 -3080.10018657125,-21.1531560904452 -3079.15632589216,-21.4608951300665 -3079.49330954513,-21.1255791945017 -3080.05930338279,-20.677056821524 -3080.61172336409,-20.2411861654382 -3080.43157987185,-20.1760286455049 -3080.25975184557,-20.1083630115422 -3079.5315467775,-20.3186248775581 -3078.50251479963,-20.6777444661268 -3077.5069303129,-21.0153822291943 -3077.4304486068,-20.8898577780288 -3077.35937779526,-20.7630570744226 -3076.47138852648,-21.0448908060757 -3075.55086956513,-21.3416099818645 -3074.66074238213,-21.6184503930648 -3074.77377833153,-21.3919052681054 -3074.88673539652,-21.1675859881207 -3074.44625726289,-21.222101442172 -3074.02675737274,-21.266276959449 -3073.62285717189,-21.3009663988981 -3073.28355315453,-21.303875108484 -3072.95749732749,-21.2995817456564 -3072.93047627841,-21.146785820965 -3072.69610783334,-21.098878625722 -3072.47184953148,-21.0452695686909 -3071.3205271586,-21.4555200198546 -3070.20646475299,-21.8425179797694 -3069.53014498113,-22.0067971149699 -3069.12654240881,-22.0341172268029 -3068.73824008336,-22.0536583831927 -3067.80040162236,-22.3466307581918 -3066.89370603369,-22.6215856767403 -3066.39785870184,-22.6889506855792 -3066.34378742382,-22.5335620228628 -3066.29482219403,-22.3774530918247 -3065.23154556369,-22.7313416478568 -3064.20315967306,-23.0629300260982 -3064.41495371126,-22.7714100919558 -3065.31524939105,-22.1384158057091 -3066.19240804157,-21.5236482167264 -3065.93991972384,-21.4793826920097 -3065.69818205048,-21.4308205402824 -3065.36088265823,-21.4292899060059 -3064.81582531325,-21.5325848286639 -3064.2901547286,-21.623691113465 -3063.280732267,-21.9551385579847 -3062.30452015137,-22.2684067349398 -3061.05232426071,-22.7157307971566 -3059.1827935689,-23.4678657290694 -3057.37211415098,-24.1832668357956 -3057.23121098513,-24.0562718167738 -3057.09827293227,-23.9260289177656 -3057.04212398821,-23.7604008524106 -3056.75352024092,-23.713692419652 -3056.47713016355,-23.6584408884156 -3056.39198750206,-23.5076496486195 -3056.31308085208,-23.3560719685809 -3055.45409729336,-23.5961661439788 -3055.04181687767,-23.6102543176395 -3054.64543122869,-23.6169118834186 -3054.08098929321,-23.7073522939552 -3053.53694119608,-23.7861186805543 -3052.39741356146,-24.1610801047118 -3051.4679795553,-24.4270363654438 -3050.56987801976,-24.6766080494546 -3050.13475534956,-24.6916958221182 -3049.71640388096,-24.6969146211718 -3049.1032950594,-24.8003171134228 -3048.22412025723,-25.0357334869485 -3047.37489411469,-25.252442907735 -3047.86852244571,-24.7955628981303 -3048.35157496481,-24.3493000966304 -3048.45385522062,-24.0971713742289 -3048.42443751192,-23.914365385043 -3048.39968603286,-23.7301246802296 -3047.64160150073,-23.9144156435141 -3046.90970010414,-24.0855574516315 -3046.80563890127,-23.9404561775857 -3046.68239757714,-23.8068206259325 -3046.56655644976,-23.6699339669584 -3046.41291339248,-23.5530542804796 -3046.26754060409,-23.4333763687915 -3046.00676563898,-23.3722104359663 -3045.95197415456,-23.2084924619031 -3045.90247701198,-23.045409455516 -3045.895864976,-22.8612194922761 -3045.89305155521,-22.6764303141207 -3045.73933219072,-22.56994853902 -3045.44840354078,-22.5326913462779 -3045.16959810686,-22.4906660756445 -3044.89067587053,-22.4478913942631 -3044.62351210267,-22.4003954063114 -3044.16655206127,-22.4473640575919 -3043.66354461223,-22.51711257975 -3043.17891977144,-22.5769127657289 -3043.01357186994,-22.4766798879315 -3042.85663330158,-22.3735802670036 -3042.0619463714,-22.5903256984964 -3041.44369458945,-22.7157897682138 -3040.84727351796,-22.8296415385867 -3039.56144316324,-23.2873366397014 -3038.31723513607,-23.7195843448787 -3037.81903479086,-23.7740147828655 -3037.49885011568,-23.7398880649124 -3037.19187562835,-23.698205427097 -3036.54063881971,-23.8307573436967 -3035.91238986314,-23.9506425018238 -3035.22560352712,-24.0974268622177 -3034.951192606,-24.0374702727208 -3034.68869342917,-23.9716950719511 -3034.08945486328,-24.0757439932855 -3033.51171301039,-24.1662152440346 -3033.30107599328,-24.0731536865201 -3033.41824910115,-23.8167975986268 -3033.53575394852,-23.5629283734522 -3032.51384931334,-23.8807479919755 -3031.52590631878,-24.1791056599948 -3031.0996632274,-24.1933486243343 -3030.5190666907,-24.2845375882779 -3029.95948302892,-24.3644552546622 -3029.1778819979,-24.5548300243371 -3028.42326927725,-24.730746824936 -3028.56830024544,-24.4543764415963 -3028.94755612753,-24.0637333151962 -3029.3194479375,-23.6794859559727 -3028.5516714,-23.8690964492513 -3027.81035580177,-24.043606502953 -3027.65504224654,-23.9227543331689 -3027.03363909607,-24.036987642471 -3026.43440602904,-24.1391212908546 -3025.67238710133,-24.320794283379 -3024.9367558829,-24.4874754912371 -3024.92734356797,-24.2898569735317 -3024.6506939072,-24.2283555024816 -3024.38607345765,-24.1603361667055 -3023.88297294484,-24.2137879564738 -3023.39857184408,-24.2575918994005 -3022.18793283236,-24.6634981441102 -3021.74001604359,-24.68435394538 -3021.30926127548,-24.695332011649 -3020.65767390884,-24.8162356348815 -3020.02931197091,-24.9236458553682 -3019.65291645696,-24.9054596139314 -3019.20348568004,-24.9232846776163 -3018.77133452521,-24.9344421668667 -3018.19336860047,-25.0168938943849 -3017.63648029758,-25.0880716600359 -3016.81429709411,-25.2909443090095 -3016.13770368044,-25.4185298146921 -3015.48518778286,-25.5334054395428 -3015.36470136693,-25.3806269315292 -3015.25187497526,-25.2256194431412 -3014.39533444434,-25.4462876333774 -3013.02112004983,-25.9217185626607 -3011.69165270586,-26.3702314426299 -3011.28723530934,-26.3508639011959 -3010.89904724956,-26.3252366424829 -3010.42278363931,-26.3438402376032 -3010.42149347499,-26.1228894198533 -3010.42449964497,-25.9027837726657 -3009.64420134514,-26.0765518604141 -3008.89115938639,-26.2355505913352 -3007.83272790452,-26.5445749722455 -3006.78499643286,-26.8457552770923 -3005.77255900777,-27.1269309678766 -3004.90032379067,-27.3358476890738 -3004.05827434469,-27.5269116437488 -3003.59709479854,-27.5246353490524 -3003.3947748197,-27.3948473109177 -3003.20288177231,-27.2595709927771 -3002.70502897536,-27.2780841093229 -3002.22634120255,-27.2878140163523 -3002.44949711896,-26.9458602730638 -3001.73821431638,-27.0753544739428 -3001.05233252096,-27.1913353000208 -3001.52180340151,-26.7275390623777 -3001.98177858271,-26.2731924317432 -3000.66341445075,-26.7123948901566 -2999.04271086922,-27.2989064476169 -2997.47428465631,-27.8533550801166 -2997.27194086636,-27.7181306881708 -2997.08012940537,-27.5795713204228 -2996.91618089436,-27.4277606467163 -2996.66867790547,-27.319398337275 -2996.4329617577,-27.2081700208179 -2996.09078874417,-27.1502798247238 -2995.76314471376,-27.0856604398109 -2994.99549644032,-27.2420830003564 -2994.39375066296,-27.3123276123624 -2993.81424948308,-27.3709236795851 -2993.34279824562,-27.3755419517627 -2992.88974382982,-27.3713767013376 -2992.19350328948,-27.4886872664047 -2991.50560360522,-27.6004894727549 -2990.84252804377,-27.6996223101626 -2991.12815871187,-27.3222011450895 -2991.40984227445,-26.9501525512969 -2990.99299155091,-26.9320337034605 -2991.13315316674,-26.6350088488034 -2991.27352662744,-26.3404068722895 -2991.14309364549,-26.1850354077668 -2991.0207605176,-26.0277467017661 -2989.75609214799,-26.4422036088064 -2988.53856220899,-26.8297702634336 -2987.36132411799,-27.1933378289822 -2987.09754695434,-27.096525976984 -2986.84597278962,-26.9954238787872 -2986.51575561432,-26.9345993181699 -2986.42672438548,-26.7523348012222 -2986.34468642282,-26.5696154588123 -2985.211006076,-26.9142257133316 -2984.115155283,-27.23631525346 -2983.6534351816,-27.2377195733606 -2982.52179096037,-27.5741824145705 -2981.42805301571,-27.8887055023401 -2981.35094213244,-27.6912275975638 -2981.28064945699,-27.4913630242151 -2980.66151695902,-27.5696896716807 -2979.72458272025,-27.8052414539327 -2978.81985928204,-28.021477057696 -2977.86521310118,-28.2614778501857 -2976.94338671343,-28.4829121716044 -2976.34015986144,-28.5413172435704 -2975.74884723414,-28.5942422583217 -2975.17970293127,-28.6357890447598 -2975.52893780797,-28.2174083611058 -2975.87251873318,-27.8071337645843 -2976.18904711794,-27.4148313403222 -2976.24314442692,-27.1560941550799 -2976.30009242715,-26.8996436991673 -2976.04532639567,-26.8004323542422 -2975.80245614551,-26.6957824853764 -2975.23419704818,-26.756478747251 -2974.12028503597,-27.0883968409356 -2973.04367135281,-27.399233373145 -2972.37290588191,-27.5032162972367 -2971.72644295646,-27.5941940414075 -2971.98111755296,-27.233419226481 -2973.05006437567,-26.4703267994182 -2974.09176131128,-25.7267860256417 -2974.45192051347,-25.3324373688914 -2974.80553562758,-24.9466165969644 -2973.79701791478,-25.2447704681754 -2973.11582401846,-25.3761831917009 -2972.45881447974,-25.4934613368128 -2972.39223147575,-25.3149974541107 -2972.3316885126,-25.1353927039475 -2970.89131374752,-25.6480590720388 -2969.45441483227,-26.1519476003575 -2968.06417398706,-26.6273564804163 -2967.3949881693,-26.7376688224323 -2966.74992133408,-26.835430060947 -2966.37165435216,-26.7999338877142 -2965.64278487616,-26.9391453826192 -2964.93981925379,-27.0637419177188 -2964.38269038828,-27.1155843563677 -2963.8464103072,-27.1563661223065 -2963.64806358181,-27.0266858978718 -2963.53095944469,-26.8591123596952 -2963.42166701133,-26.6890849907817 -2963.8792897516,-26.2368380659463 -2964.32765942786,-25.7937813623493 -2962.86964206412,-26.3084796472481 -2960.66950857373,-27.1878626610632 -2958.53874409274,-28.025949531225 -2958.45984740317,-27.8292293560828 -2958.38782438237,-27.6292552590437 -2958.03366735039,-27.5736315100345 -2957.9952097078,-27.3615854669312 -2957.962334621,-27.1488128561405 -2957.84875915176,-26.978112688636 -2957.74291710817,-26.8038752045227 -2957.75717889672,-26.57158942962 -2957.79756173578,-26.3289402275837 -2957.84102386586,-26.0864776661422 -2957.3772019836,-26.0998360445817 -2956.93130982845,-26.1051831597773 -2955.84220606632,-26.4325625890454 -2954.33416486189,-26.9664940742387 -2952.87499391149,-27.4699528402231 -2953.37154728798,-26.9904653175132 -2953.85784458323,-26.5219132165392 -2953.72248562127,-26.3680878914517 -2953.70174692605,-26.1577419762801 -2953.6858633588,-25.9478496750712 -2952.78973702243,-26.1796964149824 -2951.92429260738,-26.3933683364407 -2951.4226790424,-26.423573304217 -2950.26798745536,-26.7804485016068 -2949.15171359049,-27.1146309403445 -2949.10742006296,-26.9087016114593 -2949.06882037825,-26.7026420578769 -2948.87449965538,-26.5751588891265 -2948.79089815837,-26.3944231114058 -2948.71404765224,-26.2126617592259 -2948.41005056013,-26.1449006996244 -2948.11927525287,-26.0715405570294 -2947.45485764207,-26.1868653373974 -2946.33116060119,-26.531623601224 -2945.24489882538,-26.8523175097087 -2944.67390768018,-26.9129401985541 -2944.12414013874,-26.9631105868429 -2943.37925061606,-27.1104375703318 -2943.04024018617,-27.0529359613895 -2942.71562726775,-26.9882529494016 -2942.56268840816,-26.8376272975806 -2942.41864066172,-26.6854957036374 -2941.60514147696,-26.868032641585 -2940.15940594692,-27.3667586781515 -2938.76077417131,-27.8363834552049 -2937.83287765224,-28.0654603197189 -2936.93696198621,-28.2765098805144 -2936.71752954009,-28.1472713620663 -2936.66950166471,-27.9333219890058 -2936.6274681672,-27.7190468043412 -2936.58744511873,-27.5056735246847 -2936.55309150942,-27.2921635701688 -2936.05294915264,-27.3122165838814 -2936.16421016364,-27.0268010618363 -2936.27659312731,-26.7444824533372 -2935.45084519359,-26.9341767270468 -2934.65382964305,-27.1062242107884 -2934.35843456907,-27.0275325686351 -2934.2900432265,-26.8352774024532 -2934.22802784016,-26.6426102083243 -2934.64414558819,-26.211141993396 -2935.05223840008,-25.7892222565411 -2934.60784255713,-25.7985751432337 -2934.19465097384,-25.7908486334659 -2933.7978090707,-25.7746424048772 -2933.33280442258,-25.7937986014319 -2932.88566446802,-25.8035764195978 -2933.07297693393,-25.4954575052776 -2932.51926793189,-25.5603448636283 -2931.98602295311,-25.6157700571251 -2931.78052165766,-25.506385298134 -2931.58517996745,-25.3927301316173 -2930.1759828804,-25.8878575103262 -2929.21749411032,-26.1516865995817 -2928.29151792114,-26.3964015432416 -2928.28168739091,-26.1810458207005 -2928.27638054782,-25.9667134493091 -2927.48151486295,-26.1487993876787 -2927.17023270152,-26.0871777608433 -2926.8723399978,-26.0203487747792 -2927.15872584761,-25.6617830982244 -2927.44077265797,-25.307929183115 -2926.57572072862,-25.5315126402574 -2925.73797769024,-25.7396798490928 -2924.92908238989,-25.9297912818012 -2923.95792484166,-26.2008034986159 -2923.01963858655,-26.4513213458174 -2923.10010733386,-26.1911173456271 -2922.78928174085,-26.1285976684181 -2922.4918449603,-26.0602382038968 -2922.40269259909,-25.8889503946511 -2922.32032732741,-25.7165147177827 -2922.14868633591,-25.5890449083622 -2922.32314158182,-25.2892492198581 -2922.4965172659,-24.9938638302089 -2922.55937514054,-24.756773141131 -2922.62432425056,-24.5209368258278 -2921.860224294,-24.7018084308972 -2921.24375003278,-24.807443584002 -2920.64941781409,-24.9010579031447 -2920.4991565244,-24.7724470470005 -2920.35725832861,-24.6398486362633 -2920.13742265741,-24.5486254762845 -2919.763669078,-24.5352416135783 -2919.40482752832,-24.5134488811753 -2919.37345791889,-24.3291489687294 -2919.34685977989,-24.1431766311786 -2918.70709414459,-24.26450066993 -2918.17654568197,-24.3313057294852 -2917.66551626955,-24.3873217102367 -2917.38611621293,-24.326298468167 -2917.1188440208,-24.2593490512641 -2916.04773161889,-24.5969763042346 -2915.26852684443,-24.7843737387683 -2914.5162736352,-24.9577071380093 -2915.29533215957,-24.3630585833169 -2916.0552705099,-23.7833034615066 -2915.25255975761,-23.9900793335747 -2914.50484788881,-24.169196665421 -2913.78301185971,-24.3325751891983 -2912.78991194439,-24.6300946952922 -2911.83003432185,-24.9079774125376 -2911.58351591988,-24.8271055833426 -2910.69883762865,-25.0653738199621 -2909.84426898759,-25.2865338493562 -2909.259476949,-25.3703768027275 -2908.69600345012,-25.4429742324011 -2907.74949989288,-25.7057018221626 -2907.27093534825,-25.7316887120132 -2906.81063592238,-25.7486954304987 -2907.15984905531,-25.3615956625177 -2907.50280800145,-24.9805413673633 -2906.94755148754,-25.0524673282586 -2905.75636595405,-25.4403420170215 -2904.60443338739,-25.8059664374446 -2903.83659721685,-25.9759429567578 -2903.09560160633,-26.1314086084788 -2902.58373011038,-26.1703757947988 -2901.17746986048,-26.6554306366908 -2899.81702824536,-27.1134877627582 -2899.19082217557,-27.2005080384258 -2898.58749743154,-27.2747093733964 -2898.95231974853,-26.8642871178208 -2899.20607819296,-26.5139300645187 -2899.45661918061,-26.1681848631569 -2898.55277063993,-26.403120723694 -2897.67984744766,-26.6203058850509 -2897.41082511803,-26.5331092576948 -2896.92806792394,-26.5533377173441 -2896.4638508949,-26.5649278137207 -2896.11529241846,-26.517858083491 -2895.78130537471,-26.4645118605283 -2894.9829840463,-26.6436749191869 -2894.27607062546,-26.7764520536249 -2893.59432380447,-26.8939758322755 -2893.56782165107,-26.6823995104238 -2893.54642425361,-26.4710285323714 -2893.19954767667,-26.4252832425962 -2892.59941879537,-26.5053227509983 -2892.0212828964,-26.5745140018275 -2891.52273592981,-26.6034330425079 -2891.04318124752,-26.6219590209185 -2890.38182708275,-26.730494376139 -2890.48229921496,-26.4569671000322 -2890.58408788874,-26.185609333652 -2890.19058988341,-26.1641885625993 -2889.81293252081,-26.1356197350367 -2889.32941122909,-26.1610299033638 -2888.51185674391,-26.354189853443 -2887.72264678171,-26.5297547940383 -2887.70170447818,-26.3197853887083 -2887.68561805114,-26.1103605352194 -2887.08907923395,-26.192041992201 -2886.88495289705,-26.07659438104 -2886.69104875596,-25.9579333258607 -2886.48509014301,-25.846540808284 -2886.28934764739,-25.7302635372222 -2885.32223275962,-26.0011145731303 -2884.56319223645,-26.1647608001144 -2883.83076903831,-26.3133180906348 -2884.21850383008,-25.9004874887756 -2884.59896844248,-25.4959979951639 -2883.96874540414,-25.6014866179782 -2882.94268334554,-25.9026819906559 -2881.95106538801,-26.1847704857249 -2881.9496549582,-25.9675862735065 -2881.95247319995,-25.7512213396443 -2880.52419843018,-26.2520512903131 -2878.61522812559,-26.989082228911 -2876.76694575431,-27.6879040702784 -2876.57246214444,-27.5528132731798 -2876.38820009937,-27.4148908151507 -2875.28517222624,-27.7363706556825 -2873.99361383664,-28.1491095081828 -2872.74476624072,-28.5360405027693 -2873.03514044107,-28.1502205098045 -2873.32154293258,-27.7703077496066 -2873.57365291764,-27.4116111652404 -2873.90899101025,-27.0156458985819 -2874.23878931297,-26.6259139908404 -2873.89693880504,-26.5741262881015 -2873.56948737052,-26.5155465203826 -2873.22586762226,-26.466259138208 -2873.15222967573,-26.2826366327991 -2873.08500752086,-26.0975362184233 -2872.51413847384,-26.1664612362426 -2871.96432870722,-26.2249120748162 -2871.37132014154,-26.3036826751278 -2870.27304847986,-26.6339202980804 -2869.21149418191,-26.9430292940292 -2868.67876883447,-26.9868048656657 -2868.16609042276,-27.0181207403842 -2867.65739492011,-27.0475422779632 -2867.27472316421,-27.0131442539957 -2866.90771692297,-26.9719534371688 -2866.64220137479,-26.8788346479362 -2866.38888602228,-26.7810104355317 -2865.77615513926,-26.8655502953518 -2864.78146433594,-27.1385897764489 -2863.82052860731,-27.3929478467564 -2863.49433890684,-27.3260294013772 -2863.18222497012,-27.2526724525701 -2862.72553486143,-27.2528211971296 -2862.43858428365,-27.1679804634883 -2862.16451529787,-27.0768036458268 -2861.38950131641,-27.2389645957333 -2860.6417595188,-27.3845211173357 -2860.10065467226,-27.4242078809386 -2859.80627552216,-27.3407614589163 -2859.52504244498,-27.2533326900095 -2859.12493490546,-27.2250413404626 -2858.74105919166,-27.1883635723863 -2857.57862286984,-27.5424125324314 -2856.93167977012,-27.6354889049264 -2856.3083147207,-27.7151282043249 -2856.28784193193,-27.4925619378782 -2856.27244866879,-27.269769774171 -2855.40859567218,-27.4729835229166 -2854.60521399739,-27.6447363253645 -2853.83003248631,-27.7997810941354 -2853.46018896306,-27.7505332589761 -2853.10579331153,-27.6950385851814 -2852.76434479716,-27.6334293820986 -2852.74108757885,-27.413002142918 -2852.72297796031,-27.1918774213723 -2851.94106486117,-27.3563372021519 -2851.18665028584,-27.5044583002189 -2850.97454480161,-27.37877139106 -2850.52069319925,-27.3774569121872 -2850.08466234084,-27.3669222868624 -2849.73653018037,-27.3109735115003 -2849.40312335475,-27.2491216668366 -2849.87737604159,-26.7838446715715 -2849.23028393236,-26.8840035706111 -2848.60663961965,-26.9716211378887 -2848.00599694221,-27.0468308199266 -2847.42746020199,-27.1098861296488 -2846.44085120629,-27.3755693742376 -2845.86000941029,-27.4373259115384 -2845.30075567348,-27.4865636999652 -2845.84285548331,-26.9852830667907 -2846.37333211197,-26.4952852161214 -2845.7903818591,-26.5660487658137 -2845.50628490152,-26.4863197185576 -2845.23485942058,-26.402870767002 -2844.78984216521,-26.406478148617 -2844.36220468225,-26.4012213303426 -2843.91667870596,-26.40350147649 -2842.82387238235,-26.7308584590014 -2841.76762448081,-27.0364928060091 -2841.39629833954,-26.9965679917051 -2841.040299054,-26.9489597526029 -2840.52464249507,-26.9816416985788 -2840.19350967477,-26.92183194529 -2839.87650983834,-26.8557598998855 -2839.44915463009,-26.8447284636136 -2839.0387679634,-26.8268437080447 -2838.01193693862,-27.1158226931179 -2837.44272643871,-27.1736915552154 -2836.89472264059,-27.2201506439996 -2836.69903930925,-27.0882923051313 -2836.51356246942,-26.9548534346055 -2836.048036215,-26.9613648489306 -2835.13035051402,-27.1946534172269 -2834.24416436944,-27.4104213461606 -2834.34049776973,-27.13125678103 -2834.43841831597,-26.8554148696812 -2833.62669603263,-27.037848091518 -2832.91978637867,-27.1650013269774 -2832.2381512446,-27.2784161429716 -2831.65061386129,-27.3448330878485 -2831.08483751715,-27.3979128375538 -2831.73844860002,-26.8416319304446 -2832.29156581064,-26.342032377507 -2832.83259554538,-25.852409364768 -2832.26494415632,-25.9219727588233 -2831.71821361665,-25.9807418675878 -2831.86804291467,-25.6916129244543 -2831.13100631052,-25.847501909934 -2830.41987332109,-25.9891558491284 -2829.90024814546,-26.0321490145336 -2829.40017128343,-26.0667800127137 -2829.37368421702,-25.8637829779657 -2828.85552876611,-25.9075421933138 -2828.35684928076,-25.9421753705847 -2827.31254671624,-26.2489076839087 -2826.30329706481,-26.5347321039369 -2826.15212490596,-26.3887576603406 -2825.89817539826,-26.2959089638019 -2825.65596739266,-26.198025816928 -2824.98928028643,-26.312517198956 -2824.34653388484,-26.4153650281083 -2823.91077225349,-26.4132195128675 -2823.39726120608,-26.4497090190292 -2822.90318371083,-26.4768716289297 -2822.01851882957,-26.6994951005731 -2821.16426369938,-26.9032446707507 -2820.89772482905,-26.8112414475392 -2820.48144911212,-26.7956848400853 -2820.08179446559,-26.7722975463051 -2820.35799547697,-26.4104011958176 -2820.63032079715,-26.0539727260157 -2820.85330573711,-25.7260387387316 -2821.43713855001,-25.2202938933039 -2822.00779761743,-24.7265599953824 -2821.45401049272,-24.8004737582512 -2820.92051700487,-24.8630177260481 -2819.71597790297,-25.2610714768242 -2818.9346967121,-25.4428816978836 -2818.18055586536,-25.6096951600016 -2817.63695451388,-25.6688673899571 -2817.11353068626,-25.7171265489181 -2816.19831803697,-25.9615265025136 -2815.16232254506,-26.265198681827 -2814.16111304952,-26.5475698034366 -2813.39435573384,-26.7095552894937 -2812.65455023047,-26.8567415622858 -2812.76279935359,-26.577974873888 -2813.28267880455,-26.0954430316892 -2813.79144605978,-25.6237034063359 -2813.53339529072,-25.5391373990883 -2813.28708767537,-25.4517700022122 -2813.1376113026,-25.3149116714407 -2813.17933756939,-25.0845729163572 -2813.22385389639,-24.8550842907066 -2812.90549230963,-24.8095109817185 -2812.60048938298,-24.7580112816636 -2811.90499942181,-24.9018686577093 -2811.4589508379,-24.9206640049291 -2811.03003061576,-24.93066824788 -2810.56111697413,-24.960387151961 -2810.11001832647,-24.9796062260654 -2809.8042213742,-24.9279487195748 -2809.93202023519,-24.6586783518857 -2810.05998235898,-24.3929514344546 -2809.39333630823,-24.5263994886106 -2808.75026508469,-24.6462516476461 -2807.69324626553,-24.9728415460611 -2807.3402423758,-24.9437964027266 -2807.00163786617,-24.9072252747647 -2806.55660732499,-24.9246257088545 -2806.1286920326,-24.9320591906907 -2805.72764181412,-24.9271194570673 -2805.70979718738,-24.729761682831 -2805.69644463486,-24.5331349414764 -2805.96408529476,-24.1979225251774 -2806.22767316098,-23.8668519104457 -2805.37668958258,-24.0981841961152 -2804.6418421181,-24.2683655743809 -2803.93253779257,-24.4245561992268 -2803.36016549802,-24.509753671846 -2802.80859873781,-24.5842420819715 -2802.11262601767,-24.729685993285 -2801.69526955673,-24.7347098826185 -2801.29418107132,-24.7310803837689 -2800.75924600578,-24.7954445378044 -2800.24404889275,-24.8495912573625 -2798.93281089219,-25.3007969203867 -2796.77311819751,-26.1710938437317 -2794.68138342835,-26.9990542395624 -2794.06974159786,-27.078579414785 -2793.48055405483,-27.1454757651534 -2793.73500312059,-26.7899114383292 -2793.84903510021,-26.5090497926748 -2793.96399287665,-26.2299459513882 -2793.40968050832,-26.2886928919449 -2792.87597381426,-26.3365618475378 -2792.20628253773,-26.4517225003973 -2791.37568483252,-26.6460705043014 -2790.57392024449,-26.8255019205598 -2790.01180080449,-26.882041836018 -2789.47063556316,-26.9284827620228 -2788.64413490752,-27.1175393889967 -2788.05857658087,-27.1818583498892 -2787.49474200919,-27.2362294781996 -2786.64991956671,-27.4301682577816 -2785.8344958558,-27.606597341863 -2785.80343494581,-27.389483386902 -2785.88390250332,-27.1190993896318 -2785.96641057956,-26.8502517125066 -2785.26205025508,-26.977620591474 -2784.58286034772,-27.0897181545454 -2784.55609403056,-26.8768039842598 -2785.01167732064,-26.4231613981413 -2785.45811433212,-25.9803183325162 -2785.51615032024,-25.7347279933378 -2785.57662993712,-25.4910675166689 -2785.9473713423,-25.0938807736633 -2787.14652063564,-24.2859420410413 -2788.31417657109,-23.5023873998041 -2787.72470664565,-23.6049735891425 -2787.15637851318,-23.6967191741566 -2785.91051717626,-24.1262343315267 -2784.88460797045,-24.4417811358594 -2783.89286109811,-24.7374599111762 -2784.1824804738,-24.3884603231545 -2784.46745020367,-24.0460861739494 -2783.57141912994,-24.2979984363296 -2783.03876936919,-24.3647481414296 -2782.52572211403,-24.422255188858 -2782.30357338943,-24.3344660365104 -2782.09182203756,-24.2418670073125 -2781.18684320808,-24.4948729139562 -2780.07300612513,-24.8505179180732 -2778.99600850165,-25.1835366185851 -2778.3367599934,-25.3050583518503 -2777.70102542913,-25.4132210893067 -2777.90812775041,-25.098419945485 -2778.52372272433,-24.5834980131033 -2779.12507490604,-24.081654642368 -2778.45061460032,-24.2200514839507 -2777.79994042321,-24.3477299342226 -2777.15260501454,-24.4721260943834 -2776.39728538522,-24.6491083515798 -2775.66818092246,-24.8106219010087 -2775.19087131811,-24.8451037631963 -2774.73161438871,-24.8707361152389 -2773.71538167976,-25.1732792077952 -2772.36993368253,-25.6384994961589 -2771.06830101336,-26.0764603146112 -2770.65358889892,-26.067816109706 -2770.25530371878,-26.0502293744499 -2770.20700594533,-25.8584944151566 -2770.66386771695,-25.4149759775114 -2771.1113385372,-24.9806829561858 -2770.2802973375,-25.1906845021719 -2769.477805849,-25.3837711830485 -2769.15823214789,-25.3328775895378 -2769.0570667004,-25.1745843593495 -2768.96290967336,-25.0146968658704 -2767.90264261101,-25.3394437631803 -2766.87770826377,-25.6418443551327 -2766.92617068347,-25.4053161890159 -2766.64054316894,-25.3381295395245 -2766.36740613183,-25.2651410733788 -2766.38358185984,-25.0486450551269 -2766.40328348337,-24.8323589574533 -2765.95710785935,-24.8517687846892 -2766.45650363484,-24.3973801294447 -2766.94504958399,-23.9522989065231 -2766.44008056371,-24.0088727609133 -2765.95382422654,-24.0554711438479 -2765.25464337578,-24.209219150465 -2764.8943007931,-24.1893565486262 -2764.5484688902,-24.1641345126059 -2763.83392049441,-24.3248672938252 -2763.14430087508,-24.4699254665534 -2761.7194313008,-24.9814577452985 -2759.7207757993,-25.7736321958378 -2757.78526515375,-26.5268665221781 -2758.01566765531,-26.1905138542403 -2758.24349937927,-25.8577198023116 -2757.89841261688,-25.8154801363947 -2757.46793911336,-25.8159754336653 -2757.0543349241,-25.8085698849275 -2756.44260326711,-25.9008590964345 -2755.8530841485,-25.9795037226253 -2755.21401495766,-26.083212216387 -2754.90132439934,-26.0225447474585 -2754.60206018696,-25.9556542073703 -2753.49358589004,-26.2941462699051 -2752.4220703857,-26.6102140594653 -2751.8232072998,-26.6868080022445 -2751.89332190504,-26.4284824736867 -2751.9656512543,-26.1722727674494 -2751.96761957913,-25.9524708699768 -2751.97373439576,-25.7334970697916 -2751.13595579817,-25.9383786377916 -2750.67187626084,-25.9547864680244 -2750.22567795559,-25.9615984249796 -2749.55146655153,-26.0825353142546 -2748.90136702365,-26.1911491846855 -2748.0978561784,-26.3742419971694 -2747.21191919926,-26.5962801212989 -2746.35645309797,-26.801749109076 -2746.03474541638,-26.7379966420447 -2745.72687692212,-26.6674702074197 -2744.95366402363,-26.8315227970247 -2744.71955688582,-26.7243174934868 -2744.49668910609,-26.6127784994818 -2744.37666248782,-26.4501499647004 -2744.26446714135,-26.2859471060192 -2743.50756679647,-26.4453974595932 -2743.61536596562,-26.171724470411 -2743.72419718379,-25.90000913561 -2742.94101156904,-26.075666259622 -2742.18515920741,-26.2351803235443 -2742.08356089646,-26.0675217426945 -2741.83931018074,-25.9726328613249 -2741.60645988204,-25.8738487840844 -2741.43969385368,-25.7423188597565 -2741.28199416094,-25.6077782988395 -2741.10506153122,-25.483849277013 -2740.85807838979,-25.3959025080788 -2740.62246940533,-25.3025992184531 -2740.37298819488,-25.2177269453339 -2740.13492001157,-25.129151160603 -2740.07028738722,-24.9548475089176 -2739.78789697499,-24.8900927799769 -2739.51782338236,-24.8197871669916 -2738.5456274168,-25.1018562057678 -2737.60613099493,-25.3647110977453 -2737.3308000501,-25.2939836376417 -2737.25956689841,-25.1192845760708 -2737.19448377543,-24.9442732704906 -2736.31940527404,-25.175878738324 -2735.47418804628,-25.3899945428308 -2735.61820905796,-25.1079362076544 -2736.05424710873,-24.6807535898533 -2736.48139679869,-24.263504338667 -2735.61440276493,-24.4973751616082 -2734.77690948284,-24.7155572362505 -2734.59358361263,-24.6025962176721 -2734.28645267038,-24.5538142430203 -2733.99230169267,-24.4983260183353 -2733.26200469239,-24.6625997721059 -2732.55718592747,-24.8119231459681 -2732.56755894134,-24.6017827886971 -2731.51767734946,-24.9246660040908 -2730.50275707136,-25.2269492852399 -2729.87807792408,-25.3307196955917 -2729.27589836479,-25.4227630238612 -2729.27295224608,-25.2138498548422 -2729.15846071766,-25.0629556782265 -2729.0513579455,-24.9092763063118 -2728.96388735627,-24.7473930775605 -2728.88295719788,-24.5835616947563 -2727.73057749754,-24.9580718900234 -2726.97521678032,-25.1305371273917 -2726.24615963888,-25.2882985260134 -2725.8650554598,-25.2703071468534 -2725.499240064,-25.2432110576491 -2724.79068825367,-25.3881444576862 -2723.64381686341,-25.7515432923895 -2722.53493120909,-26.0929760884304 -2722.09192874096,-26.0965905218117 -2721.66622691008,-26.0924949354229 -2720.54352250312,-26.4372338576037 -2720.59631896675,-26.1897632164133 -2720.65180063198,-25.9432951269463 -2719.47260764628,-26.316947983129 -2718.33247068447,-26.6670511424805 -2717.67405723913,-26.7736424301823 -2716.31578000852,-27.2293681616892 -2715.00200358469,-27.6594842126338 -2714.52293171097,-27.6659241533581 -2714.06252045863,-27.663018550126 -2713.75898497059,-27.5817257401493 -2712.61393420222,-27.9212853106226 -2711.50725587394,-28.2380753523722 -2711.79379931235,-27.8565332710685 -2712.07643904229,-27.4815913448494 -2711.66381241312,-27.4561389477791 -2710.86264131517,-27.6257109818502 -2710.0896256096,-27.7792094624928 -2709.36469752489,-27.9083366821504 -2708.6657125296,-28.0234454262312 -2708.89323309323,-27.6722354585875 -2709.28610605441,-27.2428314841219 -2709.67182583965,-26.8210474290428 -2708.61713020292,-27.1223696162654 -2707.59799895073,-27.403993191913 -2708.1200924348,-26.9126671316258 -2708.11861721543,-26.6885074550411 -2708.12150724717,-26.4638627807514 -2707.50792602004,-26.5499715352344 -2706.91674861521,-26.6227045340747 -2705.5376911832,-27.0893014281641 -2704.36610503244,-27.4473206809621 -2703.2335770544,-27.7823665357146 -2704.07710365984,-27.1270439172114 -2704.90014820368,-26.489703341283 -2704.34999614373,-26.5421470641637 -2703.57204245063,-26.7106331535955 -2702.8213546646,-26.861943168713 -2702.54220454212,-26.7769994403228 -2702.27563213554,-26.6851081228748 -2701.83940707779,-26.6797953330991 -2701.61940778315,-26.5667165798101 -2701.41020754221,-26.4498143122663 -2700.98398147658,-26.4430921753462 -2700.57459687228,-26.4266771658724 -2699.9439472351,-26.5214351012784 -2699.09079539693,-26.7262600106858 -2698.26715969956,-26.9144341011478 -2697.85626369938,-26.8955447713955 -2697.46184187224,-26.8671822759685 -2697.34841888205,-26.697912381618 -2696.62882217421,-26.8344368497651 -2695.93481736889,-26.9563698570885 -2696.28168537784,-26.5559965189166 -2696.62264621443,-26.1630592178547 -2696.13715168142,-26.1880546684096 -2696.44783988987,-25.8141170623748 -2696.75353154926,-25.4472788680558 -2695.68040281321,-25.7735807955931 -2694.64308121632,-26.0777544969592 -2694.19207147293,-26.0863611122434 -2693.19489300076,-26.3669713058037 -2692.23142166726,-26.6300589157438 -2691.76741203649,-26.638885093163 -2691.32142658432,-26.6394657224475 -2690.43802621254,-26.8574267637285 -2689.32451422147,-27.19109418217 -2688.24825125997,-27.5013106162587 -2687.70332610083,-27.5412625175519 -2687.17899970598,-27.5719549606072 -2687.03201558341,-27.4134598333318 -2686.95612894606,-27.2213215707895 -2686.88690990845,-27.0276494419711 -2686.41068468466,-27.0398346764092 -2685.95289806492,-27.041445826022 -2685.91988949653,-26.8308255146745 -2685.74225130792,-26.6954494872747 -2685.57417965741,-26.5559535210054 -2684.8604213387,-26.6911067383051 -2684.1720523494,-26.8125804032442 -2683.75695607924,-26.7955120425269 -2683.791471016,-26.5537585488683 -2683.82927811201,-26.312483637023 -2684.20164908174,-25.9064289412149 -2684.56722208188,-25.5092198940786 -2684.14489725313,-25.5087243054456 -2683.06041887003,-25.8397136109302 -2682.01210257314,-26.1475807507582 -2681.70407190373,-26.0837071240518 -2681.40934647526,-26.0146772651354 -2681.07729421985,-25.9630002382086 -2680.35867755292,-26.1047294929511 -2679.66551434702,-26.2336528286244 -2679.28309664799,-26.2056523622891 -2678.91621156788,-26.169947894468 -2678.3895047045,-26.2145039446442 -2678.11844210481,-26.132555419283 -2677.85958255466,-26.0439705561017 -2677.38337198921,-26.0648844748602 -2676.92543172438,-26.0777683463178 -2677.27352307314,-25.6853967511286 -2677.49253837484,-25.3630154547347 -2677.70916091904,-25.044236848248 -2676.99601584393,-25.1939499920695 -2676.30795627234,-25.3297926077527 -2675.85317530983,-25.3472569719441 -2674.92920980257,-25.5990312573698 -2674.03663486454,-25.8329941726995 -2674.41502489042,-25.4279003502038 -2674.78636247604,-25.0315680804694 -2674.14763835226,-25.1434052609651 -2673.96814491681,-25.0252970523841 -2673.79795894858,-24.9027664207554 -2673.38772398138,-24.9020472513455 -2672.99358811399,-24.8942435311932 -2672.17626842388,-25.0983750668323 -2671.61713669458,-25.1709732511187 -2671.07853344354,-25.2315808137158 -2670.26615387476,-25.4289559941352 -2669.48183492186,-25.610103058167 -2668.7698654077,-25.75463880329 -2667.6133264236,-26.1187802585328 -2666.495137971,-26.4611724518628 -2666.26965071114,-26.3529784390249 -2666.05508382346,-26.2414260448637 -2665.51518993989,-26.2931658688072 -2664.68263256416,-26.4891571209213 -2663.87895356781,-26.6700809767162 -2663.17954674328,-26.7970764773647 -2662.50512328429,-26.9105440924477 -2662.17280434893,-26.8503220137741 -2661.94522875982,-26.7394820299138 -2661.72870627058,-26.623690541787 -2661.566106463,-26.48281128999 -2661.41258928869,-26.337121816537 -2661.52221888022,-26.0613682342709 -2661.8059194393,-25.7024069841681 -2662.08539385022,-25.3497574124272 -2661.63417670095,-25.3660134029124 -2661.20033936829,-25.3732842133899 -2661.31376057254,-25.1069425218163 -2661.83890623886,-24.6356009074145 -2662.35251819237,-24.1765195369604 -2660.81367886131,-24.7470470302577 -2659.32421415473,-25.2881847803922 -2658.83643284401,-25.322296183172 -2658.30376648343,-25.3786477681699 -2657.79090308753,-25.4247575201768 -2657.35391030479,-25.4331189352244 -2656.93389130296,-25.4325867808952 -2656.42442927361,-25.4765284666103 -2655.76131986673,-25.5977063931222 -2655.12188239589,-25.7047159351884 -2654.25782608705,-25.9230277636519 -2653.42345432048,-26.1259625122629 -2652.87233794353,-26.1836851202395 -2652.85579248467,-25.9736648186254 -2652.84393148038,-25.76408060203 -2652.42943108671,-25.7572495211387 -2652.03131448516,-25.7413500916491 -2651.36079774905,-25.8623930413712 -2650.13275942762,-26.2611115021879 -2648.94521069611,-26.635793444109 -2648.34000743053,-26.7157573787909 -2647.75699756568,-26.7839883881692 -2648.05848797169,-26.4083766019058 -2648.84747396177,-25.7933893381342 -2649.61734134726,-25.1950494350108 -2648.35851536399,-25.6172811059945 -2647.14093432724,-26.0136737263395 -2646.32131678934,-26.2061808542441 -2645.17502367713,-26.5599231416885 -2644.06687918494,-26.8920110588415 -2643.74481953218,-26.8270473638702 -2643.43663614223,-26.756636079776 -2642.96408434346,-26.7690937754663 -2643.11664022477,-26.4679500873856 -2643.26900111949,-26.1705135752086 -2641.94474906401,-26.6142568665968 -2640.66389394309,-27.0323947875052 -2640.68008154673,-26.7979680818306 -2640.85055827345,-26.4882900495309 -2641.02030133292,-26.1817234580635 -2640.61881397272,-26.1638789490188 -2640.23341179649,-26.1383259723393 -2639.78315005541,-26.1441971508283 -2639.67683106045,-25.9800385492403 -2639.57783526394,-25.8136029996278 -2639.88261479937,-25.4459285372764 -2640.18250911301,-25.0857949744896 -2638.74325575569,-25.5968636070379 -2636.94966304671,-26.2810082364801 -2635.21325057753,-26.9309497942296 -2634.8458881312,-26.8889907666903 -2634.49373621349,-26.8394091177169 -2633.34607385762,-27.1888515575069 -2632.38396705714,-27.4421099974106 -2631.45471782374,-27.6749688322528 -2631.28748047949,-27.5255296781882 -2631.12967209133,-27.3731342802502 -2630.27773684886,-27.5693985044909 -2629.4306190175,-27.7616005096764 -2628.61302329324,-27.9368546195378 -2628.67352297756,-27.6711220730664 -2628.73675673796,-27.4070279518604 -2628.30675142269,-27.3910935988143 -2627.65560658559,-27.4864223875362 -2627.02816126659,-27.5692268696648 -2626.92529044049,-27.3888868589853 -2626.82991854916,-27.2056196301654 -2626.09587898008,-27.3446955155747 -2625.28066817503,-27.5228668318788 -2624.49399801606,-27.6855569179099 -2623.5915069312,-27.9036772358983 -2622.72021109314,-28.103500583421 -2622.04433343924,-28.2043020788348 -2621.68464167221,-28.1466759532764 -2621.34016072292,-28.0820010011264 -2620.93822865442,-28.0466427177708 -2620.55273574806,-28.0025037181696 -2620.47082927999,-27.8075942584567 -2619.51295189604,-28.0525508461144 -2618.58792577083,-28.2781144949349 -2618.12016067946,-28.2725802340347 -2617.67084296533,-28.2572600289366 -2617.49993507047,-28.1035737095751 -2618.23927305497,-27.4969447923217 -2618.9612785169,-26.9050318392175 -2618.18940807349,-27.0651472925654 -2617.44472586191,-27.2089627896724 -2616.07128357684,-27.6669043735637 -2615.13725202159,-27.9007504406268 -2614.23535022959,-28.1164823185834 -2613.9157890987,-28.0397041003378 -2613.6102332893,-27.9559873741636 -2612.98253607938,-28.033879879831 -2612.49722313607,-28.0393198436057 -2612.03083474135,-28.0366644097618 -2612.20398988607,-27.7132132472315 -2612.37657100472,-27.3939724341714 -2611.79212526343,-27.4565515390543 -2611.36410329754,-27.4394142739593 -2610.95319334512,-27.4155412486817 -2611.54068817669,-26.8909933221892 -2612.11522699159,-26.3788249231792 -2611.14944098754,-26.6416700547148 -2609.85840415274,-27.0636806959202 -2608.60987949664,-27.4624104389871 -2608.29492963513,-27.389105810376 -2607.99373753981,-27.3094073038675 -2607.54100592516,-27.3065964755261 -2606.84961623376,-27.4237551117032 -2606.18308457997,-27.526767420474 -2606.20402235239,-27.2848996392522 -2606.22878683971,-27.0435383418853 -2605.49771763031,-27.1816971100462 -2604.6862073133,-27.3591741086545 -2603.90310588839,-27.5210657038987 -2604.36616711152,-27.0568395621076 -2604.8199922184,-26.6034272959156 -2604.42281726625,-26.5788440453009 -2604.2708534214,-26.4328957888036 -2604.12765257955,-26.2840258048194 -2603.55665304137,-26.3514395085962 -2603.00674694124,-26.4075060655005 -2602.89157876261,-26.2441514063684 -2603.17140107451,-25.8865239570194 -2603.44712367396,-25.5342289881598 -2602.85415100817,-25.6194808723595 -2602.28279057009,-25.6926748420583 -2601.17201937422,-26.0357735891583 -2599.68065332855,-26.5649681085891 -2598.23759472985,-27.0645210229292 -2597.8219978354,-27.0470398891606 -2597.42303237607,-27.0204401749298 -2597.26479602567,-26.8735551633321 -2597.41419050689,-26.5735717274036 -2597.56349166459,-26.2760900021992 -2597.39312866116,-26.1418805430155 -2597.23202451987,-26.0063179766162 -2596.41519402224,-26.1970082952769 -2595.63886672863,-26.3668602164519 -2594.88971532556,-26.521601924566 -2594.31963472037,-26.5865364716691 -2593.77065916093,-26.6384673139122 -2593.24102922342,-26.6801634465278 -2593.54845937441,-26.303176935678 -2593.85107931166,-25.9324223524684 -2593.3515264945,-25.9666923172386 -2592.87090257867,-25.9915892212915 -2592.39049095353,-26.0150287909147 -2591.84097405497,-26.0735882966703 -2591.3118784024,-26.1206638842867 -2591.88018403055,-25.6196678002793 -2592.43583348164,-25.1294563050199 -2591.93192414031,-25.1743102107293 -2591.30170225368,-25.281560299264 -2590.69413042061,-25.3764258531654 -2590.09086673396,-25.467703433959 -2589.50950299653,-25.5475297352013 -2589.21737746629,-25.4832379439035 -2588.83017531383,-25.4655038077775 -2588.45849610257,-25.4397279319905 -2588.29174154202,-25.3131297416025 -2588.13395810023,-25.1831515408194 -2587.31630378392,-25.3835144624339 -2586.05354502375,-25.8043851805455 -2584.83221156577,-26.2012260910645 -2584.42304177408,-26.1874827360078 -2584.03017958692,-26.166492333902 -2583.98043702936,-25.9738604719267 -2584.62906989598,-25.4333402861987 -2585.26265644821,-24.9058465378907 -2585.82787420831,-24.4184049631358 -2586.38029640565,-23.9418728310276 -2585.54105135065,-24.1656979207412 -2585.77142486761,-23.8528779261987 -2585.99877654427,-23.5441835880923 -2585.23045626265,-23.7368822950776 -2584.48855889794,-23.9149846749888 -2584.24782935537,-23.8383617127117 -2583.80094986713,-23.8674103091236 -2583.37103429596,-23.8874262148592 -2582.986808546,-23.8848716082516 -2582.6176973459,-23.8741939496514 -2581.78385546538,-24.0962262411059 -2581.8512843668,-23.8655259313098 -2581.92050247774,-23.6358992994982 -2580.99787703528,-23.9056661025681 -2580.10624387757,-24.1565017563902 -2579.48106815878,-24.270945408911 -2578.94397329572,-24.3406698399579 -2578.42659806863,-24.4000254285038 -2577.99550250669,-24.4141764365118 -2577.58103824444,-24.4223075181284 -2577.29238306968,-24.3663192968204 -2576.73485516734,-24.4438911299706 -2576.19769728469,-24.5123627985771 -2575.7220746893,-24.5478659656934 -2575.26441899618,-24.5745016059068 -2574.66007761531,-24.67549855552 -2574.55179459847,-24.5275059960742 -2574.45060114575,-24.3759232141694 -2573.8703942955,-24.4657564837095 -2573.31121109134,-24.5434215408454 -2572.31737461332,-24.8377869253175 -2571.28563936704,-25.1483001642567 -2570.2883916168,-25.438731496276 -2569.47810229222,-25.6324669352511 -2568.69586156576,-25.8110919930723 -2568.19070551287,-25.8489663421117 -2567.22526400423,-26.1170146531065 -2566.29252661708,-26.3658147750673 -2565.9632026292,-26.3093889717455 -2565.6478756757,-26.247826597053 -2565.72769936562,-25.9882702356275 -2566.01306266997,-25.6304247836219 -2566.29411318909,-25.2762359306212 -2567.13833115289,-24.6446621537209 -2567.96158359395,-24.0302726519394 -2567.35113526103,-24.1388062428577 -2566.09994483401,-24.5671000547286 -2564.88958347506,-24.970130647527 -2564.34868828371,-25.034651848466 -2563.82776172313,-25.0877875489814 -2562.75597929945,-25.416232535426 -2561.56670550706,-25.799456608742 -2560.41669908758,-26.15988351725 -2560.66244757526,-25.8171819621198 -2560.90514556939,-25.481181035942 -2560.72308873939,-25.3626433431923 -2560.37735169166,-25.3257811788933 -2560.04587930206,-25.2831058018206 -2560.30458625502,-24.9455026328412 -2560.55963664446,-24.6131591188411 -2559.76879277368,-24.8060153990246 -2559.06314777522,-24.9553969663873 -2558.38230057438,-25.0895685917554 -2557.80156010078,-25.1722341338311 -2557.24200193024,-25.2440240167873 -2557.15865184548,-25.0771748123055 -2557.22176158243,-24.8384765118631 -2557.2869835708,-24.601029590037 -2557.10379794522,-24.4901008677209 -2556.92992659774,-24.3758626601042 -2555.76456699546,-24.7587236065101 -2554.20226629159,-25.3357292553645 -2552.69013564782,-25.8823534147074 -2553.23089276923,-25.3970373198833 -2553.75977258477,-24.9222585257593 -2552.76783318564,-25.2130716898646 -2552.27696201019,-25.2501383270084 -2551.80462558928,-25.2777039062819 -2551.17378851618,-25.3838728709442 -2550.56564639271,-25.4771058394499 -2550.2546691432,-25.4215727142377 -2549.91582845139,-25.3800624478656 -2549.59107132917,-25.3319200720387 -2549.10280457561,-25.3657227174769 -2548.63303317764,-25.3899758772311 -2548.39990855262,-25.2965275118069 -2547.91922819462,-25.326899448201 -2547.45681165407,-25.348932689732 -2547.33386766614,-25.1995836904739 -2547.21861416293,-25.0489431680881 -2546.06308572375,-25.4194387296642 -2544.58152449503,-25.9500998922603 -2543.14785808446,-26.4504680289504 -2543.22523545971,-26.1913902059055 -2543.30455726228,-25.9335876950216 -2543.13952130162,-25.8004497974765 -2542.49390931555,-25.90835503699 -2541.87153823836,-26.0042741514156 -2541.18731580041,-26.129723889947 -2540.52751105247,-26.2411979867616 -2539.8677352811,-26.3511613695557 -2539.09604516364,-26.517684321001 -2538.35141308223,-26.667461839712 -2537.74109795747,-26.7484838200179 -2537.15315633785,-26.8182448487413 -2537.04937961343,-26.6455278035013 -2536.73378892703,-26.5811099793173 -2536.43181036644,-26.5084368637368 -2536.48817877943,-26.2579134390812 -2536.54715099986,-26.0077562560563 -2536.11195854921,-26.0082983281836 -2535.78039045991,-25.956159726236 -2535.46282501402,-25.8995539826116 -2535.4490861422,-25.6913227196175 -2535.43988730108,-25.4819765501117 -2534.71986880237,-25.6306126432529 -2533.6127064345,-25.9713760482481 -2532.54240777291,-26.2900459811072 -2531.97248603387,-26.3551245925883 -2531.42366034313,-26.4079322783207 -2531.12624167716,-26.3365171017674 -2530.41559935821,-26.4718049827568 -2529.7302216029,-26.5931235950991 -2529.48634418475,-26.4925698946673 -2529.2539614007,-26.3874266436394 -2528.0652395936,-26.760965295405 -2527.12205351089,-27.0081882503369 -2526.21109909211,-27.2365024380974 -2525.78655190541,-27.2205048149477 -2525.37895858724,-27.1953438930507 -2524.7079658237,-27.3017460026997 -2524.18074491642,-27.3359382021694 -2523.67353926839,-27.3583995206562 -2522.53560284476,-27.6961043225893 -2521.43579554919,-28.0123207904852 -2521.07895620544,-27.9532393240616 -2520.12448500277,-28.1943364908906 -2519.20280566461,-28.4179760105272 -2518.85209021355,-28.3532909890034 -2518.51636926193,-28.2809738220751 -2517.84995460869,-28.3741598905138 -2516.96426649559,-28.5754887626951 -2516.1094374472,-28.7603235196891 -2515.41836913139,-28.8618793393204 -2514.75244607272,-28.9488759955182 -2514.38859841264,-28.8859827147262 -2514.09460890636,-28.7880854770543 -2513.8140278791,-28.6843187795875 -2514.39267881842,-28.1514223541684 -2514.95888093248,-27.629258745334 -2514.55971757611,-27.5957477905653 -2513.95251511523,-27.666788929944 -2513.36775590204,-27.7251013479525 -2512.28414834002,-28.0337132374334 -2511.23709871936,-28.3192456362218 -2511.20982833873,-28.0927911741232 -2511.65274230704,-27.633297554376 -2512.08711919216,-27.1830993713928 -2512.08870224791,-26.9526950516286 -2512.09465063586,-26.7230741649977 -2511.76307939722,-26.665354974308 -2511.26670293297,-26.6903177735713 -2510.78930967014,-26.7053655306695 -2510.7974760178,-26.4767700477369 -2510.80971480906,-26.2487230311912 -2510.73848004678,-26.0661202666347 -2510.05307556096,-26.1919245795431 -2509.39212829973,-26.3037497059392 -2509.1756032989,-26.1933112064387 -2508.9696903904,-26.0773196408825 -2508.39591831512,-26.1459524593428 -2507.85641041936,-26.1970476700791 -2507.33707474979,-26.2370532082194 -2507.05581405863,-26.159274631379 -2506.78707615447,-26.0753655417353 -2506.27462137543,-26.1129721979623 -2505.97151987287,-26.046417792027 -2505.68158185234,-25.9749892125327 -2505.11721601522,-26.0401037712333 -2504.57372768918,-26.0941267269186 -2504.69608768688,-25.8141398345224 -2505.16230817895,-25.3663220071036 -2505.61885338118,-24.9283282683862 -2504.76854363259,-25.147715014688 -2503.94735876932,-25.3507313395118 -2503.62348232917,-25.3026407750013 -2502.52229205238,-25.6436093742878 -2501.45772737367,-25.962317789465 -2501.73831861054,-25.604921257719 -2502.0147755482,-25.2534425086844 -2501.38344428217,-25.3605653562493 -2500.41581639834,-25.6333428448851 -2499.48088748867,-25.8883924132609 -2499.23926079164,-25.7931436385065 -2499.00893853972,-25.6931095527738 -2498.8089837311,-25.5799674050232 -2498.47940176884,-25.5322919524833 -2498.16365881112,-25.4784959367689 -2497.81337401992,-25.4422857826029 -2497.47751967462,-25.3996482965006 -2498.12197426127,-24.8681495556848 -2498.2910438598,-24.578927542345 -2498.45904188567,-24.29263810185 -2497.57716985651,-24.5333613547752 -2496.7252502691,-24.7579898461478 -2496.99635212917,-24.4176220145471 -2496.96559679709,-24.2321422857688 -2496.93961152081,-24.0467236520173 -2496.30066434665,-24.1699225485498 -2495.68440287474,-24.2792824446852 -2495.51094940801,-24.166214805788 -2495.60571466083,-23.9203235470626 -2495.70148917327,-23.6755251614338 -2494.83655341864,-23.9139964559856 -2494.00094930899,-24.1358835578336 -2493.0624607514,-24.4078837111789 -2492.61747761579,-24.429492659029 -2492.18952700023,-24.4420817714038 -2492.18792524905,-24.2412279008308 -2492.19024587054,-24.0414186841932 -2491.65314064237,-24.1138220239792 -2490.56010028914,-24.4619356895931 -2489.50322867796,-24.7882056689065 -2489.54504419519,-24.5623500931115 -2489.58956012526,-24.3379160054471 -2489.31280935803,-24.2764089351981 -2488.54301209252,-24.4624483558739 -2487.79982361989,-24.632925501111 -2487.20761339626,-24.7246793883112 -2486.63686056384,-24.8061395235176 -2485.66134765896,-25.0886025610365 -2484.43895794661,-25.4917343964232 -2483.25675153616,-25.8705313066219 -2481.95089551891,-26.3081230372032 -2480.68783333622,-26.719423243489 -2480.15235196176,-26.7631428787023 -2480.3484127192,-26.4414514825905 -2480.54296750799,-26.1220005036464 -2480.02909550291,-26.1619349376476 -2479.53460500606,-26.1907897110679 -2479.13516563041,-26.1712870070421 -2478.88750373967,-26.0775483471455 -2478.65135391543,-25.9770996427106 -2478.54511589277,-25.8140205833188 -2478.44617714936,-25.6480581232393 -2477.78083378987,-25.7677037313471 -2476.54569929017,-26.1692535329117 -2475.35127821451,-26.5486103240827 -2475.1324108242,-26.435590892094 -2474.92429696582,-26.3188247116288 -2475.39589781615,-25.8621876602113 -2475.88575215073,-25.4023459906217 -2476.36523556216,-24.9515913118207 -2475.51015220122,-25.1733245004898 -2474.6843358098,-25.3774233867607 -2474.38998049425,-25.3132134313212 -2474.21024351957,-25.1928904057919 -2474.03986612074,-25.0692373011155 -2473.50896199022,-25.1264051633606 -2472.99777604207,-25.1740726712757 -2471.76178628947,-25.5842929471638 -2470.40745923101,-26.0489808475817 -2469.09730587815,-26.4864973929431 -2468.67787999221,-26.47473429927 -2468.27512579911,-26.4539003723708 -2468.00167373621,-26.3694380596322 -2467.33160085447,-26.4839720192468 -2466.68560061521,-26.5856304918329 -2466.17076220942,-26.6196363513515 -2465.67545712667,-26.6446145916731 -2466.04345867393,-26.2377674690348 -2466.68025131032,-25.7003561612601 -2467.30240214721,-25.1756279340415 -2466.41361557301,-25.410859501596 -2465.55515808647,-25.6292774058049 -2465.01828929183,-25.6850612999969 -2464.72932944517,-25.615472942554 -2464.45303688715,-25.5420431003088 -2464.18648083515,-25.4631512911174 -2463.93189239407,-25.3786708910378 -2463.43700927497,-25.4146694093831 -2463.34804096773,-25.2477379063685 -2463.26576882338,-25.0792092565657 -2463.07668470754,-24.9655925078555 -2462.89719780172,-24.8496460044533 -2461.62872360924,-25.2780009304644 -2459.87941594612,-25.9428569489305 -2458.1859227558,-26.5731526926386 -2457.74358448026,-26.5712841605065 -2457.31862615861,-26.5605524669746 -2457.44510584236,-26.2747318752201 -2458.12820001206,-25.7128190658119 -2458.79530771883,-25.1657613184221 -2458.313110312,-25.1977625642477 -2457.84920489749,-25.2204187636751 -2457.7987520053,-25.0371356454118 -2457.61069462196,-24.9239306846144 -2457.4321862777,-24.8068569726401 -2456.55493691711,-25.0407267044603 -2455.70759043971,-25.2567969209752 -2454.92925237913,-25.435880600797 -2454.68533028952,-25.3466767114264 -2454.45268648986,-25.2528015867488 -2453.9113497296,-25.3141063392876 -2453.39006072062,-25.3645730008352 -2452.38001081607,-25.6589773487649 -2451.57824630706,-25.8469261485231 -2450.80430733374,-26.0190792149773 -2450.10047701578,-26.1545078809115 -2449.42164145816,-26.274011219072 -2449.05633702531,-26.2361714858474 -2448.7179814176,-26.1862155106918 -2448.39385265042,-26.1306299326523 -2448.2040152683,-26.0074820696689 -2448.02398777971,-25.8803898909314 -2447.64756127456,-25.8533855673001 -2447.13348480174,-25.8942444064412 -2446.63878009113,-25.9264015304424 -2446.5583583032,-25.7508249972399 -2446.484463691,-25.5735832287863 -2446.15794110167,-25.5251326232606 -2446.03405966244,-25.3754300251664 -2445.91791226,-25.2222790787446 -2445.23798984064,-25.3534525693812 -2444.58220652142,-25.4712942831152 -2443.50321520049,-25.7987058752714 -2442.68048474695,-25.9960383999804 -2441.88622158633,-26.1768682897859 -2441.86346195503,-25.9696443066736 -2441.845576702,-25.7614852593255 -2441.58018394879,-25.6795063545125 -2441.714112189,-25.3996029239626 -2441.84816768236,-25.1221468146198 -2441.40119937674,-25.1379457645223 -2440.9714530733,-25.1445172887194 -2440.23987931786,-25.3009801266849 -2440.0408445365,-25.1902015920577 -2439.8517425914,-25.0769580453572 -2438.83123622775,-25.3796053263497 -2437.84492822723,-25.6622637400461 -2437.07953111232,-25.8317070721061 -2436.51937092853,-25.8963150893526 -2435.9799330861,-25.9499581018791 -2435.9308767032,-25.7582375678275 -2435.88742788092,-25.5655635258689 -2435.26005291491,-25.6665486080174 -2434.92066868938,-25.6232196056427 -2434.59542429381,-25.5741289571034 -2434.51530883831,-25.402355235116 -2434.4416354732,-25.228043269122 -2433.70313787943,-25.3880090932295 -2433.5201885812,-25.2694180198501 -2433.34669153292,-25.1479892392389 -2433.40727737291,-24.909663136775 -2433.47006727403,-24.6733031662179 -2432.92563318826,-24.7419644683854 -2432.34404656294,-24.8283789807233 -2431.78360337876,-24.9055161966752 -2431.51112805846,-24.8361038573623 -2431.25067028751,-24.7617140453046 -2430.15148444435,-25.1076003773235 -2430.01351874174,-24.9694223261424 -2429.88361786535,-24.827819708609 -2429.24525146411,-24.9410905513481 -2428.62973876858,-25.0433431392987 -2427.93226832984,-25.1842399685061 -2427.31969156498,-25.2822087345181 -2426.72925133792,-25.3686684445796 -2426.3513053245,-25.3472485142963 -2425.9885901453,-25.3190050232546 -2425.16397238902,-25.5227160674988 -2424.46526830307,-25.6609300239346 -2423.79130445672,-25.7860803091247 -2423.07528388664,-25.930169888795 -2422.38456962932,-26.0585084661508 -2422.21718895078,-25.9249275638578 -2422.17707547349,-25.7286939647701 -2422.14230562835,-25.532330734155 -2421.62168475755,-25.5826233329727 -2421.12051097702,-25.6213966586716 -2419.63753378811,-26.1513174156324 -2418.06148445347,-26.7228538990515 -2416.53624935604,-27.2613715323602 -2417.05469256965,-26.7742530836876 -2417.56216803762,-26.2964256398603 -2416.36463008636,-26.675481718135 -2415.3835498446,-26.9440681854304 -2414.43577657672,-27.1913196217398 -2413.63549579162,-27.3635058118883 -2412.86328525671,-27.5193176769793 -2412.46378468281,-27.4871115046073 -2412.04137856757,-27.4654135500144 -2411.63595190606,-27.436448164479 -2411.12353641894,-27.4611088092215 -2410.6307388282,-27.4765634192136 -2410.09452011348,-27.5141375926045 -2409.01932993172,-27.8203741127788 -2407.98041329114,-28.1046280077638 -2406.83075289592,-28.4410368875746 -2405.71970622694,-28.7550361174 -2404.73863323161,-29.0015459248169 -2403.35412953778,-29.4470040281444 -2402.01535228899,-29.8656696339791 -2401.0774190268,-30.0789386663128 -2400.17216391771,-30.2726505369565 -2400.52284675637,-29.8391297259631 -2400.60570702687,-29.5433352335409 -2400.69100228105,-29.2485481244084 -2400.61399361598,-29.0379645277338 -2400.54405098715,-28.8273629060941 -2399.91333846675,-28.8977563309208 -2399.54787951532,-28.8351562710576 -2399.1979530906,-28.7653158705634 -2398.81558490953,-28.7123952248453 -2398.44922626701,-28.6521905748247 -2397.38620368357,-28.9407208169279 -2396.22839761414,-29.2738876252764 -2395.10958696118,-29.5826814155945 -2394.77066146006,-29.4997915539196 -2394.44661799598,-29.4094788572119 -2394.72217039058,-29.0203595826269 -2393.77915696079,-29.2457776529022 -2392.86878742356,-29.4534156441982 -2392.78110199952,-29.2461197154458 -2392.70083807142,-29.0372961790992 -2391.63354932022,-29.3247824904142 -2390.84823216137,-29.4679189802645 -2390.09095674339,-29.595081817236 -2389.99364833631,-29.3918044211803 -2389.90406152224,-29.1864602627223 -2389.56538504532,-29.1060831196932 -2388.80551794026,-29.23754337233 -2388.07291904974,-29.3549435871787 -2387.94290201795,-29.1688727282864 -2387.82155844431,-28.9817183584256 -2387.42844840795,-28.932503357168 -2386.83244011661,-28.9851098753426 -2386.25879038649,-29.0252182656663 -2386.93886104598,-28.4379228165118 -2387.6035515419,-27.8646512203344 -2387.97762753334,-27.4435226201542 -2388.65048449587,-26.8769854719047 -2389.30784525593,-26.3229313751275 -2389.13373403275,-26.1914327883266 -2388.96897654752,-26.0556929658746 -2388.88455384501,-25.8817234357994 -2388.7541283143,-25.7318262579713 -2388.63169715269,-25.5802665802574 -2388.57207553836,-25.3972001669713 -2388.51830945066,-25.2123145475771 -2387.9502909725,-25.2884126465473 -2387.86738110725,-25.1204975193687 -2387.79094875498,-24.9518810277055 -2387.34586137389,-24.9696635164277 -2386.91788412878,-24.9768016815327 -2386.28835145965,-25.0859246155204 -2384.68692719289,-25.6789944423656 -2383.13689833195,-26.2405763387774 -2382.67352092609,-26.2537709112333 -2382.22805896712,-26.2578142011717 -2382.09961549757,-26.1032841118507 -2382.50263400056,-25.6845071147129 -2382.89789731584,-25.2730845637078 -2383.03926928276,-24.9929781389139 -2383.1804805356,-24.7168663425768 -2382.28051936734,-24.9646927124959 -2381.87959449254,-24.9594788488682 -2381.49449003872,-24.9475777812738 -2381.37345626929,-24.802677292146 -2381.25995260336,-24.6541676210606 -2379.9953716698,-25.0838403108422 -2379.35077677379,-25.1984459078721 -2378.72925415389,-25.3007227397481 -2378.06287715409,-25.4251460678067 -2377.42023784939,-25.535071436591 -2377.147260237,-25.4598501225256 -2376.47782029408,-25.5838055842771 -2375.83224713445,-25.694043086156 -2374.71861161698,-26.0386521443183 -2373.64201972017,-26.3600341736689 -2373.00127373294,-26.459115431899 -2371.90237714991,-26.7870306328318 -2370.84026706095,-27.0938452816214 -2369.95192354423,-27.3113128870752 -2369.09423309168,-27.5111676750059 -2368.3314906386,-27.6615746480092 -2367.93128478538,-27.6295129541517 -2367.54738706294,-27.5876252614346 -2367.46607410474,-27.3956494442623 -2367.39163839038,-27.2022443914572 -2366.89130766852,-27.2240502259289 -2366.11333285598,-27.3836693849551 -2365.36279516378,-27.5293691831606 -2365.0697812446,-27.4451346943225 -2364.78987501107,-27.3540433923197 -2364.58759862101,-27.2247618136112 -2364.68390693114,-26.9482464371599 -2364.78175246471,-26.6739192744273 -2364.50045203343,-26.5925724046273 -2364.23174451496,-26.5056615840996 -2364.12647139989,-26.3375120074458 -2364.41728700138,-25.9713801181878 -2364.70373526405,-25.6119080621019 -2363.83063283097,-25.8356397941944 -2362.98746549017,-26.0429932604049 -2362.15651416619,-26.2422087379733 -2361.26060551284,-26.4712722213473 -2360.39542372798,-26.6826048085762 -2360.0917278183,-26.6112556332309 -2359.80131083264,-26.5341675994729 -2359.53341805008,-26.4466932451129 -2358.84167668107,-26.5718069335329 -2358.17465427623,-26.6831783542096 -2357.79558404238,-26.6492789085823 -2357.43202852724,-26.6085618977113 -2357.12833227038,-26.5384008556797 -2356.53197874103,-26.6150093311708 -2355.95753609281,-26.6797166019913 -2356.56658392994,-26.1537136384784 -2357.16185861847,-25.6396822335276 -2357.27748167508,-25.3695889490862 -2357.55694932507,-25.0193226217538 -2357.83218971901,-24.6749498538318 -2357.08931526521,-24.8439104961233 -2356.3723221454,-24.9963308104346 -2356.04965244275,-24.9521443437001 -2355.52627138941,-25.0077774001193 -2355.0223430317,-25.054371684277 -2354.12200630514,-25.2993989456798 -2353.25226331468,-25.524942036248 -2352.4915804746,-25.6943682255084 -2351.95824626227,-25.7471049603385 -2351.44481066329,-25.7895818121474 -2351.43329295825,-25.58168425438 -2351.42622177972,-25.3736761480427 -2351.21976931226,-25.2678421227675 -2351.54356575468,-24.8973471088642 -2351.86178552307,-24.5323182657712 -2351.16775799198,-24.6777877901791 -2350.49814791159,-24.8099728319053 -2349.94583351019,-24.8820648593626 -2349.46635305856,-24.9161536242793 -2349.0050179543,-24.9411751240361 -2349.57101401193,-24.4528739656338 -2350.1242005074,-23.9758272458774 -2349.4724145745,-24.1059406234413 -2349.18777457961,-24.050136775209 -2348.91536761192,-23.9892409114456 -2348.57474713476,-23.9638278554415 -2348.24797069162,-23.9312084497075 -2348.56453308903,-23.5779939089212 -2348.57319799418,-23.3807645565019 -2348.5853130692,-23.1846076414391 -2347.91625718615,-23.3303249324224 -2347.27063485643,-23.4631788040075 -2347.45970324203,-23.1766909837681 -2347.66759551687,-22.8838110467877 -2347.87296427493,-22.5968054147597 -2346.66447185629,-23.0175102991767 -2345.49528014755,-23.4150699097178 -2344.77167932398,-23.5863506770832 -2343.86667004585,-23.8459549171101 -2342.99215760587,-24.0886311678114 -2342.46515921222,-24.1540921260772 -2341.95756649883,-24.2099483663133 -2341.38678289979,-24.2961665810136 -2340.51709085245,-24.5318682489322 -2339.67697016453,-24.7504952370974 -2338.95821883735,-24.9071243604623 -2338.2646399383,-25.0493234961894 -2338.27001389822,-24.8399381451811 -2337.75392398217,-24.8929750935802 -2337.25705076314,-24.9357482782266 -2336.67123291198,-25.0233492613204 -2336.106701609,-25.0991955172278 -2335.96128107905,-24.9649513672926 -2336.40954850231,-24.5351210749284 -2336.84849892923,-24.1133735219111 -2336.68528687386,-23.9967159527341 -2336.53071601888,-23.8784205144914 -2336.5289543382,-23.6847771547218 -2336.03231517659,-23.7396527640104 -2335.55409471814,-23.7846893638151 -2335.12883622375,-23.8031344898303 -2334.71989764317,-23.8132379870928 -2334.23908985554,-23.8585387241776 -2333.4393270134,-24.062507581828 -2332.66700338349,-24.2510830204847 -2332.72212968512,-24.0247727729996 -2332.77944322167,-23.7994867651986 -2332.36749079559,-23.8113126753181 -2332.31138411135,-23.6441792310606 -2332.26068896882,-23.4757931735697 -2331.50934790825,-23.6591579495455 -2330.78394336967,-23.8283291271497 -2330.86574005206,-23.5910633681525 -2331.24618740655,-23.2095864799996 -2331.61904783476,-22.8350479105863 -2330.32804930757,-23.295886908392 -2329.07881533905,-23.7298780853548 -2328.59861059287,-23.7766933489248 -2328.14734948466,-23.8077221386276 -2327.71318604549,-23.8305057688153 -2327.30126251593,-23.8420977550894 -2326.90526772585,-23.8446611471079 -2326.0523101241,-24.0758700115197 -2325.44413787937,-24.1815441149401 -2324.8577814073,-24.2769983472079 -2324.68361726169,-24.1641587421838 -2324.51845038183,-24.0491391909636 -2323.78715343222,-24.217349578906 -2322.68410155262,-24.5701021505703 -2321.61752182594,-24.9018866502529 -2321.39442950907,-24.8070271682703 -2321.18190742515,-24.7079253509478 -2320.81347054926,-24.6889880860498 -2321.11645049084,-24.3339885610806 -2321.41437221348,-23.9847517153413 -2321.28097516264,-23.8555367420186 -2321.15529156882,-23.7242727551075 -2320.77299100675,-23.7210341328144 -2320.10056816563,-23.8639817773641 -2319.45176411697,-23.9926464650386 -2319.22005841139,-23.9123152121699 -2318.99898149749,-23.8285990952247 -2318.98591197154,-23.640429873452 -2318.68446163372,-23.5968069708696 -2318.39566938867,-23.5494645547652 -2317.80907634698,-23.6508046036612 -2317.24353624145,-23.7399248224284 -2316.96624825422,-23.6848821172239 -2316.48726951755,-23.7296085394164 -2316.02621204495,-23.7668524309763 -2315.65187699119,-23.7586775924975 -2315.29237667114,-23.7448417816531 -2314.38328104558,-24.0045009286977 -2313.44007389982,-24.278905112706 -2312.52857693476,-24.5358906180965 -2312.19301870373,-24.5022502420674 -2311.87126411101,-24.4608120305136 -2311.20127593411,-24.5950739760289 -2309.90720125504,-25.0405431020935 -2308.65530709471,-25.4608439023097 -2307.67253192111,-25.7407683861647 -2306.72291231043,-26.0021706634253 -2306.78832409405,-25.7526377816258 -2306.58340399869,-25.6415166578581 -2306.38865408541,-25.5259206578912 -2305.43942150612,-25.7892628226541 -2304.52234792987,-26.0329119258448 -2304.19227149413,-25.980751356038 -2304.16525097684,-25.7778432760295 -2304.14318897329,-25.5750159577255 -2303.24603129571,-25.8107950231793 -2302.37952041548,-26.0287279044144 -2302.36904969021,-25.8169933481623 -2302.86851687849,-25.3522841177734 -2303.35732975846,-24.898037139837 -2303.07598114793,-24.833424333873 -2302.80690578087,-24.7624486579046 -2302.2231297808,-24.8493134965645 -2302.19232819504,-24.6599051270092 -2302.16637397065,-24.4689971177394 -2302.05632768756,-24.323141191579 -2301.953399049,-24.175566999714 -2300.66639053882,-24.6210251607898 -2299.68276793565,-24.9102658921343 -2298.7321551039,-25.1798032150812 -2298.10376138046,-25.2862510334313 -2297.4979614447,-25.3794156321553 -2297.55859995526,-25.1380666756388 -2297.77453527389,-24.8218940831014 -2297.98807929569,-24.5095542941543 -2297.74176380015,-24.4304544145222 -2297.50662628318,-24.3473362367596 -2297.51409701549,-24.1434538335832 -2296.74187057716,-24.3317203207369 -2295.99630538451,-24.5043961712327 -2296.18485715315,-24.2091264138361 -2296.37168966704,-23.9170184964662 -2296.00457580999,-23.9042122785294 -2295.37881677905,-24.0203489337007 -2294.77536205094,-24.1261462611091 -2294.38778959297,-24.1235323692262 -2294.01546404824,-24.1117207257303 -2293.20645706985,-24.3186870617105 -2292.58501588138,-24.4307752737272 -2291.98578748757,-24.5303429772835 -2292.15496347015,-24.2445840940932 -2292.32299716194,-23.9614545346325 -2290.93757978397,-24.4586920442365 -2289.57085030212,-24.9417491177539 -2288.24842784552,-25.3985042559135 -2287.81682919017,-25.4032496700207 -2287.40206229678,-25.4001903116812 -2286.93874672592,-25.4212274749209 -2286.46745308673,-25.4459849522168 -2286.01416309881,-25.4627044120708 -2285.03393659784,-25.741719835111 -2284.08678319489,-26.0009586447368 -2283.70074603119,-25.9765489736587 -2283.14967512483,-26.0369358096918 -2282.61905128336,-26.085052413535 -2281.85115319728,-26.2516132723308 -2281.11016373358,-26.4032752760935 -2280.57622320569,-26.4498167999616 -2279.8144204424,-26.6085472177886 -2279.07943777256,-26.7525543744397 -2279.38713787475,-26.3750142863689 -2279.69002781586,-26.0029408247499 -2278.74266795658,-26.2603232214116 -2278.2027465159,-26.3107446198029 -2277.6830264643,-26.3508308211475 -2278.21362746488,-25.8666382397058 -2278.73272779107,-25.39276605736 -2278.28426649898,-25.4071005739019 -2278.03131698123,-25.3231209482161 -2277.78989932976,-25.2344599770128 -2277.83521746445,-25.0024644801514 -2277.88321665814,-24.7717505568899 -2277.31972172942,-24.8497155230468 -2276.72869487292,-24.9387461062933 -2276.15913133837,-25.0181281352046 -2275.65090754688,-25.0663747261962 -2275.16168407285,-25.1036047755463 -2274.58771782414,-25.1825016140733 -2273.22537582136,-25.6547895253094 -2271.90737574921,-26.0999993774615 -2271.26311337992,-26.2042399801681 -2270.64210942008,-26.2971979148327 -2270.70555148181,-26.0456010901237 -2271.32803735091,-25.5165577177689 -2271.93628159113,-24.9998914852987 -2271.17253238399,-25.1740683011001 -2270.43538277529,-25.333748672544 -2269.64657238068,-25.5173855779334 -2268.54831893918,-25.8540159826924 -2267.48665930458,-26.1683168350522 -2265.80101849966,-26.7920132125174 -2264.1694867106,-27.3821940082163 -2263.78151003189,-27.3450806638134 -2262.48616957332,-27.7633449938068 -2261.23358202657,-28.1555183312749 -2261.3516138736,-27.8588091477732 -2261.47071920611,-27.5639652380056 -2261.2633572519,-27.4352748509611 -2260.83902513113,-27.4167450177892 -2260.43168710463,-27.3886999124043 -2259.87444770609,-27.4367454721365 -2259.33813438605,-27.4740994094338 -2259.1073006174,-27.3583186874728 -2258.99519724932,-27.1850485629563 -2258.89081896971,-27.0093697286753 -2258.37129327447,-27.0424475756703 -2257.87150252302,-27.0654622193406 -2257.43843284362,-27.0556964733792 -2257.96924272881,-26.5623246245407 -2258.48872013624,-26.0798633770715 -2258.90821983714,-25.6519644402319 -2259.31949340925,-25.2342950184722 -2258.92565722474,-25.2215588090138 -2258.88441267923,-25.031954547736 -2258.84842872692,-24.842763567046 -2257.58160616314,-25.2714479356968 -2256.35621809741,-25.6744303935274 -2255.68577509482,-25.7962322590975 -2255.59385847417,-25.62844283568 -2255.50877010516,-25.4585851532686 -2254.45843299796,-25.7724871079299 -2253.44324764739,-26.0658417590029 -2252.93096841871,-26.1061270648957 -2251.80049273861,-26.4542359656669 -2250.70765372831,-26.7797066671497 -2250.02951302083,-26.8943667563106 -2249.37575887095,-26.9955617049487 -2248.89410948247,-27.0084882602784 -2248.55673521513,-26.9502011846362 -2248.23370939881,-26.885490778642 -2247.94937068986,-26.803547998226 -2247.67775547524,-26.7148085966457 -2247.29916348381,-26.6804498332868 -2248.08805920205,-26.0629535410857 -2248.85788806825,-25.4609695722511 -2247.74082842704,-25.8093356510228 -2246.66087447193,-26.1354716185048 -2245.49351292578,-26.5013435974739 -2244.67371697543,-26.6889920819525 -2243.88245934296,-26.8611556922831 -2243.20706058835,-26.9732367972934 -2242.55599043684,-27.0726800532194 -2242.44241092489,-26.9026843719835 -2242.50926569561,-26.6449960802343 -2242.57845078318,-26.3879337056414 -2241.82920277338,-26.5415824284258 -2241.10638023499,-26.6801202946502 -2240.01836781248,-27.0003384774387 -2239.01235978903,-27.2754620903557 -2238.04051053928,-27.5313463608751 -2237.7395603007,-27.4498597783956 -2237.451976127,-27.3614674294549 -2236.67150152001,-27.5211739154913 -2235.80692193293,-27.7220024942872 -2234.97238336046,-27.9049766438018 -2234.64052957403,-27.8351979217963 -2234.3230286022,-27.7602739316211 -2233.63889101068,-27.86855690527 -2232.99978260525,-27.9517134809486 -2232.38413566924,-28.0237978650488 -2231.99798221112,-27.9777927935582 -2231.62785382366,-27.926355790113 -2231.07467920784,-27.9671862695993 -2230.11061139721,-28.2133243555362 -2229.17961486803,-28.4385592668273 -2229.03325267748,-28.2705308210177 -2228.89585813804,-28.0995699764737 -2229.08000117462,-27.7696455398517 -2228.83461531172,-27.6565421360586 -2228.60102438152,-27.5398216578659 -2228.17337739587,-27.5215756992544 -2227.76284902518,-27.4945944977392 -2227.79975922891,-27.2450010021745 -2227.86049713592,-26.9850957450774 -2227.92384780229,-26.7258645137534 -2227.58529399119,-26.6705353912669 -2227.2610780415,-26.6085665007102 -2227.23745305855,-26.3979871638091 -2226.82462655895,-26.3837272657548 -2226.42826096889,-26.3626094755534 -2225.7860247695,-26.4648535085017 -2225.16700589928,-26.5519960381132 -2225.06086185497,-26.382435694546 -2225.36625339841,-26.0093874540013 -2225.66683898473,-25.6418548983148 -2224.96922760065,-25.7775994489696 -2224.29636106302,-25.898284158076 -2223.42658329353,-26.1173569239023 -2222.57523090094,-26.3243562914847 -2221.75328230907,-26.51482114464 -2221.05154185883,-26.6427692396072 -2220.37485797054,-26.7564390272778 -2219.94017756359,-26.7480639815408 -2219.04119710095,-26.9734109674523 -2218.17313536768,-27.1802115678038 -2218.11372634689,-26.9815509823476 -2218.06046417146,-26.7805019586609 -2217.44287552546,-26.864985091803 -2216.35615175251,-27.1833209107003 -2215.30592125422,-27.4786856841175 -2215.28857484321,-27.2545548680329 -2215.2762154369,-27.03151322967 -2215.10058358307,-26.8918380656278 -2215.15383800392,-26.6394294447436 -2215.20985455715,-26.3876887768059 -2215.1123159299,-26.2160022895546 -2215.02190087793,-26.0425873753438 -2215.09623152774,-25.7875730261553 -2215.01252392772,-25.6148618613525 -2214.9354172795,-25.4406147797163 -2214.46998015408,-25.4618073776307 -2214.02238554851,-25.4730391286165 -2213.38448864421,-25.5793377980339 -2213.03849623023,-25.5393037988284 -2212.70683943663,-25.4930392201788 -2212.22044942255,-25.5251951537671 -2211.75251282013,-25.5469487384551 -2211.63820998597,-25.3924919601282 -2211.39847821846,-25.3028614029065 -2211.16986863747,-25.2073491535054 -2211.56982550833,-24.7980170203713 -2211.96196574719,-24.3969033713926 -2211.24472218355,-24.553902265699 -2210.85961778908,-24.544271743699 -2210.48979836544,-24.5262316624522 -2210.46217470135,-24.337590255229 -2210.43925905478,-24.1481819331182 -2209.93667308198,-24.1997501228682 -2209.76251985769,-24.0876130003718 -2209.59734997214,-23.9734390059978 -2208.25818174173,-24.4475540499847 -2206.96241169035,-24.8944246000606 -2206.53074134732,-24.9046434206032 -2206.37449224952,-24.7755823590195 -2206.22684967815,-24.6438701034587 -2206.20637273395,-24.4507560426218 -2206.19040953059,-24.2569338344465 -2205.27758261504,-24.5140849938536 -2204.63222671951,-24.6339896026707 -2204.00987111406,-24.7410494708013 -2203.56991985296,-24.7562751506128 -2203.14692647213,-24.7635299113975 -2202.19616261117,-25.0349352677129 -2201.34949814668,-25.2506875367673 -2200.53188547561,-25.4499231397101 -2199.65040918007,-25.6794597063306 -2198.79908477076,-25.8912584709006 -2198.04106337314,-26.0543510148281 -2196.93000518629,-26.3924775973315 -2195.85601412912,-26.7103071784153 -2195.87305239471,-26.4783532154854 -2195.8938797726,-26.2469301787897 -2196.35549880021,-25.7957341562837 -2196.8700344344,-25.3242500278937 -2197.37345511282,-24.8617548113511 -2197.05673394776,-24.8137094272649 -2196.75335462491,-24.7599700605578 -2196.51297395438,-24.675839713145 -2196.099768886,-24.6791990092526 -2195.70270100387,-24.6735044876849 -2195.43123430021,-24.6054730749359 -2195.17171906251,-24.5326974254288 -2195.05410682925,-24.389555662234 -2194.93491380743,-24.2479029924208 -2194.82311630409,-24.1041424338573 -2194.38506447918,-24.1264071447905 -2193.96376079717,-24.1396857941283 -2193.40832578934,-24.2189910152842 -2192.51085659886,-24.4680256843999 -2191.64379170307,-24.698660932302 -2191.2043339163,-24.7139517985128 -2190.7818134081,-24.7225589704665 -2190.49550531474,-24.6625175009254 -2189.87106198531,-24.7712325748526 -2189.2690139818,-24.8672720551618 -2189.16674745574,-24.7125860619479 -2189.07146320739,-24.5568496263443 -2188.24692793855,-24.7670329346571 -2187.53214125122,-24.9194799826059 -2186.84245190074,-25.057345187589 -2186.08393229149,-25.2283170734663 -2185.35186881387,-25.3848625136135 -2185.4606038013,-25.1188916793463 -2185.1392871869,-25.0708174065145 -2184.83149315705,-25.016503375281 -2184.9825458067,-24.7335229690744 -2185.13311338934,-24.4540801537113 -2184.63425137051,-24.5024901062561 -2184.23621212509,-24.4983813171989 -2183.85385892045,-24.4867260204729 -2183.22744090806,-24.5981548232642 -2182.62344350228,-24.6970219581788 -2182.79255791755,-24.4075790675783 -2182.03872576232,-24.5833646210681 -2181.31107344553,-24.7429722288191 -2180.71990814156,-24.8339534237997 -2180.15017410547,-24.9139893223949 -2179.5119818994,-25.0275011698754 -2178.8200437803,-25.1654891383085 -2178.15258495032,-25.2911359567105 -2177.37637124111,-25.4683578420056 -2176.62718734902,-25.6308909495878 -2176.38312471488,-25.5389347011269 -2176.42718606969,-25.3040688620443 -2176.47403291765,-25.0705510379496 -2175.51974118769,-25.3402680354219 -2174.59768433214,-25.5915701271109 -2173.92338522721,-25.7147349326697 -2173.736313041,-25.5943417357547 -2173.55888939211,-25.4707035069728 -2172.42804124335,-25.824703951961 -2171.33473115812,-26.1557825166767 -2171.49241333243,-25.8585796504049 -2171.4037313034,-25.6858897478545 -2171.32184486458,-25.5128476114253 -2170.96108960273,-25.4791453815126 -2170.61512714133,-25.4404627028026 -2170.37621452509,-25.3478775631747 -2169.73721015868,-25.4578214322427 -2169.12114844301,-25.5547587262631 -2168.4258055765,-25.6903389699339 -2167.75512176534,-25.8111450594207 -2166.87442989221,-26.0356618179555 -2165.68171619388,-26.4147775263191 -2164.52848369244,-26.770587417216 -2164.08842006789,-26.7670742017334 -2163.66567881227,-26.7534662885472 -2163.07313992325,-26.8258039968079 -2162.76763076888,-26.7534740581533 -2162.47549048186,-26.67448963708 -2161.95378390686,-26.7122352142105 -2161.45180809359,-26.739444677308 -2161.67531352157,-26.4029516899482 -2162.18100259538,-25.9301147277565 -2162.67594958214,-25.4671352385639 -2161.74837735524,-25.7190450436276 -2160.85233451263,-25.9535693006069 -2159.92287590341,-26.2009452657577 -2159.02842504648,-26.4291193873103 -2158.16466098775,-26.6390755434221 -2158.31302542668,-26.3412622831463 -2158.4612952283,-26.0464418072264 -2158.3010447734,-25.9089737068235 -2158.31699163817,-25.6852090202618 -2158.33661304547,-25.4610523060648 -2156.96915984832,-25.9331681669251 -2155.64625229739,-26.3781014833877 -2154.83041998303,-26.5643403738185 -2154.33619161656,-26.5885410499615 -2153.86087686959,-26.6028739971284 -2153.55754519396,-26.5309237210029 -2153.26748971141,-26.4541144300485 -2152.33056905858,-26.7016561899391 -2151.26998636132,-27.0080040130547 -2150.24510230815,-27.2935072291172 -2149.69731906581,-27.3376591594339 -2149.17016594604,-27.3705749400038 -2148.97027633359,-27.2402697782883 -2148.1095981533,-27.4418553363118 -2147.27879346781,-27.6265484903208 -2147.22357062661,-27.4212832066658 -2147.17445740557,-27.2143417378686 -2146.46793679377,-27.3371682449987 -2145.36900601541,-27.6571081821332 -2144.307016323,-27.9539994448068 -2144.20741300102,-27.7665028398555 -2144.11531801492,-27.5773923759199 -2144.17297670857,-27.3150127525502 -2144.07565919654,-27.1328257228823 -2143.98565836622,-26.9487981595758 -2144.42719182606,-26.501100082342 -2144.86001567153,-26.062686259398 -2144.93808127587,-25.8051920271291 -2144.93993698058,-25.5890447987616 -2144.9458733655,-25.3725689293718 -2144.53035299506,-25.3691098333167 -2144.13119161455,-25.3576546838066 -2144.25463046214,-25.0851506622978 -2144.18563213299,-24.9118489975498 -2144.12266935324,-24.7363858746964 -2144.12945340381,-24.5296335549719 -2144.13994436385,-24.3224396590198 -2144.48074884358,-23.9515964207015 -2144.52913025771,-23.7301836274427 -2144.57986926476,-23.5113355964885 -2143.596334612,-23.8110204509669 -2142.64560558994,-24.0908544692864 -2142.28534018438,-24.0726847174739 -2141.60254903627,-24.2147162268188 -2140.94380082538,-24.3455792713077 -2140.68511101412,-24.2749148662325 -2140.43792228295,-24.1993945196476 -2139.53589445714,-24.4516230553009 -2138.16867363377,-24.9339541766674 -2136.84579305086,-25.3894096765392 -2137.39280745034,-24.9058820351463 -2137.92766483002,-24.4307568780362 -2137.2562797528,-24.564540547708 -2137.30779914728,-24.3357012508347 -2137.36169580093,-24.1084712410994 -2136.492903301,-24.3447029607959 -2135.65363670394,-24.5641107179089 -2135.2633720488,-24.5562387030921 -2134.2441235002,-24.8626897643761 -2133.25895090322,-25.149886542175 -2133.37105745161,-24.8861832994011 -2133.48383558037,-24.6232179464444 -2133.70709896715,-24.3082938509131 -2133.33279924144,-24.2955222770465 -2132.9734211942,-24.2739116926079 -2133.55152290718,-23.7851479476592 -2134.1163492852,-23.3077117997905 -2133.64283910874,-23.3544504286703 -2133.1510971218,-23.409475730055 -2132.67757894373,-23.4540848817562 -2131.88731092951,-23.6577525148755 -2131.12411562436,-23.8458600972542 -2130.26243368354,-24.0807553344786 -2129.01284765356,-24.5070172156745 -2127.80406682855,-24.9084378849967 -2127.98340543974,-24.611875462488 -2128.16141088293,-24.3189851617643 -2127.93148012234,-24.2335241379141 -2127.23453575034,-24.3819857261313 -2126.56206570323,-24.5182161891901 -2125.60630502829,-24.7925257030752 -2124.68274857611,-25.0489558755312 -2124.15411666702,-25.1056165087415 -2123.30706554561,-25.3209672083409 -2122.48908909488,-25.5196925288205 -2121.98274335215,-25.5615775476644 -2121.49544653146,-25.5917983301169 -2121.23192091554,-25.5105584576465 -2120.82581783416,-25.5009156819273 -2120.43582331593,-25.4853357377444 -2120.02896035224,-25.4772146359227 -2119.63820650643,-25.4612583652954 -2119.10029676129,-25.5186122715639 -2118.34709277404,-25.6834521913435 -2117.62025432395,-25.8328102490588 -2117.83042870154,-25.5127632317252 -2118.0385121185,-25.1959082153117 -2117.3029450087,-25.3545268384428 -2117.05845012453,-25.2649139544498 -2116.82526384868,-25.1709543726832 -2116.76486258722,-24.9919146886269 -2116.71027004545,-24.8121328917655 -2116.02599237264,-24.9498300514593 -2115.16122209897,-25.1765725519739 -2114.32600235996,-25.3854553996971 -2113.48426662462,-25.5943506003855 -2112.67152119169,-25.78821105901 -2111.8836637405,-25.9667239976845 -2111.51568133093,-25.9338442305975 -2111.16275929342,-25.8939465758943 -2110.77890744753,-25.8709511252862 -2110.41054827797,-25.839045065845 -2110.04115044927,-25.8075346743976 -2109.48769655628,-25.8698332332691 -2108.95474642961,-25.9202676245303 -2108.75429204417,-25.8040040884041 -2108.56393155626,-25.6841490381133 -2108.53777508544,-25.4820895502371 -2108.32402341711,-25.3764352351124 -2108.12068316703,-25.2685065161929 -2107.87555426021,-25.1816213814688 -2107.6417064058,-25.0894714951141 -2107.28983838513,-25.0570977023614 -2106.80793762926,-25.0908806956646 -2106.34428299635,-25.114846017973 -2106.20577261366,-24.9755455429456 -2106.07536998234,-24.8330284546105 -2105.84528005987,-24.7433518656109 -2105.12482225016,-24.9000702928952 -2104.42960206357,-25.0415099630599 -2104.35550271025,-24.8700004896934 -2104.28760447867,-24.6988494445133 -2103.5948071333,-24.8420207193652 -2102.5937231064,-25.1368720320527 -2101.62622570013,-25.4119601782904 -2101.06133842131,-25.4829335138556 -2100.51723651818,-25.5433065447315 -2100.31821072562,-25.4310545126386 -2100.06954767633,-25.3445795857318 -2099.83229637043,-25.252996511493 -2099.57236326392,-25.1726401543021 -2099.32416622563,-25.0874260229995 -2099.57902535347,-24.7511827180384 -2099.70725886671,-24.4823873478507 -2099.83562947261,-24.2149074681051 -2099.88434874165,-23.9912909669743 -2099.93545470235,-23.7687722502751 -2099.62354512444,-23.7293644372089 -2099.29885492317,-23.6957297567921 -2098.98754211619,-23.6575230962937 -2098.60082590318,-23.6578251231682 -2098.2292669984,-23.6498175359816 -2098.3509202137,-23.3946048540686 -2098.89640042817,-22.9304797950416 -2099.42941094193,-22.4771906324905 -2098.67537408077,-22.6725795244077 -2097.94714839069,-22.8522143372045 -2097.95437280079,-22.6628552257343 -2097.90931980594,-22.5012036341488 -2097.86913960035,-22.3389577437738 -2097.70051557356,-22.2426919355187 -2097.54035310611,-22.1423275793289 -2096.18224061796,-22.6426050878183 -2094.67354423695,-23.2144034844851 -2093.21301615632,-23.7558325494835 -2092.23164198304,-24.0521619062537 -2091.28305320681,-24.3288829466517 -2090.48312594973,-24.5286748550563 -2089.59484679407,-24.7720180730379 -2088.73672095835,-24.9959016702514 -2087.91395512329,-25.1994363811875 -2087.11953878846,-25.3873243076847 -2086.39636847506,-25.5371387636946 -2086.50096057802,-25.2715745904863 -2086.60655466141,-25.0082775472386 -2085.76573812355,-25.2210941679263 -2084.95380049322,-25.4176161679696 -2084.64229569551,-25.3617112958013 -2084.97173221379,-24.9859805360615 -2085.29547152016,-24.6169771147709 -2084.31847685265,-24.9021184816524 -2083.3743108483,-25.1683444367661 -2082.99551535438,-25.1486552852949 -2081.81042044078,-25.5322438339787 -2080.66442204291,-25.8926710110736 -2080.00022935377,-26.0083978249321 -2079.35985582356,-26.1104239670015 -2079.12934446607,-26.0077499872525 -2078.73667216122,-25.9868424781955 -2078.35979826071,-25.9579592992297 -2078.43845415063,-25.7026295810723 -2078.51893231457,-25.4475569316403 -2078.72890398282,-25.1311673415335 -2078.85357645786,-24.8607667047963 -2078.97855650006,-24.59231179461 -2078.40633676117,-24.6759534338823 -2077.85494647152,-24.7467893034684 -2077.81112062807,-24.5650761093477 -2077.47594226109,-24.529770696321 -2077.154584633,-24.4870034905475 -2076.78809417451,-24.4703665563146 -2076.43629346975,-24.4447098707801 -2075.60619691624,-24.6585124019872 -2074.45783966384,-25.0289403906395 -2073.34739133711,-25.3764198429427 -2073.02139590581,-25.3281340564167 -2072.70911057951,-25.2733523382974 -2072.22575014422,-25.3041064371556 -2071.8709157237,-25.2712482706684 -2071.53062572855,-25.231367452582 -2071.58066546885,-24.9971285332923 -2071.63324424352,-24.7636150305094 -2071.41241491738,-24.6697979691938 -2071.65318939571,-24.3454466201684 -2071.89075579709,-24.0267431831995 -2071.97568763724,-23.7869166772339 -2072.06189776526,-23.5487950061728 -2071.62407793323,-23.5759244877561 -2070.94663449295,-23.7224968619907 -2070.29293705035,-23.8549563315545 -2069.90771886116,-23.8515727336748 -2069.53767006503,-23.8417374234319 -2068.45681657686,-24.1859273577334 -2067.40996772623,-24.5098459424093 -2066.3979413804,-24.8147662220797 -2065.76667530406,-24.9254020767645 -2065.15803516367,-25.0225184837897 -2064.34921949839,-25.2202168207154 -2063.97708141981,-25.1967610850244 -2063.61998556641,-25.1657751764142 -2062.91652101451,-25.3079511875926 -2062.23790722563,-25.4368498292103 -2061.60045422276,-25.5430330887325 -2060.42866269947,-25.9170843972949 -2059.29562933274,-26.2675856550122 -2059.26453572147,-26.0635898884092 -2059.23858123039,-25.8591898194856 -2058.81669062775,-25.8540179427645 -2058.88094204132,-25.6061467746281 -2058.94743720526,-25.3595706174865 -2058.97625474752,-25.1346340387711 -2059.0082646929,-24.9105778381408 -2058.97585774787,-24.7202450615301 -2059.48455182676,-24.2618297757742 -2059.98210886851,-23.814438050437 -2059.18054930842,-24.0201507438378 -2058.40646590054,-24.2099085398638 -2058.07422067244,-24.1778964941849 -2057.19999314007,-24.4171787743341 -2056.35544599879,-24.6384683064711 -2055.14428101463,-25.0410043219552 -2053.97287066082,-25.418278923335 -2054.24190899589,-25.0715498849445 -2055.13285498574,-24.4184178531013 -2056.00141750983,-23.7826439736366 -2054.82022279071,-24.1792922331666 -2053.6777207082,-24.5526634338268 -2053.38208920092,-24.4984523892752 -2052.48535721465,-24.7448231953403 -2051.61905180562,-24.9729624165278 -2050.99481088809,-25.0782916084061 -2050.39302242237,-25.1715732784552 -2049.72287434562,-25.2972400010623 -2049.29082508529,-25.3043139633298 -2048.87558051019,-25.3010677916443 -2048.74166521434,-25.1575397498877 -2048.61575873295,-25.0109249610282 -2047.78933485862,-25.2166153523262 -2047.10820068513,-25.347673094058 -2046.45125534878,-25.4648715519044 -2045.74351080639,-25.6078928268815 -2045.0607686027,-25.7353575735726 -2044.68804488164,-25.7073892426156 -2044.3660215279,-25.6541381483054 -2044.05764794668,-25.5945796219971 -2043.25051141319,-25.7848077913029 -2042.47136725214,-25.9594181830954 -2042.31742220346,-25.8192979093861 -2041.68605102837,-25.9187246588516 -2041.07752530208,-26.0067985692268 -2040.59950606225,-26.0280185468403 -2040.13982215986,-26.0402206023864 -2038.75090732005,-26.5174230134025 -2037.85707733749,-26.741869975905 -2036.99398142906,-26.9485621685384 -2036.92314180097,-26.7572526873039 -2036.85875595408,-26.5652331594615 -2035.69126517428,-26.9264614556607 -2034.36153710445,-27.3650242671527 -2033.07552023036,-27.7773132486236 -2031.7997798715,-28.1820765891874 -2030.56628333845,-28.5596616249339 -2029.79970800214,-28.6997989708936 -2028.84127000543,-28.9351773698907 -2027.91588930161,-29.1521418377607 -2027.48844468049,-29.1184026968485 -2027.07840845355,-29.0748478896069 -2026.63576538197,-29.0489337434208 -2025.84098909808,-29.19938453904 -2025.07448489634,-29.3339040564232 -2024.62545675008,-29.3068957610031 -2024.19455394771,-29.2724461219489 -2024.31554863777,-28.9627479933197 -2024.54885413198,-28.5986732764721 -2024.78000772388,-28.2404763854551 -2024.53679411705,-28.1230113725112 -2024.30537408075,-28.000090634057 -2023.79311835432,-28.0200662746601 -2023.52917672272,-27.9152344504367 -2023.277598649,-27.803985329582 -2022.33629894183,-28.0405735272203 -2021.42736128934,-28.2574243197672 -2020.99832104272,-28.2324223633634 -2020.78347685388,-28.1006483061277 -2020.57958883271,-27.965134001129 -2019.81766303044,-28.1105414587391 -2019.08281815733,-28.2399900105431 -2019.03715524255,-28.0233647551739 -2019.02096237721,-27.7938860609901 -2019.00981404989,-27.5645047719613 -2018.71976249911,-27.47754882125 -2018.44275477484,-27.3841796627498 -2017.74073066524,-27.5041565561248 -2016.67189194057,-27.8058754040152 -2015.63916452765,-28.0872361642974 -2015.75505053301,-27.7908537757366 -2015.87208788249,-27.49889702254 -2016.06163248938,-27.1718998774003 -2016.78022837748,-26.5830835123981 -2017.4819627565,-26.0089489674826 -2017.42102860449,-25.8218049236614 -2017.36607979855,-25.6341547115028 -2016.82059812911,-25.6941083564485 -2016.4520773061,-25.6641589973043 -2016.09858165614,-25.6269344592811 -2015.84176162881,-25.5419835270389 -2015.59664389456,-25.4524828206959 -2015.43194340269,-25.3231149127482 -2015.49408714291,-25.0809131360306 -2015.55844833332,-24.8403048537393 -2015.23053197848,-24.7987881941264 -2014.91627097369,-24.7501665674345 -2014.4644095479,-24.7712039580203 -2013.82473272228,-24.8860117620916 -2013.20793145007,-24.9880552578191 -2012.91802741264,-24.9260751197334 -2012.64068148745,-24.8594973563314 -2012.28073533402,-24.834067214313 -2012.48616575686,-24.5258242022813 -2012.68946440575,-24.2220953889258 -2012.09049551492,-24.3227749188308 -2011.51307750872,-24.4116919399297 -2010.59779368983,-24.6679018474537 -2009.97930781307,-24.7727990553549 -2009.38305703434,-24.8658329638882 -2008.46876594462,-25.1169386635371 -2007.5854989384,-25.3514708235578 -2008.11290413139,-24.8767313309852 -2008.67724515907,-24.3885000855242 -2009.22884017474,-23.9127988550495 -2009.50229754106,-23.5794608447065 -2009.7714380229,-23.2506538004892 -2009.39092911672,-23.2503530306733 -2009.07185841298,-23.2206276506654 -2008.76586964312,-23.1844522834543 -2007.91175697078,-23.4214331739221 -2007.08658021052,-23.642564850418 -2005.80964613512,-24.0873858359375 -2004.79133093435,-24.3981390281688 -2003.80697241981,-24.6892121486557 -2003.27665247521,-24.7497348956305 -2002.7659633403,-24.8007383968774 -2001.84769976844,-25.0546508492938 -2000.98547460591,-25.2772695891726 -2000.1527794258,-25.4832617321352 -1999.90035755338,-25.3975626939311 -1999.65947989818,-25.305292784577 -1998.89603061312,-25.4755164133819 -1998.34301163893,-25.5413808167379 -1997.81041085735,-25.5953877780088 -1997.35293257551,-25.610695799756 -1996.91309782475,-25.6172217751074 -1996.99003153063,-25.3659123191578 -1997.58409188396,-24.8565548235364 -1998.16464689073,-24.3603652012936 -1997.17281996449,-24.6559963003993 -1996.21420170448,-24.9322412367413 -1996.85425536471,-24.4055184984579 -1997.54758406651,-23.8585144502959 -1998.2242385264,-23.324650515721 -1997.51516415349,-23.4890609143433 -1996.83073325267,-23.6396816375045 -1996.23166555048,-23.7454904827224 -1995.32103906938,-24.005761317329 -1994.44111686735,-24.2484084277594 -1994.51248633491,-24.0128657795065 -1994.58558355213,-23.780531659195 -1993.88826962048,-23.9348650387655 -1993.2024896098,-24.0810707840609 -1992.54078951812,-24.2144716964386 -1992.15144135956,-24.2093467659982 -1991.77745799093,-24.1975532826122 -1990.90233804013,-24.4353158446908 -1989.92933828155,-24.720511990923 -1988.98900949344,-24.9855853959961 -1988.95204487011,-24.7968244288686 -1988.92015682001,-24.6074065645315 -1988.66860692072,-24.5300032947687 -1988.21524312879,-24.5539083493035 -1987.77919634023,-24.5688482127013 -1987.4041682876,-24.5534155240074 -1987.04414160652,-24.530237559593 -1987.44563208816,-24.1278066575388 -1988.19520572855,-23.5542258638522 -1988.92641046093,-22.9962133643792 -1988.17853097646,-23.183569635948 -1987.45637558608,-23.3558340465073 -1986.98356895699,-23.4014188349132 -1986.68840462123,-23.3584418708767 -1986.40563949239,-23.3097375328398 -1985.4701496404,-23.5877954274915 -1984.56599716566,-23.8469095566783 -1983.7316875355,-24.0686758729486 -1983.2015322672,-24.1349919962092 -1982.69089002727,-24.1931042799408 -1981.86301552798,-24.4083932872922 -1981.06346497102,-24.607144306293 -1980.49078278768,-24.6910495120091 -1979.5757291491,-24.9452192351625 -1978.69167061583,-25.1804292264363 -1978.02272164484,-25.3062032029092 -1977.37758526194,-25.4189943435971 -1976.86250242407,-25.4648517200141 -1976.7122274665,-25.3281728662912 -1976.57047117177,-25.1892161623985 -1975.49868852427,-25.5165807880285 -1974.46263981532,-25.822638001604 -1974.07497841781,-25.8012256702647 -1973.19119194416,-26.0273440370056 -1972.33771362208,-26.2364172124123 -1971.87954517066,-26.245296844485 -1971.43917083848,-26.2460009444963 -1970.86628815626,-26.3120050440732 -1970.1305161195,-26.459923375742 -1969.42075127638,-26.5928583526109 -1969.06347159628,-26.549649100256 -1968.72103112439,-26.4993774248892 -1968.70439695719,-26.2862159541493 -1968.31491145541,-26.2610800971911 -1967.94118065478,-26.22795215269 -1968.05722599014,-25.9512457026556 -1968.17403833339,-25.6772269815216 -1967.90708833721,-25.5960300944169 -1967.09762765522,-25.7889579064485 -1966.31619859954,-25.9638863473114 -1965.86175650481,-25.9750089558694 -1965.42491931859,-25.9775043676363 -1965.62096637231,-25.6618233567928 -1965.50444031931,-25.5063049936104 -1965.39547165359,-25.3482534797728 -1964.79350156881,-25.4390657635944 -1964.21338965228,-25.5179099640362 -1963.23433339194,-25.7941352135313 -1962.78244445799,-25.8054830371512 -1962.34805599562,-25.8065066709437 -1962.25992311039,-25.6360324181059 -1962.17852170799,-25.4635250714816 -1962.19915437707,-25.2415560024951 -1961.64599514824,-25.3087127901801 -1961.1132347772,-25.3651500303523 -1960.58568108445,-25.4179612003847 -1960.077797921,-25.4617502324213 -1959.58115780236,-25.4991582950819 -1958.99035032239,-25.5830040005021 -1958.42109719422,-25.6548909938585 -1958.16450348489,-25.569103613568 -1957.91961926775,-25.4785267714233 -1957.96675363697,-25.2435879369789 -1957.68428239018,-25.1752513448286 -1957.41419996088,-25.1017441179248 -1957.43952109985,-24.8814843119779 -1957.4680818677,-24.6609836675555 -1957.13627718214,-24.6234635044048 -1956.42148209881,-24.7779670276483 -1955.73174516472,-24.9178651205107 -1955.45520838924,-24.8504818739237 -1955.19080942181,-24.7770217724483 -1954.77470727224,-24.7805335754431 -1954.95700759323,-24.4848242243169 -1955.13784222538,-24.1917748591847 -1954.4370668833,-24.344195587278 -1953.76084000009,-24.4826503800112 -1952.97077557714,-24.6759647999398 -1951.80203599261,-25.057004126925 -1950.67180061799,-25.4148699297764 -1949.80137530926,-25.6391570842987 -1948.9607694501,-25.8460020566137 -1948.35808062992,-25.932448625356 -1947.84083592983,-25.9754460070592 -1947.34304612407,-26.0072517427162 -1946.70233132288,-26.1107183480993 -1946.08475070425,-26.2011949494421 -1945.62149534614,-26.213567822137 -1945.93944993081,-25.8344143097592 -1946.2522232802,-25.4626805660695 -1946.03727965856,-25.3587337697764 -1945.83276138021,-25.250944430773 -1945.60635427637,-25.1554068624751 -1945.2387182698,-25.1313561295756 -1944.88595939588,-25.0996179740292 -1944.56509742208,-25.05204645503 -1944.2577305456,-24.9988257038269 -1944.14435106078,-24.8491323924233 -1944.73622243137,-24.3469718613126 -1945.31453598979,-23.8578809088277 -1944.82741272547,-23.9054905287429 -1944.35847466853,-23.9438090381517 -1944.42258541364,-23.7157746918049 -1943.66463935181,-23.9005159357418 -1942.93286234361,-24.0699172293384 -1942.02141281571,-24.3287691173316 -1941.14072710469,-24.5686705265743 -1940.3574353214,-24.7574628110587 -1939.63441626654,-24.9137208863646 -1938.93674410705,-25.0559780460235 -1938.28182968716,-25.175971197342 -1937.65028864492,-25.2834165986346 -1937.20202171673,-25.297487176536 -1936.04850623285,-25.6657831720356 -1934.93314289644,-26.009160264331 -1934.03598614575,-26.2418423709773 -1933.16953566659,-26.4556710282372 -1932.94967344845,-26.3442301817164 -1932.5978005364,-26.299649846662 -1932.26058118008,-26.2482023516212 -1931.85676107684,-26.2314241296319 -1931.46909713468,-26.2054958790192 -1930.52790074813,-26.4573031940021 -1930.08150082787,-26.4590486561338 -1929.65257067247,-26.4526119300106 -1928.52396798336,-26.795830599434 -1927.43302249394,-27.1154618253375 -1926.7605381259,-27.222337342837 -1925.55330526101,-27.5963260131454 -1924.38622140851,-27.9465916119168 -1924.50481687732,-27.6494301870826 -1924.62447242221,-27.3570480077104 -1924.59952046632,-27.1385113326904 -1924.23514254949,-27.092215866904 -1923.88594146625,-27.0377032743795 -1922.96091400631,-27.2725667626209 -1922.06764370919,-27.4892875392099 -1922.17468785063,-27.2044689732522 -1922.46438496198,-26.8319775912884 -1922.74988079316,-26.4638253311033 -1921.83601665528,-26.6980439436358 -1920.95348435907,-26.9145117561846 -1920.13702659894,-27.0963881329638 -1919.12988904665,-27.3721296503919 -1918.15694268328,-27.6280933577588 -1917.60856568711,-27.6684808706211 -1917.08091443084,-27.6989069400531 -1917.98066231736,-27.0144062029204 -1918.63179163368,-26.4609256243556 -1919.26802579435,-25.9212002153698 -1919.40338002788,-25.6358386493654 -1919.53891048392,-25.3539296024481 -1919.92222247893,-24.9509658292848 -1920.68239580071,-24.3656265097512 -1921.42401055131,-23.7952699164171 -1920.85067882498,-23.8883444364507 -1920.29803888845,-23.9690307768097 -1919.70831235133,-24.0672522519341 -1919.21966679003,-24.1130567442294 -1918.74930081223,-24.1503726791996 -1918.58703580225,-24.0330001379849 -1918.43338859785,-23.9121993013141 -1917.71243433231,-24.0762450279485 -1916.65777689041,-24.4059861572576 -1915.63813624268,-24.7147581754529 -1915.68727101853,-24.4874548159917 -1915.73884703999,-24.2600621176049 -1915.20246246178,-24.329003724651 -1914.97084316691,-24.2437100308932 -1914.74994463284,-24.154298447445 -1914.04188864717,-24.3103587453561 -1913.35859665657,-24.4508703093749 -1913.05408467199,-24.4006130251795 -1912.0068738288,-24.7241474046776 -1910.99450706691,-25.025219866049 -1910.45401356237,-25.0878673809172 -1909.93350894287,-25.1388677012499 -1909.37086918983,-25.2131302614966 -1909.14323749536,-25.1183128099752 -1908.92635321483,-25.0191809677343 -1908.51437371021,-25.0184087315636 -1908.11856272829,-25.0093651781411 -1907.60595179228,-25.0585136329167 -1906.2899866206,-25.508913894721 -1905.01696553643,-25.9332904246621 -1905.00925766088,-25.7193745304848 -1905.00596257591,-25.5068214222305 -1903.74791144174,-25.9231506214019 -1902.80212716537,-26.1800322221893 -1901.88849082926,-26.4180525350823 -1901.41386155622,-26.4355216418463 -1900.95750677628,-26.4424161949699 -1900.80686555349,-26.2960457125676 -1901.15456951242,-25.9026738470335 -1901.49619898254,-25.5165080343111 -1901.0739720704,-25.5145258989218 -1900.66833873017,-25.5051609802638 -1900.15469392982,-25.5498074267512 -1899.9347180253,-25.4473513453046 -1899.72533613421,-25.3408283155301 -1899.31995149972,-25.3336900529857 -1898.9305991319,-25.3177466649004 -1898.48644188868,-25.3288787056014 -1897.55422647636,-25.5847118625296 -1896.65364711693,-25.8218515091659 -1896.52598344079,-25.6711870267207 -1896.40622058603,-25.5179909990058 -1896.16942673546,-25.424219618699 -1896.25218536032,-25.1717230163175 -1896.3365509507,-24.921676899683 -1896.41434093331,-24.6765773801575 -1896.49379056063,-24.4344988295314 -1896.81354841543,-24.0729014225049 -1896.55767172803,-24.0030076268402 -1896.31317101047,-23.9273034142697 -1895.49909508859,-24.1388417561355 -1894.71287413995,-24.3339577505821 -1894.22652481244,-24.3774068695456 -1893.23470194155,-24.6725685224001 -1892.27609659866,-24.9487631853584 -1892.22794027783,-24.7663276755852 -1892.18517780706,-24.5823177015432 -1891.56045623207,-24.6921287971256 -1891.22299827843,-24.65664933098 -1890.89945379066,-24.6152682702857 -1889.89206094874,-24.9151966775677 -1888.91840453514,-25.1959103977288 -1888.36779248075,-25.2620285495149 -1887.60261252894,-25.4355442562183 -1886.8641009787,-25.5944317799052 -1886.37865439041,-25.6242639783741 -1885.91166887457,-25.6445188294824 -1885.22142868444,-25.7765126833414 -1884.5143534546,-25.9155732567509 -1883.83233042781,-26.0413875547288 -1883.64679892414,-25.9161771480435 -1883.47094811428,-25.7876933082262 -1882.95436024809,-25.8311154315128 -1882.19600406624,-25.995351286573 -1881.46422704627,-26.1438565436222 -1880.4884404766,-26.412403412982 -1879.54575407725,-26.6625490797755 -1878.87768863187,-26.7725911618934 -1877.92482750498,-27.0251318371244 -1877.00447521547,-27.2590905660444 -1877.0642713938,-27.0000886967161 -1877.12669989727,-26.7424188933496 -1877.18544844798,-26.4886382104388 -1877.33995405767,-26.1889172698564 -1877.49416089285,-25.8931095137896 -1876.90161132512,-25.9730179639145 -1876.33076007383,-26.0419740445029 -1875.64179285335,-26.1698211464922 -1874.85690561092,-26.3444291631646 -1874.09943850174,-26.5034723075211 -1873.96224808511,-26.3494027707043 -1873.83339746345,-26.1940012583133 -1873.47878966045,-26.1532156642246 -1873.10558867967,-26.1207874508339 -1872.74764401374,-26.0827176934091 -1872.62853027132,-25.9239771387009 -1872.51713729625,-25.7641621649746 -1872.22829371025,-25.6933413077026 -1872.56600233622,-25.3114058122256 -1872.89780863056,-24.9350518472757 -1872.48495178192,-24.9344531304705 -1872.08829452226,-24.9256054776885 -1872.03226857467,-24.7479697039601 -1871.616659614,-24.7509931033934 -1871.21728855053,-24.7458047499296 -1870.79320882338,-24.7546344844762 -1870.38558755812,-24.7534071462045 -1869.70196277169,-24.8905574015653 -1869.69915793502,-24.6862738650667 -1869.70038854768,-24.4808500804724 -1869.56110417762,-24.3486501434934 -1869.42982146437,-24.213595818766 -1869.61604308268,-23.9216455958678 -1869.71689589878,-23.6757590928834 -1869.81851919024,-23.4319603962167 -1869.3575473102,-23.4703890027045 -1868.91391166439,-23.5002393033971 -1868.67840422389,-23.4255750476724 -1869.22207314775,-22.9619340196853 -1869.75333409042,-22.5095897414962 -1868.91877552216,-22.7448539974538 -1868.11241913763,-22.9631806748587 -1867.91531463625,-22.8747456093799 -1866.83022061581,-23.2311564934102 -1865.78082432464,-23.5669800837567 -1865.64815442966,-23.4410261920615 -1865.52310681569,-23.3124372906017 -1865.13011003034,-23.3188498182717 -1864.95641914649,-23.2163555311618 -1864.79150817825,-23.1101738412869 -1864.3749913477,-23.1308141308229 -1863.9744094892,-23.1427590135901 -1863.80432744587,-23.038863736403 -1864.46605113714,-22.5209413832318 -1865.11178098837,-22.0159074619106 -1864.01667348337,-22.3859987746191 -1862.95739345518,-22.7343433371862 -1862.09440513201,-22.9809055202838 -1861.63765085651,-23.0232887915347 -1861.19799145125,-23.0573573605198 -1860.75499794715,-23.0914953143278 -1860.32871819493,-23.116927613379 -1859.12517967722,-23.5301597224871 -1857.93868392993,-23.9314864294544 -1856.79099877201,-24.3085925778161 -1856.30923026568,-24.3484691880592 -1855.84558560309,-24.3797083741539 -1855.13102384405,-24.5365002991654 -1855.04411443188,-24.3784735978105 -1854.96364934059,-24.2186239598783 -1854.65707905394,-24.173309649967 -1854.3634001146,-24.1230480204467 -1853.97128073322,-24.1220827075972 -1853.63684694366,-24.0910398871802 -1853.31612278904,-24.0540526419621 -1852.35555831666,-24.3364332096488 -1851.42723133177,-24.6001757029421 -1850.41562852041,-24.9038875289211 -1849.54367705529,-25.1332211035505 -1848.7015079092,-25.346530471838 -1848.62622595373,-25.1736424304478 -1848.55721798003,-25.0001548318714 -1847.19076220386,-25.4767401373014 -1846.06953645588,-25.8249517122887 -1844.98558271564,-26.1520215414478 -1845.09686119171,-25.8783211025822 -1845.20903582093,-25.6074532108237 -1845.23528453457,-25.38170399711 -1845.5260549327,-25.0253659155502 -1845.81227156855,-24.6745654567759 -1844.78805210846,-24.9824782929729 -1843.79807541986,-25.2710361353508 -1843.85702678289,-25.0321313649198 -1843.75396249717,-24.8766434870181 -1843.6579271781,-24.719220348067 -1843.07698007109,-24.8059908565039 -1842.517144489,-24.8804686699691 -1842.02895932599,-24.9189157397586 -1841.4291267809,-25.0134596806611 -1840.85099688453,-25.0957138329529 -1840.77345107173,-24.9260358840061 -1840.70220632188,-24.7544938342442 -1840.058432767,-24.8731337036815 -1838.93094059581,-25.2305308759169 -1837.8407896297,-25.5652562742513 -1837.37132093899,-25.586968694311 -1836.9198428567,-25.6004390054989 -1835.80214402924,-25.9462748270453 -1834.80963721326,-26.2262758013454 -1833.85066606732,-26.4871685136456 -1833.0499398106,-26.6655232733894 -1832.27718273695,-26.8280300443431 -1832.19410276531,-26.6450485110543 -1832.18612008035,-26.425428386292 -1832.18267057257,-26.2062955717085 -1831.99601469084,-26.0798847593735 -1831.81910665646,-25.9517762941779 -1831.27769250918,-26.0061143572449 -1830.53288262004,-26.1613798386305 -1829.81429311665,-26.3021501953189 -1829.63131146237,-26.1731638016789 -1829.45798308113,-26.0404511183295 -1828.99510660848,-26.0543930561764 -1829.15412066477,-25.7560598175999 -1829.3126325049,-25.4622271725299 -1828.83192927773,-25.4912051550638 -1828.36951755065,-25.5106418995211 -1828.30755327144,-25.3293616899628 -1828.62264892574,-24.9613696903796 -1828.93246096579,-24.600924450275 -1828.41702206318,-24.6547948554978 -1827.92075831588,-24.7002917443305 -1827.74021934295,-24.5867940047648 -1827.46219232587,-24.5239468012746 -1827.19627438538,-24.4558200752164 -1826.81030424257,-24.4465462158821 -1826.43964616295,-24.4311958587454 -1826.11624141618,-24.3919176489262 -1825.5615107774,-24.4683500224535 -1825.02706237346,-24.5348842871676 -1824.62499545546,-24.5332941518665 -1824.23872410503,-24.5247164822275 -1823.95638595334,-24.4630088082575 -1823.88708255859,-24.2954795248632 -1823.8237157539,-24.1276936505401 -1823.24021019432,-24.2212057736156 -1822.67778693085,-24.302779804837 -1822.64288051158,-24.1191629284088 -1822.44603760055,-24.0198107656808 -1822.25882201584,-23.917572609138 -1822.41266970892,-23.6455881378051 -1822.56571144584,-23.3767841049766 -1822.07840505312,-23.4297448344014 -1821.75664854756,-23.4000267074203 -1821.44807914659,-23.3627883461873 -1820.88993971211,-23.4504991599215 -1820.35199944681,-23.5272995889571 -1820.01484468303,-23.5035653967303 -1819.77516431456,-23.4306494170069 -1819.54628293325,-23.3545627622547 -1819.42233643886,-23.2244341370507 -1819.30575040249,-23.0934751341458 -1817.89512987109,-23.6114513564829 -1816.33032093758,-24.2005332934123 -1814.8155483561,-24.759046365285 -1814.03878098721,-24.9438250207479 -1813.288919935,-25.1138242271377 -1813.37691415958,-24.8631809532671 -1813.53281637442,-24.5805380145796 -1813.68803688646,-24.3010194417776 -1813.18144226171,-24.3537914176695 -1812.69369711602,-24.3972180072223 -1812.02275696257,-24.5315207335698 -1811.36223570388,-24.6604806573124 -1810.72513536283,-24.7757040234327 -1809.89835474269,-24.9842867011463 -1809.09998404145,-25.1765648162794 -1808.37351349555,-25.3318028742474 -1807.27781752299,-25.6698388163717 -1806.21858807066,-25.985356562421 -1805.97090068307,-25.8915783466212 -1805.7347271218,-25.7937198784497 -1805.51647964848,-25.6891013667291 -1806.04118899681,-25.2133042979647 -1806.55446735545,-24.7478166637282 -1805.79091127859,-24.9265865718938 -1805.05385896761,-25.0902453187834 -1804.78435046495,-25.0178702202226 -1803.85640634541,-25.2756560022851 -1802.95989328044,-25.5145803224198 -1802.13225706957,-25.7170583027073 -1801.33318163191,-25.9029873066575 -1800.89923802751,-25.9040578529463 -1800.72149615243,-25.7766781245273 -1800.55317122571,-25.6455134478616 -1799.83306634053,-25.7923369067506 -1799.13837538009,-25.9247836826589 -1799.52825004251,-25.5144909736013 -1800.45923808769,-24.8378747991063 -1801.36672388793,-24.1783479848266 -1801.29009430082,-24.0186130275543 -1801.21953878897,-23.8575484584845 -1800.83808467463,-23.8540526694053 -1800.36794275499,-23.8942462306301 -1799.91546271107,-23.9238032187752 -1799.66055547176,-23.8550649779003 -1799.41696398539,-23.7817253082139 -1798.98525108219,-23.8025334645374 -1797.75304681324,-24.223641336407 -1796.56106525021,-24.6201879158317 -1795.82585256767,-24.7851876611736 -1795.11629691349,-24.9358853662394 -1794.863132615,-24.8558413173476 -1794.34855701586,-24.9082463680201 -1793.85315087992,-24.9501647766788 -1794.32825191311,-24.5068735534542 -1794.79324246882,-24.0734110207458 -1794.42254346293,-24.0617092931948 -1794.45128267699,-23.8503075707514 -1794.48295728231,-23.6404222824633 -1794.0197714267,-23.6790851343786 -1793.5740041139,-23.70817076694 -1792.87973923839,-23.8625044490053 -1792.84090976922,-23.6863001173479 -1792.80698870793,-23.5095811423226 -1792.24810427116,-23.5970266468106 -1791.70945331318,-23.6731963659059 -1790.70341807121,-23.9836193327452 -1790.55833608202,-23.8600739501551 -1790.42131676963,-23.7342527169213 -1790.39835744673,-23.5516888312211 -1790.37980646846,-23.369281204013 -1789.2068970228,-23.7654723340937 -1788.29529171552,-24.0285597272886 -1787.41437494457,-24.2717927535037 -1787.05773641486,-24.2507801607516 -1786.71548542732,-24.2226446195413 -1786.15861004241,-24.3024153764143 -1786.11515990112,-24.1240305570851 -1786.0768412437,-23.945108160863 -1786.26455905026,-23.6560212040446 -1786.45047149418,-23.369821445205 -1785.77330941969,-23.5181482262812 -1785.21540712441,-23.6042038852717 -1784.67772650521,-23.6795394822241 -1784.7283938618,-23.4620241776236 -1784.7812542863,-23.2443568827106 -1784.11205835555,-23.3905966378297 -1783.72154413762,-23.3952790297705 -1783.34625197517,-23.3925069789766 -1781.92575053284,-23.9124266112478 -1780.55095616643,-24.4040051890913 -1780.56171290584,-24.1979581001092 -1780.488470782,-24.0356033508523 -1780.42122025265,-23.8730953200394 -1780.017168657,-23.8794901769427 -1779.62883700993,-23.8781805507008 -1779.62002023728,-23.6862621103358 -1779.30059767995,-23.6526469394276 -1778.9943455981,-23.6130982628466 -1778.49434518301,-23.6706341621962 -1778.01284414594,-23.7174215239951 -1777.28374082495,-23.8895000680548 -1776.84288514557,-23.9154233104718 -1776.41881724637,-23.9316519563959 -1776.33455172868,-23.7775830684517 -1776.25655081241,-23.6224918265047 -1775.7407313631,-23.6881677935602 -1775.50962412093,-23.6115730744635 -1775.28905040424,-23.5297427464016 -1775.28104808918,-23.3426448724703 -1775.27695477987,-23.1555471704944 -1774.30796073794,-23.4513936080691 -1773.59032555995,-23.6188511090119 -1772.89761097001,-23.7710829500646 -1772.24768509069,-23.9017829759966 -1771.62073124757,-24.0205217497746 -1771.73023723849,-23.7691431924271 -1772.27518229295,-23.3022812941449 -1772.80773122084,-22.8467941244137 -1771.81354229701,-23.1588768834701 -1770.85233852132,-23.4509965797194 -1770.51805589448,-23.4269845014979 -1769.98717623606,-23.5024463206323 -1769.47566226743,-23.5658474181949 -1768.32914369639,-23.9480828331779 -1767.22023506731,-24.3074443122568 -1766.11568341453,-24.6601856144018 -1765.02974219621,-24.9995423065146 -1763.97985963571,-25.3182472515022 -1763.00760490813,-25.5954472488182 -1762.06814559084,-25.8524008417195 -1761.23627679915,-26.053689146033 -1760.1225139746,-26.3945150632583 -1759.04587245849,-26.7128565368666 -1758.39493675469,-26.8149785693847 -1757.76756183127,-26.9049222924052 -1757.38751616492,-26.8704009285556 -1757.06254615469,-26.8085545640826 -1756.75150662015,-26.7404128373153 -1756.01744821374,-26.8837748890754 -1755.30941736225,-27.0128665244189 -1754.88081445708,-27.0005292857729 -1754.63158664275,-26.8985509707258 -1754.39409062623,-26.7917300092262 -1754.29182856834,-26.6183130864167 -1754.19690854278,-26.4427366912814 -1753.84388973973,-26.3988045121094 -1753.73936998523,-26.2313111272479 -1753.64216696162,-26.0623290911225 -1753.65457049855,-25.8388659997108 -1753.67078171621,-25.6173543764801 -1753.4699396503,-25.5063705249208 -1752.51663940227,-25.7719050177794 -1751.5956155229,-26.0183723193104 -1751.39236174494,-25.9037764548426 -1751.19927958281,-25.7852325899132 -1750.89125462371,-25.7247279531951 -1750.75255791944,-25.5803603934598 -1750.62207364028,-25.4337756662614 -1749.70260896657,-25.6832933323057 -1748.81440174752,-25.9140322104678 -1748.75814679833,-25.727051252175 -1748.97437025097,-25.4041331504241 -1749.18832072943,-25.0879596925681 -1748.46948257563,-25.2398928147585 -1747.77591049185,-25.3793763260219 -1747.3653690062,-25.3740023381636 -1747.11248873054,-25.2908102055502 -1746.87112247386,-25.2024769596611 -1746.5506309126,-25.1530589441005 -1746.24365540671,-25.0990986543053 -1746.28911151989,-24.8689404786389 -1746.20875888036,-24.7037527093543 -1746.13473107683,-24.5368602838879 -1745.20393472386,-24.8006807246983 -1744.3045653005,-25.0472628423724 -1743.8262562192,-25.0785118778281 -1744.00182144741,-24.7839878384484 -1744.17616229251,-24.4921281501993 -1743.64473945991,-24.5569950271128 -1743.13290720521,-24.6110006458063 -1742.47773761159,-24.7355980202889 -1742.15776303236,-24.6913903873532 -1741.85118411599,-24.6422723274492 -1741.79288783215,-24.4688787473927 -1741.74020923758,-24.2944920421639 -1741.08435672786,-24.4226432993466 -1740.53628850408,-24.496832081523 -1740.00828439479,-24.5592930379507 -1739.81908890034,-24.4510441765851 -1739.6393918348,-24.3395834489522 -1739.34283212721,-24.2884050843925 -1739.45919504129,-24.0308624478751 -1739.57594426299,-23.7758396083579 -1739.14037234428,-23.7990249674659 -1738.72143364056,-23.813675124375 -1737.83476093219,-24.0624534140966 -1737.73800464985,-23.9139714708137 -1737.64789537319,-23.7624897333573 -1737.21150392064,-23.7879949840124 -1736.79173323835,-23.8031829834738 -1736.77742519772,-23.6160638264722 -1736.6155942507,-23.5035250603451 -1736.46227120483,-23.3896927310056 -1735.99099600355,-23.4346797809373 -1735.53733500316,-23.4706496669363 -1734.72918084616,-23.6833282536424 -1734.00523532111,-23.8512979905336 -1733.3064479693,-24.0063362752878 -1732.08509906532,-24.4209096637142 -1730.90367279461,-24.8116257274498 -1730.48439367064,-24.8161635042434 -1729.84440912103,-24.9326091624414 -1729.22728071796,-25.035115635119 -1729.14725981958,-24.8678176457711 -1729.07359129922,-24.6993646663689 -1728.68337125333,-24.691905396939 -1728.68133221438,-24.4895559068037 -1728.68326143365,-24.2868290499819 -1728.60326626914,-24.1282237529731 -1728.52945543659,-23.9679708449007 -1726.96837938084,-24.5530273246016 -1726.09892840266,-24.7855434813255 -1725.25910054374,-25.0004708473012 -1724.94282883774,-24.9510155673578 -1724.639908443,-24.8966738731123 -1724.81571131728,-24.6028841511025 -1725.3119993155,-24.1522110678486 -1725.79748794538,-23.7114805181279 -1724.94786408792,-23.9433114097287 -1724.12709909781,-24.1586296476513 -1723.94288078849,-24.0534656711709 -1723.76942770232,-23.9427488897969 -1723.60490320954,-23.8312080188303 -1723.1698112687,-23.8541213217689 -1722.75133895073,-23.8686017633649 -1722.56712955673,-23.7646845218458 -1722.25449096811,-23.7267310183073 -1721.95484022064,-23.6829062766772 -1721.53117051033,-23.7014810335315 -1721.12375592676,-23.7115938621866 -1720.17373676873,-23.9928184545297 -1719.81493903187,-23.9743464433982 -1719.47056468018,-23.9495644151597 -1718.66855883371,-24.1546997160294 -1717.89405773336,-24.3442534341869 -1716.88955249551,-24.6455035884683 -1716.24652555021,-24.7635905442152 -1715.62644250471,-24.8693146840894 -1714.87218667213,-25.0409635508138 -1714.1442067801,-25.1994581753923 -1713.7801753833,-25.1737055191831 -1713.38911671688,-25.1606753777527 -1713.01364181425,-25.1398620150887 -1712.12379351522,-25.377685644383 -1711.26426612544,-25.5967777050477 -1710.85129575919,-25.5903363757474 -1711.08804207609,-25.259565627078 -1711.32186161384,-24.9329242939732 -1711.15632286424,-24.8099824591003 -1710.99963730173,-24.6835474116492 -1710.49890390335,-24.7323163946243 -1709.97004045415,-24.7931401024101 -1709.46074492238,-24.8429657646371 -1708.33802112256,-25.1990973907899 -1707.25247587884,-25.5332094765313 -1706.33546675221,-25.7800871129489 -1704.90380747611,-26.2820520899865 -1703.51863778679,-26.7561857740501 -1703.27908868482,-26.6517728490899 -1703.05093866211,-26.5427186908003 -1702.75278225991,-26.4705519035058 -1702.58396731526,-26.3340409626408 -1702.4243947583,-26.1933861321107 -1702.75855163698,-25.8083772804141 -1703.08700450476,-25.4310661924609 -1702.64895679926,-25.4394390414368 -1702.93882085189,-25.0841886013666 -1703.22414578007,-24.7331789230561 -1703.09300756479,-24.5962531637095 -1702.96964240671,-24.457123703208 -1702.9195173625,-24.2807951510301 -1702.32704509622,-24.3783192692789 -1701.7559296162,-24.4632917019009 -1701.19500574533,-24.5431887707589 -1700.65454036853,-24.6122227306775 -1700.59685170846,-24.4381483585234 -1700.35945707691,-24.3571840520317 -1700.132926464,-24.2713202948942 -1699.53597517096,-24.3704486988106 -1698.96052545884,-24.4576348941983 -1698.35371121346,-24.5610195541735 -1697.65861697588,-24.707528929973 -1696.98796203288,-24.8400833830994 -1696.31922175548,-24.96996877886 -1695.6742068791,-25.0870156826054 -1695.81509488577,-24.8091081642821 -1695.67727883704,-24.6743884933564 -1695.54745529107,-24.5360348045521 -1694.77313123602,-24.7221913091086 -1694.02559121904,-24.8925366616184 -1693.62911354764,-24.8852745894539 -1694.03758522452,-24.4753197844405 -1694.43791836968,-24.0736602809832 -1693.26657671085,-24.4624321254922 -1692.13369270254,-24.8279887349241 -1691.46801384392,-24.9571004966133 -1690.88482110347,-25.0426639885972 -1690.32285113284,-25.1162308917809 -1689.70620603868,-25.216323990701 -1689.11181618041,-25.3049862337629 -1688.3886398811,-25.4571899477262 -1688.55211224973,-25.1641627269741 -1688.71480563274,-24.8744567922797 -1688.32798871286,-24.8634353841675 -1687.9565506388,-24.8451900253151 -1687.5631379262,-24.837587752065 -1687.04296018609,-24.8928456503839 -1686.54211674893,-24.9382759664708 -1685.60560357342,-25.2012976903866 -1684.70075683168,-25.4459560275208 -1684.24842587125,-25.4607376008966 -1684.61959553071,-25.0632294042323 -1684.98385009602,-24.6745842602021 -1684.74397342187,-24.5908778401393 -1684.51511077897,-24.5029770202986 -1683.91177873099,-24.6037550790724 -1683.39005141362,-24.6634460991292 -1682.88763397201,-24.7113656988855 -1681.84062422125,-25.0312962503491 -1680.82851991743,-25.331177466955 -1681.34822902916,-24.8624277980883 -1682.14547540355,-24.2587366491761 -1682.92306222044,-23.6712542634665 -1682.09357928578,-23.8933093301259 -1681.29235334481,-24.0983586679213 -1680.59290395602,-24.2510667336526 -1679.25283300924,-24.7224703848082 -1677.95624773851,-25.1685848167077 -1677.26017849312,-25.3082089855178 -1676.58871907707,-25.4343393037658 -1675.36371718069,-25.8362673236585 -1674.64565085586,-25.9807541771736 -1673.95296342372,-26.1117985087272 -1673.66961126532,-26.0361875279831 -1673.39882224808,-25.9544346242735 -1672.74519740174,-26.0648923967452 -1672.14914286029,-26.1460753659457 -1671.57489957411,-26.215841853749 -1671.75482514336,-25.907367871397 -1671.93362342022,-25.6021426636068 -1672.0351294516,-25.3387769753687 -1671.41803504299,-25.4374630985132 -1670.82324052402,-25.5249900985712 -1670.48042116051,-25.4859872721102 -1670.15179318751,-25.440315353775 -1669.45769056448,-25.5772371440139 -1669.03551184632,-25.5764653756184 -1668.62990155222,-25.5676370411114 -1668.08560784776,-25.6285385141496 -1667.56148558548,-25.6787186049699 -1667.42268318078,-25.5356607324209 -1667.38652799845,-25.3415223162845 -1667.35552098323,-25.1472015779988 -1667.03867211826,-25.0977012977132 -1666.73519805961,-25.0418985015444 -1666.1638722268,-25.1210427313156 -1665.32703889568,-25.3328415190155 -1664.51894784934,-25.528054244531 -1663.62196549061,-25.7649826664804 -1662.75560096918,-25.9837833734244 -1662.49468035377,-25.8984009446473 -1662.75669051554,-25.5524831361829 -1663.01507436771,-25.2118676163487 -1662.65396472259,-25.1849344117916 -1662.30753170101,-25.149670019119 -1661.60906928587,-25.2902644039778 -1661.27101283322,-25.2493095354735 -1660.94699852779,-25.2020621843558 -1660.78974384195,-25.0721687451759 -1660.64115110638,-24.9390288429775 -1659.32315236317,-25.3935492279063 -1657.73775867263,-25.9761612170043 -1656.20333278604,-26.527281087184 -1656.14011923696,-26.3367754891363 -1656.08304500388,-26.14496505659 -1655.57776514641,-26.1810270064624 -1654.86551357642,-26.3186554206664 -1654.17854469346,-26.4425901251298 -1653.99215613296,-26.3143065367083 -1653.81554092505,-26.183632672924 -1653.1524911862,-26.2975286866064 -1652.90365439133,-26.2028869214154 -1652.66639308474,-26.1017681642125 -1653.11383543022,-25.6598808985472 -1653.552224815,-25.2274259529244 -1652.7071650738,-25.4406816160823 -1651.45109535237,-25.8571716808059 -1650.23627283422,-26.2495353584563 -1650.26400504554,-26.016822994702 -1650.29512163367,-25.7844567925636 -1650.47328490518,-25.4803311005315 -1650.19293400524,-25.4088297423199 -1649.92494959767,-25.3324655116261 -1648.99022610994,-25.5909969987303 -1648.08718516595,-25.8303109402814 -1647.20086393021,-26.0580479642097 -1646.11850036942,-26.3822553631274 -1645.07234629259,-26.685537425914 -1644.36965425829,-26.8147402400147 -1643.69203198704,-26.9287862730934 -1643.67822178862,-26.7105014631558 -1643.81250170757,-26.4192829759513 -1643.94711251826,-26.1315873833652 -1643.65017050042,-26.0622379545295 -1643.36620416032,-25.9868189101361 -1643.31102957677,-25.7983506736726 -1643.36076274145,-25.5598329066366 -1643.4131291828,-25.3220239715444 -1642.92626434253,-25.3559588756929 -1642.45783734748,-25.3809849471638 -1642.26002677034,-25.2691327182087 -1642.022376394,-25.179978624764 -1641.79575743737,-25.08395698851 -1641.26563202093,-25.1409842745931 -1640.75519695482,-25.1879529258527 -1640.67662439412,-25.0177624434961 -1640.48776226985,-24.9060273013301 -1640.30845249476,-24.790647526613 -1640.02061897974,-24.7308423378467 -1639.74522059857,-24.6654986363867 -1638.82927541552,-24.918794323426 -1638.64581462835,-24.806148668875 -1638.47171190057,-24.6885392686769 -1637.84339064562,-24.7988420639684 -1637.23758626039,-24.8980976442688 -1636.50673801057,-25.0595885670836 -1635.88759402311,-25.1623010763052 -1635.29075291888,-25.2523152963058 -1634.88903874194,-25.2439069250813 -1634.50323731947,-25.228679651976 -1634.2366728366,-25.1543263670622 -1633.55422236893,-25.2873207329794 -1632.89597513639,-25.4072412932177 -1632.17782978909,-25.5557755426386 -1631.48498865898,-25.6897527180621 -1630.83368776841,-25.8023928196497 -1630.52472346292,-25.7418404488779 -1630.22903718558,-25.6759079434598 -1630.20907118487,-25.4729844456247 -1630.19378738713,-25.2702353452285 -1629.9870365336,-25.1647332573903 -1629.91648212976,-24.9930792034332 -1629.85199262871,-24.81966712796 -1629.23164673438,-24.9256762138141 -1628.63358750359,-25.0186893679167 -1627.64174864933,-25.308552988301 -1626.80434748627,-25.5170753184355 -1625.99577383239,-25.7098506901781 -1624.95906223945,-26.0142017185734 -1623.95715167653,-26.2990135377135 -1623.74119375445,-26.1880039613489 -1623.44545637264,-26.1178879425698 -1623.16266216553,-26.0421195231757 -1622.68357424994,-26.0649748286825 -1622.22283215034,-26.0789226938478 -1621.41215893786,-26.2673714975503 -1620.36046550769,-26.5742485677769 -1619.34411200425,-26.8601797777129 -1618.96817845227,-26.822179109368 -1618.60771543823,-26.7767139751945 -1618.24600300202,-26.7337697291646 -1617.44353799699,-26.9107121380189 -1616.66913749068,-27.0730380040905 -1616.18948156908,-27.0852810369099 -1615.72839765828,-27.0881436447189 -1615.3815198988,-27.0337062095117 -1615.05042898681,-26.9733493793775 -1614.73347992798,-26.9062114975004 -1614.45452575412,-26.8205859633638 -1614.18815471449,-26.7286482486643 -1613.38940517951,-26.9038016025805 -1612.96676676037,-26.8892313429729 -1612.5609799392,-26.8670487712872 -1612.49342948101,-26.6761612228684 -1612.43219572817,-26.4836401803274 -1611.91893334761,-26.5194621448004 -1611.67185943103,-26.4221142040587 -1611.43634388177,-26.3192853030977 -1611.06893580672,-26.283682703145 -1610.71661790552,-26.2405766081414 -1610.08747429675,-26.336699595131 -1609.12324988414,-26.5982597488633 -1608.19180654593,-26.8418460120497 -1607.82569523686,-26.8004981839451 -1607.47473365472,-26.7512760097052 -1607.02700511675,-26.7521576504103 -1606.62049634621,-26.7310117903363 -1606.23033308683,-26.701519401902 -1606.19693025934,-26.494497848175 -1606.16881523917,-26.2873492446556 -1605.28115768672,-26.5114249472246 -1604.72138063757,-26.5681889404364 -1604.1824616363,-26.6154463279585 -1603.46529679465,-26.7505375276488 -1602.77365604363,-26.8713994445924 -1603.07165381409,-26.4958581480708 -1603.18884606206,-26.2163147240084 -1603.30681486229,-25.9395803182313 -1602.44487759951,-26.1548665493614 -1601.61259993065,-26.3529559078803 -1600.92882457138,-26.4754565077899 -1600.24398986366,-26.5961328183221 -1599.58368857825,-26.7040161205693 -1599.0569222441,-26.7442143244662 -1598.55003793525,-26.7738199785604 -1597.96791047814,-26.8405087668771 -1596.61600163538,-27.291363638439 -1595.3084374929,-27.7168289612915 -1595.21817792786,-27.5286607238615 -1595.13507323669,-27.3384619816871 -1595.19050235805,-27.0812574147163 -1596.08017145608,-26.4098430024888 -1596.94785846577,-25.756091185126 -1596.5722078012,-25.7296860264494 -1596.21179376557,-25.6963293590191 -1595.77025440297,-25.7032975379532 -1595.18256147179,-25.7844078076432 -1594.61635333478,-25.852909758046 -1594.05882187032,-25.9168145107664 -1593.52192318912,-25.9695201013276 -1593.54610167805,-25.7412110623692 -1593.00026469206,-25.7997259473169 -1592.4747055204,-25.8487263881774 -1591.78654784954,-25.9776826355457 -1591.12289478848,-26.0932315260742 -1590.63455274386,-26.1200432545141 -1590.16518428834,-26.1376072972429 -1589.71388222542,-26.1459390623514 -1589.61299626698,-25.9793243202614 -1589.51926767476,-25.8096877007299 -1589.33641690345,-25.6850189290002 -1588.6808579332,-25.7989618307799 -1588.04881387377,-25.9004460170622 -1587.69223441963,-25.8643795783809 -1587.35032946301,-25.8202298289254 -1587.73158702553,-25.4152580521669 -1588.13787698784,-25.0023312474465 -1588.53617107265,-24.5975354910643 -1588.39077977826,-24.4691801569733 -1588.25355571556,-24.3375500469642 -1588.55067957744,-23.9891079347235 -1589.33167822439,-23.4028833533428 -1590.09331875184,-22.8317896128441 -1589.63608466905,-22.8758531597952 -1589.19593198185,-22.9114192464766 -1588.59125071433,-23.0286000027461 -1587.9094334296,-23.1828915748505 -1587.25138531006,-23.3234173285608 -1586.31193287989,-23.6044765709287 -1585.40391552604,-23.8667248367173 -1584.98833024344,-23.8803392934674 -1584.41758655485,-23.9699912995764 -1583.86749894568,-24.0484296240775 -1583.58873284236,-23.9916663605846 -1583.32198788736,-23.9279069899513 -1582.6703818178,-24.0583112193925 -1582.19568877045,-24.0988285646093 -1581.73882982642,-24.1293002792834 -1581.28594603001,-24.1585940434645 -1580.85025686803,-24.1792697827147 -1580.06954014117,-24.3722883787147 -1579.44819798946,-24.48190111856 -1578.84911231738,-24.580678797425 -1578.54777869178,-24.5290326262016 -1578.25925275622,-24.4713605071998 -1577.99636615246,-24.4017968176702 -1577.74410200456,-24.3268791796717 -1577.50316871628,-24.2483196458984 -1577.59546693577,-24.0025353336984 -1577.688869092,-23.7595407135509 -1576.71055106855,-24.0541978997143 -1575.4499192141,-24.4874129457085 -1574.23039205988,-24.895970777047 -1573.85980467759,-24.8770879274834 -1573.50411084613,-24.8501255611174 -1572.99323605512,-24.9011355970325 -1572.74816726845,-24.8187298843938 -1572.5142911012,-24.7323072057812 -1572.67472267755,-24.4482604046214 -1572.83432193153,-24.1673227734126 -1572.18130653809,-24.2950104019815 -1571.70778383018,-24.3323560196586 -1571.25211028395,-24.3619070974076 -1570.65977525186,-24.4570994965094 -1570.08883643094,-24.5406075549148 -1570.23729207361,-24.2643132598592 -1569.41115052574,-24.4773383134247 -1568.613308475,-24.6749630330876 -1568.32161667559,-24.6169447703942 -1568.04247695583,-24.5540968070231 -1567.34239942632,-24.7015896022321 -1566.52021803108,-24.9098238778326 -1565.72627291434,-25.1003442726394 -1565.18439689166,-25.1634156219132 -1564.66255581813,-25.2150306254171 -1563.95298426552,-25.3612574143221 -1562.65632263509,-25.799607927364 -1561.40207974742,-26.2117201852021 -1560.99010627876,-26.1996433590429 -1560.59451832288,-26.1780557375244 -1560.20173215743,-26.1560875118194 -1560.34700673222,-25.8649047378087 -1560.49218041291,-25.5780674642471 -1559.96838047163,-25.6288586116924 -1559.46414269171,-25.6676851657209 -1558.89829884379,-25.7369508073355 -1558.16603560692,-25.8893442125853 -1557.45955599181,-26.027440228219 -1557.03032836391,-26.0240652926443 -1556.61799556921,-26.0132618638667 -1556.55194812998,-25.8285981341693 -1556.60287179945,-25.5880333908401 -1556.65642140028,-25.3485565753644 -1557.17930232225,-24.8776247959476 -1557.69073045655,-24.4162738091676 -1557.00361618159,-24.5597053947996 -1556.50896780484,-24.6058527951076 -1556.03282779225,-24.6424610523123 -1556.2695282998,-24.3221761931146 -1556.50310232961,-24.005963706869 -1556.12217313884,-23.9996530717648 -1555.83478737741,-23.9473160080725 -1555.55967568743,-23.8885927501218 -1555.00187543969,-23.9715031512231 -1554.46435330541,-24.0441222552237 -1553.90500962525,-24.1265371004728 -1553.213084222,-24.2741133067919 -1552.54545336359,-24.4082113647665 -1551.92163414165,-24.5200104068695 -1551.32012651351,-24.619206633227 -1549.93294854566,-25.1090332641487 -1548.71287151465,-25.5104702647384 -1547.53291967308,-25.8894303170464 -1546.92862152286,-25.9768638412413 -1546.34633774972,-26.0508161248406 -1546.00957734064,-26.0010865029237 -1546.2079782178,-25.6844063801623 -1546.40468507477,-25.3727940992544 -1546.25131256785,-25.2397386639697 -1546.10651055155,-25.1041022868496 -1545.26568330255,-25.3170164436848 -1544.5110231869,-25.4846140340493 -1543.78273271222,-25.6371286892994 -1543.67407385489,-25.4783082748518 -1543.57272736428,-25.317544589691 -1543.28200963827,-25.2534563089944 -1542.85857840985,-25.2551664587883 -1542.45171702428,-25.2498236179228 -1541.21189111335,-25.6602564534689 -1540.01279188169,-26.047133552321 -1539.4392373741,-26.1174426961263 -1539.5164531156,-25.8608945615483 -1539.59557101208,-25.6076553864725 -1539.50370511584,-25.4403723440654 -1539.41865575184,-25.2718057046778 -1539.23025433958,-25.1562408093896 -1539.66455857439,-24.7303381168762 -1540.09001783637,-24.3150364449998 -1539.48538435581,-24.4174394234718 -1538.90249075054,-24.509183053122 -1538.3833716837,-24.5677963711033 -1538.66415107905,-24.2249313979601 -1538.94050956197,-23.8883043873969 -1538.97315193819,-23.6764813954002 -1539.00858475802,-23.4643057914748 -1537.21313023524,-24.1713053556146 -1535.60638310899,-24.7760729811871 -1534.05101531487,-25.3504594144045 -1534.79979514699,-24.7668430017188 -1535.53043003873,-24.196722233093 -1536.04826689605,-23.7400012057962 -1536.755802165,-23.1924258493628 -1537.44611713181,-22.6594087076819 -1537.68498433201,-22.3573070476765 -1537.92029069387,-22.0581562993328 -1537.54326176002,-22.0692222917634 -1537.20540563501,-22.0606119618701 -1536.88096227615,-22.0454834882161 -1536.25181074679,-22.1827328717377 -1535.64469084186,-22.3086151156252 -1534.45717511511,-22.7231036307652 -1533.55902719213,-22.9885964369912 -1532.69099392059,-23.2362980090358 -1532.25440617295,-23.2652095520252 -1531.83438143765,-23.284824463032 -1531.34090433948,-23.342041248631 -1531.10082292677,-23.272717974356 -1530.87148718941,-23.1978657680064 -1530.43553315534,-23.2274895523227 -1530.01610359947,-23.2476530064212 -1530.29836683936,-22.9183634363147 -1530.76498850988,-22.5007159162649 -1531.22133941375,-22.0901559381429 -1530.37347728332,-22.3376500322271 -1529.55410396207,-22.5676952005339 -1529.11041132008,-22.6071502867338 -1527.96128977464,-22.9988851043659 -1526.84969769494,-23.3689412287649 -1526.2041995356,-23.5013344373268 -1525.58146726605,-23.6225211999345 -1525.13945183232,-23.6512784489809 -1524.01315242655,-24.0222654654679 -1522.92388631787,-24.3709678074324 -1522.48792261062,-24.3877711739739 -1522.06873011544,-24.3973975131493 -1521.49521115519,-24.4835353256356 -1520.35974849889,-24.8511517058521 -1519.26174319948,-25.1960614403721 -1518.77361881894,-25.2309583627134 -1518.30396318415,-25.257268721145 -1517.80864310885,-25.2968698158609 -1517.67876836263,-25.154273994386 -1517.55672608788,-25.0083301888216 -1517.62212932901,-24.7695415964186 -1517.68955662847,-24.5310360954748 -1517.81041924944,-24.2688181154261 -1517.09428903333,-24.4273037989961 -1516.40319279649,-24.5719201627216 -1515.69041725639,-24.726977388828 -1515.00261003955,-24.8675876929121 -1514.23581878545,-25.046063817029 -1513.05014600161,-25.4317766975355 -1511.90355157101,-25.794911482542 -1511.8284898679,-25.618731961128 -1511.75975675892,-25.4407205446131 -1511.63251364307,-25.2935157608221 -1512.03043562067,-24.885325870029 -1512.42059880517,-24.4847420261163 -1512.06896769968,-24.4588671197667 -1511.7316212289,-24.4270147242215 -1511.16699289192,-24.5080554323204 -1510.99140804455,-24.3949294460782 -1510.82488167157,-24.2776050634746 -1510.77736572098,-24.1021330000794 -1510.73508470338,-23.9264899265754 -1510.65608057433,-23.770086459209 -1510.69082897596,-23.5585295493045 -1510.72828013114,-23.347232818979 -1509.57746463186,-23.7325545449677 -1508.4643682508,-24.0947064061384 -1508.03845008902,-24.1100937454222 -1507.91876753171,-23.9722519451215 -1507.80642645863,-23.8332707486256 -1506.64581652852,-24.2188976574849 -1505.52330389115,-24.5810453109476 -1504.60850953969,-24.8354339566661 -1504.1516893926,-24.8576260496949 -1503.71235468824,-24.8717644363195 -1502.9588668836,-25.0437646407883 -1502.23161815397,-25.2006774786282 -1501.61692765646,-25.2983311779492 -1500.18748760692,-25.8030679992416 -1498.80439686525,-26.2803818370896 -1498.30421839178,-26.3118327481619 -1497.82304752194,-26.3331342832922 -1497.56736029121,-26.2421909841054 -1497.14795106097,-26.2334437110928 -1496.74515491909,-26.2160100552784 -1496.762716169,-25.9890695975344 -1496.78394968651,-25.7617561786324 -1497.57854697786,-25.1500391522507 -1498.19557416186,-24.6337585634983 -1498.79832850449,-24.1298778824518 -1498.30408432515,-24.1799245647691 -1497.82825773361,-24.219840877971 -1497.40565576543,-24.2329089455626 -1497.7356314578,-23.8692876320911 -1498.05965610457,-23.5123301021701 -1497.44971804499,-23.6251349798467 -1496.86152797199,-23.7256843370809 -1496.59340836877,-23.6663080562627 -1496.46773667192,-23.5357569412791 -1496.34950119661,-23.4034664707873 -1495.70954139427,-23.5321200894447 -1495.0922021824,-23.6497255154622 -1494.84641851748,-23.5798445345544 -1494.29655162768,-23.6630104633043 -1493.76664687485,-23.7343301408075 -1493.45065574427,-23.6993308080402 -1493.14772714099,-23.6581237343167 -1492.4770993142,-23.8005373895204 -1491.72352506293,-23.983739574999 -1490.99597802119,-24.1516530062928 -1490.6771718063,-24.113645744428 -1490.37159629771,-24.0687744514464 -1489.73433409088,-24.1918358872237 -1488.99533111675,-24.3630434833313 -1488.28201449916,-24.5190278787083 -1488.62484012122,-24.1454629693713 -1488.96140192712,-23.7780967345034 -1488.1609014224,-23.9842687137123 -1487.47328082481,-24.1303373771744 -1486.80981494962,-24.2619889061053 -1486.73601555096,-24.1001220078896 -1486.66822022304,-23.937153999806 -1486.04167425089,-24.0551053054155 -1485.55591735384,-24.1011869132004 -1485.08832145099,-24.1374962475885 -1484.81673591443,-24.0746259717287 -1484.55700732787,-24.0062132152031 -1483.96281165039,-24.1070724243164 -1482.70853618785,-24.5358686635242 -1481.49520110283,-24.9404856619809 -1480.55642166397,-25.20427213129 -1479.64938282368,-25.4487415783497 -1478.91900209065,-25.6032856753045 -1477.75262005197,-25.9738886137774 -1476.62485032759,-26.32129985385 -1475.66885122991,-26.579439724482 -1474.74537641617,-26.819329208056 -1474.43833796259,-26.7478500677945 -1474.58991741489,-26.4481290890508 -1474.7413128278,-26.1506830106926 -1474.70326915085,-25.9513303277206 -1474.67054788505,-25.7515479354626 -1473.97782646443,-25.8836307520934 -1472.940051634,-26.1874545007075 -1471.93712965515,-26.4701476843199 -1471.81028625565,-26.3118182670801 -1471.6914588024,-26.151890140386 -1471.27972487639,-26.1404612129787 -1471.22096768443,-25.9496671696566 -1471.16818061777,-25.7595271665638 -1470.83599882465,-25.7116398555733 -1470.51776204624,-25.6567071365166 -1470.1266088477,-25.6383869400573 -1470.10357880199,-25.4361704009253 -1470.08533751542,-25.2346848643616 -1469.4865257298,-25.3252144625061 -1468.9094537078,-25.4037154598175 -1468.13540859547,-25.5781983615205 -1467.50207130739,-25.6818902578325 -1466.89157460103,-25.7733074182292 -1465.94027202726,-26.0334469042514 -1465.02127116289,-26.2753952297893 -1464.09766616909,-26.5171716076343 -1463.43076528168,-26.6273518668103 -1462.78789632295,-26.7253558849938 -1463.02203922045,-26.3842167362068 -1463.25355665579,-26.0463789847589 -1462.52346049148,-26.1932723528597 -1462.37408644933,-26.0488043189084 -1462.23334542056,-25.9021307380391 -1461.67925024707,-25.9629091644044 -1461.14571319503,-26.0135400628782 -1460.5729630696,-26.0829883102503 -1460.03789178735,-26.1338045836449 -1459.52282413204,-26.1730997912836 -1458.95895916626,-26.2365881547641 -1458.41598332109,-26.2889318703122 -1458.18548332672,-26.1858768537878 -1458.14395341869,-25.987282034032 -1458.1078680537,-25.7887302782003 -1457.41029682663,-25.9221879847866 -1456.73751281499,-26.0418962707417 -1456.26241320285,-26.0621102848209 -1456.61329677327,-25.6685304213382 -1456.95798517941,-25.2822665334942 -1456.34751733897,-25.3773169945055 -1455.75915942314,-25.46233918491 -1454.7381655341,-25.76200188295 -1453.86569952683,-25.9827973422442 -1453.02320008047,-26.1890217403569 -1452.49089783517,-26.2367482980884 -1451.97855001444,-26.2732570935893 -1452.37519224859,-25.8547745165265 -1453.0564245565,-25.2980720767774 -1453.72164328351,-24.7562461207997 -1453.76520291992,-24.529138722122 -1453.81141863717,-24.3041002597107 -1453.23489144091,-24.3927616217621 -1452.76429363422,-24.4272525240018 -1452.31148515971,-24.4527179763664 -1451.6384801316,-24.5880424899589 -1450.98926320804,-24.7090841850655 -1450.44489886278,-24.7771621454299 -1449.79782501745,-24.8963840245049 -1449.17383194208,-25.0021552808778 -1448.60697775685,-25.0784857599273 -1448.06088312773,-25.1434115309978 -1447.3603630578,-25.2849415651198 -1446.31771896056,-25.5962560556411 -1445.30997469784,-25.8877318876823 -1444.91520326117,-25.8690755923868 -1444.53626927676,-25.8424153760318 -1443.68523626292,-26.0529947033403 -1443.00284367026,-26.1748742848648 -1442.34486562295,-26.2854063113162 -1441.83398444091,-26.3211405108707 -1441.34244820804,-26.3456385462009 -1441.05547911206,-26.2689455938875 -1440.681588856,-26.2355515819417 -1440.32300049981,-26.1950300680273 -1439.20853127849,-26.5320790358467 -1438.13128364049,-26.8475186965293 -1437.98087988882,-26.695838644215 -1437.62256361215,-26.6507625704575 -1437.27916306104,-26.5989816822225 -1437.23186400844,-26.3997805931545 -1437.19024735654,-26.199728942977 -1436.85231048763,-26.1503762362401 -1436.33263591707,-26.1926022020878 -1435.83252633924,-26.2230729636012 -1436.11861434315,-25.8609531490174 -1436.40044328172,-25.5041315158935 -1435.95898413119,-25.5128759970702 -1434.70847929926,-25.9268538215549 -1433.49905174645,-26.315553731735 -1433.22923755296,-26.2294080901129 -1432.97165811006,-26.1390652923895 -1432.62419197946,-26.0944115837526 -1432.06549312318,-26.1564407574445 -1431.52750886426,-26.2069577473133 -1431.36097521751,-26.0715555466687 -1431.20357320361,-25.9319043137097 -1430.70284932867,-25.9664191120999 -1430.29754253236,-25.9505274669932 -1429.90843315394,-25.9288332798085 -1429.57122389818,-25.880660758251 -1429.24816226409,-25.8257858664707 -1428.63660557231,-25.9153088166325 -1427.48924716373,-26.2720914291586 -1426.38002072307,-26.6065188257835 -1426.1129383706,-26.5165450695818 -1425.85805721375,-26.4218539451954 -1425.87684767868,-26.190993113192 -1425.856465975,-25.9824222782417 -1425.84089129208,-25.7725805911163 -1425.31212953391,-25.8227693236052 -1424.80313606544,-25.8615231391563 -1424.28496349127,-25.9051745332955 -1423.49598330892,-26.0838185090649 -1422.73450618948,-26.2471591516033 -1422.62438443361,-26.0829851001902 -1422.52173527901,-25.9171395187075 -1422.10676925261,-25.9077167595711 -1422.0500688331,-25.7205618685812 -1421.99918796378,-25.5311706138131 -1422.01964075453,-25.308687148882 -1422.04356679111,-25.086409986191 -1422.07689068256,-24.8616799070805 -1422.22334808974,-24.5815723143627 -1422.36944540557,-24.3055747072326 -1422.0373175957,-24.2714376921734 -1421.71886846091,-24.2307791783278 -1421.24873767479,-24.2661446698618 -1421.06634245612,-24.1573506799601 -1420.89318950318,-24.0452721743775 -1421.07468441278,-23.7559889390948 -1421.2546217307,-23.4716399547818 -1421.11244606085,-23.3515357567343 -1421.3498031407,-23.0408930168978 -1421.58382271761,-22.7364433170294 -1421.43879592057,-22.6254248392287 -1421.30158892174,-22.5107510400765 -1420.95358005095,-22.5017718959951 -1420.7524138203,-22.4213470069573 -1420.56068073023,-22.3349586831968 -1419.88890451409,-22.4898999601328 -1419.24049126904,-22.6330066610677 -1418.49151461928,-22.8251368152289 -1417.65894149919,-23.0546160752283 -1416.85460387688,-23.2692280597477 -1416.92731330821,-23.0431883874488 -1417.00151534201,-22.8182716197909 -1416.28258667078,-22.9913977359416 -1415.66040755837,-23.1156437457147 -1415.06023655274,-23.2273303358838 -1414.80863681193,-23.1640474123192 -1414.56811830902,-23.0955633914062 -1413.83039706614,-23.2761220746896 -1413.10083690939,-23.4501506001361 -1412.39653865066,-23.6099230657673 -1412.16733576609,-23.5303690973632 -1411.94864860165,-23.4480211098613 -1411.06693917917,-23.6970587149342 -1409.89315138659,-24.0901481556524 -1408.75783419116,-24.4591976226254 -1408.2493598575,-24.512091203744 -1407.7598063694,-24.5541461441253 -1407.12068371425,-24.6709425120278 -1406.26353383574,-24.8949596057728 -1405.43568806767,-25.102502116559 -1405.73032952331,-24.7469125157072 -1406.02025105016,-24.3976041334665 -1405.14435300125,-24.6338048843793 -1404.64473646111,-24.6806394961213 -1404.16380988111,-24.7177876473929 -1403.53078344045,-24.8299648320057 -1402.92042234158,-24.9304763772593 -1402.9871588845,-24.6908832076948 -1402.97730305665,-24.4912458826362 -1402.97166986625,-24.291014960616 -1402.67892942497,-24.2379457463808 -1402.39868708056,-24.1791433750785 -1402.29932140815,-24.0294152978751 -1401.72441840842,-24.1197591471167 -1401.17032128003,-24.1977546585218 -1400.18430792442,-24.4914132455243 -1399.2313131888,-24.7648169239708 -1397.98831579722,-25.181049684313 -1396.71081592211,-25.6111962467457 -1395.47514110435,-26.016418575165 -1394.74193396118,-26.1657164098742 -1394.03460693413,-26.3003697726968 -1393.35663728337,-26.4178968637944 -1392.83652991692,-26.4574882199117 -1392.33605513925,-26.4866031473775 -1392.41406218378,-26.2255689929153 -1392.49402655883,-25.9666816490721 -1392.82048400912,-25.5863690660176 -1393.24356129191,-25.1616156216307 -1393.65821172606,-24.74721519252 -1393.4137964101,-24.6652055340249 -1393.18054048054,-24.5784538790813 -1392.36463847148,-24.78232494431 -1390.65163094812,-25.4344328231041 -1388.99325953769,-26.0532916933663 -1388.87992203537,-25.8931982685716 -1388.77410481097,-25.7309796949813 -1387.72847231008,-26.0395550821311 -1386.7320356512,-26.318951448847 -1385.7693003692,-26.5805678013651 -1385.85192400671,-26.3165736423102 -1385.93638083735,-26.055360011704 -1385.68298838572,-25.9646384988141 -1385.46378245519,-25.8570430923337 -1385.25523910373,-25.7461586485916 -1385.14209872787,-25.5882185967481 -1385.03642952183,-25.4275106798366 -1384.95923497013,-25.2549783031763 -1385.43273677802,-24.8082501960541 -1385.8962568564,-24.3710764036917 -1385.51041870806,-24.3636258214332 -1385.1398524117,-24.3480448297728 -1385.09512816459,-24.1715849668574 -1384.86646482216,-24.0876965917869 -1384.64837933354,-23.9988541242785 -1384.5113030209,-23.8710059972624 -1384.3820581638,-23.739539688184 -1383.97790270085,-23.7468547433775 -1383.64219204244,-23.7198065809003 -1383.32016432432,-23.6864737234432 -1383.0448144095,-23.6295885318319 -1382.78135403747,-23.5681587112164 -1382.03648333914,-23.7467408991156 -1380.67077440023,-24.2343790741171 -1379.34924444163,-24.6954142891331 -1379.24718406898,-24.5419986078011 -1379.1520734807,-24.3867236332038 -1378.93691917713,-24.292453643962 -1378.97839125832,-24.0702324300312 -1379.02250738127,-23.8513228215045 -1378.93936471765,-23.6965323814498 -1378.86245649363,-23.5420358869401 -1378.78297864469,-23.3883024515911 -1378.8464791375,-23.1659333089453 -1378.91176278237,-22.94354053308 -1378.36799762287,-23.0279687555421 -1377.84393109599,-23.1029731484665 -1377.46935055137,-23.1036552550141 -1376.89421675653,-23.203316317662 -1376.33971884477,-23.2916708327944 -1376.03983363155,-23.2517551677379 -1375.75247390517,-23.2055993112458 -1375.7769674275,-23.0043057429522 -1375.66851847822,-22.8709706694305 -1375.56688394393,-22.735230816744 -1375.48037107409,-22.5932531454413 -1375.39997858175,-22.4501175870297 -1374.91431655692,-22.5106783135507 -1374.09610043812,-22.7362612674043 -1373.30563175088,-22.9465441002671 -1372.63755941104,-23.0937735232689 -1371.99285300304,-23.2276709578912 -1372.14108311788,-22.9626792557807 -1372.48959143168,-22.6002050320073 -1372.83139999501,-22.245172781886 -1372.34565658306,-22.3077552549658 -1371.87775655923,-22.3616292829408 -1371.22709704351,-22.5050206760593 -1370.52631910248,-22.6733957848531 -1369.84978314602,-22.8274771177515 -1369.80781234997,-22.662342497558 -1369.77066041959,-22.4969238296926 -1369.3758963914,-22.5118818337565 -1369.04927295111,-22.491382631101 -1368.73585029851,-22.4648734675238 -1368.57892131899,-22.361110036471 -1368.43013940976,-22.2549295489375 -1367.48290155004,-22.5488321237882 -1366.93029140984,-22.6415378692807 -1366.39756765401,-22.7237482047575 -1366.37936694984,-22.5474257204294 -1366.36526807171,-22.3715340635996 -1366.13614814497,-22.3053416521551 -1365.99630508595,-22.1946655476831 -1365.8640719922,-22.0817748126621 -1364.85116320072,-22.4100894444207 -1363.87166165345,-22.7183131013718 -1362.89153284935,-23.023151341128 -1362.07894485465,-23.2413511169571 -1361.2940254869,-23.4435980128227 -1360.32758256652,-23.7359564727746 -1359.39341589392,-24.0082770467578 -1358.9365459185,-24.0392391158191 -1358.5860086875,-24.0162925007572 -1358.249656931,-23.9869801417992 -1358.03889116783,-23.8954046940618 -1357.83814920908,-23.799443097945 -1357.11145724899,-23.9675078319361 -1356.13588139186,-24.2574692217556 -1355.19298594585,-24.5294917561821 -1354.29460893568,-24.7761081455237 -1353.42671828492,-25.0045568862368 -1353.52500443752,-24.7479007130753 -1353.64720075309,-24.4821848634798 -1353.7697117039,-24.2185454099058 -1353.29734666817,-24.2548562097146 -1352.84280528673,-24.2825517659098 -1353.30301419909,-23.8518007313119 -1353.28911461143,-23.6621156494666 -1353.27940497639,-23.4722160557467 -1352.68459951123,-23.577799968336 -1352.11108744147,-23.6711198150539 -1351.44012357923,-23.812476917042 -1350.85697894846,-23.9080376207168 -1350.29486309669,-23.9926320039627 -1349.70166879279,-24.0910884471582 -1349.12984167083,-24.1792590958477 -1348.4231261579,-24.3332292887229 -1347.78030432243,-24.4534870410457 -1347.16037663081,-24.5610329248429 -1347.19602038362,-24.3398285836678 -1347.23451716645,-24.1186338686217 -1346.205006941,-24.4341098186625 -1345.10356798585,-24.7827245076198 -1344.03861745372,-25.1094550454649 -1343.87250877758,-24.9821325914624 -1343.71535981242,-24.8529091392489 -1343.34380618867,-24.8318083102919 -1343.1421187029,-24.7271021597278 -1342.95035138,-24.6188841319555 -1342.31747560006,-24.7316499071021 -1341.70724794428,-24.8317287982304 -1340.65503534091,-25.151800080591 -1339.28221988589,-25.6289999163993 -1337.95406263816,-26.0794557543273 -1336.88670225944,-26.395866941173 -1335.85511290157,-26.6905391518838 -1335.10209210703,-26.8417593669655 -1334.49510227957,-26.9179271600567 -1333.9104488497,-26.9838250779423 -1333.84628493919,-26.7883855067295 -1333.78839241852,-26.59170675898 -1333.28648021368,-26.6202685535759 -1332.583439974,-26.7475415797257 -1331.90552023291,-26.8615706674229 -1331.60722551667,-26.7847725558623 -1331.32210264978,-26.701107663794 -1331.05810074066,-26.6079395655008 -1330.94643138454,-26.440590932665 -1330.8423563131,-26.2707860256133 -1330.53447101013,-26.2063551339855 -1330.2398959566,-26.1334350599967 -1329.76162763167,-26.1534155978375 -1329.12362256443,-26.2523091526262 -1328.50873330612,-26.3399395883807 -1328.71996294697,-26.013558911516 -1328.92918195675,-25.6915131008891 -1328.26147741885,-25.8108721979918 -1327.39727651164,-26.0274122917757 -1326.5627998617,-26.2265143218556 -1326.20574755686,-26.1857059232336 -1325.86347941055,-26.1370314408366 -1325.2705221274,-26.2136732078297 -1325.05611207453,-26.1009809684678 -1324.85227449448,-25.9839347313982 -1324.62677931848,-25.8796646842481 -1324.41212942292,-25.7702744880688 -1324.13105173216,-25.6966946691697 -1323.50372320983,-25.7955986258533 -1322.89909167008,-25.8822134261198 -1322.48851153065,-25.8710735733216 -1322.09424426698,-25.8513253864544 -1322.0517479464,-25.6568164730886 -1321.39167145582,-25.7722002683805 -1320.75525931974,-25.8751650815787 -1320.34688867753,-25.8641007173308 -1319.9547428263,-25.8431724335925 -1319.89308444772,-25.6580905849115 -1319.91107658786,-25.4342719312066 -1319.93266411246,-25.2117079648687 -1319.72205865323,-25.1075992573832 -1319.52171154955,-24.9995903818152 -1319.07488032096,-25.0164782134889 -1318.06671262761,-25.3118421356663 -1317.09239945469,-25.58773960557 -1317.99574467937,-24.9231007465241 -1318.87644137819,-24.2759125955405 -1318.59763484819,-24.2149140963645 -1318.47347512129,-24.0766805490684 -1318.35683995582,-23.9372151387114 -1317.983001082,-23.92734818999 -1317.62401000199,-23.9117499960433 -1317.35560601994,-23.850200098435 -1317.23430647271,-23.7153276613565 -1317.12035475306,-23.5787509893161 -1316.11399246117,-23.8882470914644 -1315.14114233889,-24.1778721357225 -1314.76839372436,-24.1656010933292 -1314.10076207803,-24.3003154033419 -1313.45671957192,-24.4210269779542 -1312.86777094505,-24.5140429889688 -1312.30012756972,-24.5930451543561 -1311.64810878093,-24.7152020377267 -1310.48389098287,-25.0933052454263 -1309.35805651572,-25.4482173958601 -1308.8240126745,-25.5029112418957 -1308.30985766365,-25.5470912264635 -1308.07611801652,-25.4506072165756 -1307.93146798116,-25.3115365559786 -1307.79516201639,-25.1688059349585 -1307.49131692476,-25.1113178478431 -1307.20049025464,-25.0472908801968 -1306.95126068509,-24.9641576390272 -1306.88990274,-24.7884856661755 -1306.83432631284,-24.6111517724241 -1306.66205301465,-24.4942233422042 -1306.49878141228,-24.3731371588318 -1306.56348670602,-24.1398053456623 -1306.95965932151,-23.7424679937059 -1307.34793319603,-23.353174425472 -1306.82018375626,-23.4258082425344 -1306.31173161297,-23.4879327168808 -1306.28545706932,-23.3093012858737 -1306.30799669137,-23.1083364007931 -1306.333514238,-22.9073471741646 -1306.27730930692,-22.7494929433008 -1306.22634146229,-22.5895569566853 -1305.24807632763,-22.894521069607 -1303.64203538028,-23.5110754358486 -1302.08711958418,-24.0959886642354 -1301.5905657697,-24.1457547653049 -1301.1125254952,-24.1856398512989 -1300.63899149263,-24.22191611034 -1300.42636590328,-24.127068606835 -1300.22389991716,-24.0296840834864 -1300.11979707553,-23.8840580747602 -1300.02257441852,-23.7362749225424 -1299.68884481773,-23.7075368770938 -1299.16320623519,-23.7753310215113 -1298.65687518077,-23.8320330293511 -1298.06553698977,-23.9316320507186 -1297.4954712471,-24.0202819011997 -1296.80219755057,-24.1698333209424 -1295.93956488708,-24.4018958608625 -1295.10629671391,-24.6166938076159 -1294.83184990722,-24.5505816690976 -1294.5694345357,-24.4787772096767 -1294.28190126919,-24.4209746365312 -1293.73771125356,-24.4900631380771 -1293.21353129417,-24.5491183747056 -1292.42160926993,-24.7422768793945 -1291.65702674968,-24.9198881175963 -1291.21135614298,-24.9353523426916 -1290.78957099437,-24.9402455788724 -1290.3842299804,-24.9358999230036 -1290.2537585944,-24.7933580590705 -1290.13114203724,-24.6489968646629 -1289.40114630009,-24.8098518267856 -1288.76161306794,-24.9241435679373 -1288.14495967545,-25.0257163253229 -1287.51801176978,-25.1303429139551 -1286.91363595778,-25.223119074928 -1286.70411010711,-25.1178697582905 -1286.66005972019,-24.9305512324593 -1286.62133602107,-24.7429133934306 -1286.70838366189,-24.4942612432099 -1286.79679622202,-24.2479483531262 -1286.60626495019,-24.1424414787717 -1286.61186209181,-23.9418181583565 -1286.62109490787,-23.7412400541453 -1285.93141694373,-23.8911634244359 -1285.26590029988,-24.0274814041639 -1284.9083365567,-24.0097417535736 -1284.53820513166,-23.9971715650636 -1284.18282807655,-23.9780013249078 -1283.52340251834,-24.109974327275 -1282.88729701671,-24.2302516211441 -1282.56509197016,-24.1920448428465 -1281.39446161883,-24.5761021134034 -1280.26235162202,-24.9387138317558 -1279.52953767087,-25.0983689208197 -1278.82238939587,-25.2413462233472 -1278.70374398889,-25.0899721167661 -1278.392420952,-25.0379713455367 -1278.09430410309,-24.9799976266082 -1278.05576942919,-24.7920749577701 -1278.02235678151,-24.6026991499373 -1277.35290841903,-24.7332984421049 -1276.86887983007,-24.7704688465267 -1276.40311570442,-24.7971871896572 -1275.86277628481,-24.861683674982 -1275.34238417914,-24.9158700373738 -1274.67938239748,-25.040905545806 -1274.30489109495,-25.019333661908 -1273.94549808762,-24.9909267660075 -1273.55749552418,-24.976340747383 -1273.18498679239,-24.9546060204682 -1273.05753929785,-24.8112966668575 -1272.51614677319,-24.87626356542 -1271.99473381526,-24.9314961464718 -1272.23578134665,-24.6041735796866 -1272.47366718904,-24.2811628333705 -1272.5855958865,-24.0239970314751 -1272.957956281,-23.6406247887759 -1273.32308325903,-23.2630665276388 -1273.18569520846,-23.1410923859963 -1273.0560379633,-23.0161779466622 -1272.37796956832,-23.1668069046486 -1271.38905336223,-23.4713000728641 -1270.43306140151,-23.7569524875328 -1269.49492462923,-24.0303192509402 -1268.58831916358,-24.2847384061605 -1268.31195657562,-24.2220311190227 -1267.93825821871,-24.2086890247081 -1267.57946892365,-24.1890321735015 -1267.61504625531,-23.9718873179075 -1267.6534012151,-23.7549923809615 -1266.27943421484,-24.2461511508517 -1264.79208288585,-24.791519683011 -1263.35257079049,-25.3058052054506 -1262.84356210627,-25.3501600494788 -1262.35365929813,-25.3829088876316 -1262.11697539356,-25.2899618670955 -1261.91031202289,-25.1833941530847 -1261.71379969057,-25.072021125736 -1261.02894680567,-25.20550658276 -1260.36838191778,-25.3250036516009 -1260.29061457334,-25.1522916638265 -1260.81577882808,-24.6802859361779 -1261.32942140263,-24.2195783431385 -1261.15494392361,-24.1078689370221 -1260.98945427844,-23.9913075301118 -1259.86143478788,-24.3584818884775 -1259.25874670636,-24.4587970326105 -1258.67776234061,-24.5462785924587 -1258.11488710993,-24.6240519667371 -1257.57258769449,-24.6907789498757 -1257.13387139923,-24.7059579201456 -1256.35119970053,-24.891034845616 -1255.59566009532,-25.0620657568954 -1254.77596944382,-25.2637280751994 -1253.98454369439,-25.448262380784 -1253.73369282662,-25.3609576915348 -1253.92821692568,-25.0520798731019 -1254.12104908519,-24.7475054271655 -1253.82695729126,-24.689094636812 -1253.54551922331,-24.6269758482504 -1252.53104840371,-24.9293125076734 -1251.15517146113,-25.4098110470963 -1249.82400937928,-25.8638294268929 -1250.3659602023,-25.3760529842967 -1250.89603419206,-24.8997742603076 -1251.44386523758,-24.4186121930495 -1251.35630146162,-24.2609172450605 -1251.27520128917,-24.1015221630671 -1251.20524933033,-23.9381028380182 -1251.14118041556,-23.7734036403875 -1250.80154208645,-23.7462441649813 -1250.11771155394,-23.8930643779412 -1249.45787269406,-24.0255488682554 -1249.24107717325,-23.9352866617271 -1249.0345166482,-23.8411631941559 -1249.17915475295,-23.5731093711386 -1249.04853644679,-23.4450152675636 -1248.92550110488,-23.3154648775552 -1248.38891581397,-23.3924906919799 -1247.8718898768,-23.4573582901839 -1247.32780892807,-23.5372431289123 -1246.687688312,-23.6637840704951 -1246.07023518868,-23.7780476580302 -1246.34107307601,-23.4469557441208 -1246.60765362788,-23.121847427934 -1246.20323435494,-23.1357664489355 -1245.99383316953,-23.0520072165304 -1245.79425208871,-22.9643622036379 -1244.81588117879,-23.2655356206402 -1243.87008482568,-23.546849291676 -1244.07534332836,-23.2495104720595 -1244.7693219061,-22.7130638920929 -1245.44639789013,-22.1894107291116 -1245.03140483373,-22.2166167173798 -1244.63216083714,-22.2370122479443 -1244.08912916349,-22.3277704648735 -1244.05257120746,-22.1663935182926 -1244.02054767335,-22.002049293627 -1243.02345494652,-22.3234557493894 -1242.05928206341,-22.6236664947602 -1241.64485399537,-22.6468595172851 -1240.84069945172,-22.8654800723309 -1240.06387477447,-23.0664777446524 -1239.69640905913,-23.0608977409766 -1239.34345886945,-23.0487257532011 -1238.96664455079,-23.0490768476551 -1238.44805803929,-23.1192228699733 -1237.94845735155,-23.1788146605455 -1237.40092375878,-23.2631332259369 -1236.87323866574,-23.3356467683011 -1236.14655374221,-23.50732094439 -1235.17886920452,-23.7974972437443 -1234.24355153029,-24.0702706943373 -1233.18771972392,-24.3988132790572 -1232.16697378946,-24.7071743356618 -1231.28371309525,-24.943610307859 -1230.59765260913,-25.0795253821861 -1229.93588078292,-25.2013843661548 -1229.65685272612,-25.1306405786869 -1229.39012473578,-25.0547412357211 -1229.22914283419,-24.9275391985525 -1229.4330821225,-24.6196659689367 -1229.63494099845,-24.3166143638796 -1229.01170134084,-24.4278542824159 -1228.41076129635,-24.5269282790912 -1227.89292688489,-24.5826202152021 -1228.10670923971,-24.2721888091605 -1228.31807439373,-23.965621434677 -1227.73905349195,-24.0575519028097 -1227.18096943598,-24.1384557360112 -1226.91898734661,-24.0707311845464 -1226.77767408842,-23.9432335893247 -1226.64435168033,-23.8134500086748 -1226.41371347544,-23.7324560294792 -1226.19367494044,-23.6481748185601 -1226.32421476806,-23.3893489541057 -1226.47689312804,-23.1212942179427 -1226.62873586831,-22.8568393240391 -1226.94183157366,-22.5136051579259 -1227.24924634097,-22.175996951431 -1226.72806758952,-22.2575768625621 -1226.85598922457,-22.0132495562606 -1226.98359000754,-21.7708186270306 -1226.74654872424,-21.7133420372222 -1226.51990626952,-21.6509642098041 -1226.19617738761,-21.6388870803422 -1226.13127365735,-21.4977686933012 -1226.07162650011,-21.3554152395246 -1225.38500985665,-21.5278994205951 -1224.72200097529,-21.6852028600069 -1224.22352378627,-21.7612505596643 -1223.78064821058,-21.8073873613323 -1223.35425119531,-21.8447180261012 -1222.56448135604,-22.0642925815802 -1221.80145902816,-22.2675257919708 -1221.2136456912,-22.3811679791839 -1220.63125551893,-22.4904159806335 -1220.06960153102,-22.5875548620105 -1218.82368035267,-23.0263045739959 -1217.61818071708,-23.440184731994 -1217.49663690748,-23.3083026794746 -1217.67514345227,-23.0278107020953 -1217.85204064785,-22.7515688662033 -1217.3017502465,-22.8402170950203 -1216.77133324119,-22.9179648497974 -1216.47464851962,-22.8792417985254 -1215.60305141451,-23.1277824627313 -1214.76085365439,-23.3590275602428 -1214.16330088914,-23.4664742662373 -1213.58711344564,-23.5624053916394 -1213.74172997321,-23.2917129765975 -1213.84685348992,-23.0484460800171 -1213.95252969033,-22.8067212495944 -1213.25427012878,-22.9696568538369 -1212.58025833079,-23.1183212614283 -1212.36876211591,-23.0348504552321 -1212.33246710399,-22.8650035065515 -1212.30085896187,-22.69285836801 -1211.33649420848,-22.9916073058989 -1210.40420141994,-23.2700527233314 -1208.8853781204,-23.8393245150464 -1207.53325453507,-24.3185186314266 -1206.22493950875,-24.7713505211943 -1206.32202599758,-24.5168884150901 -1206.42019542625,-24.2650504921096 -1206.19837733514,-24.1746774923584 -1205.81828624035,-24.1649112186761 -1205.45328615389,-24.1473017380434 -1204.7292472691,-24.3098384031878 -1204.030474619,-24.4572406275163 -1203.1407888069,-24.6996976944279 -1202.50612137063,-24.8120789128797 -1201.89417969878,-24.9114172607088 -1202.13139171334,-24.5857964932918 -1202.36555972777,-24.2638888656667 -1202.42982690791,-24.0320965078286 -1202.8082981892,-23.6438028859069 -1203.17939101489,-23.2637583874068 -1202.629792288,-23.3475157863371 -1202.10013381786,-23.4205010136648 -1201.24492613923,-23.6562204607297 -1200.40297028826,-23.8829430987181 -1199.58967080191,-24.0919092823808 -1199.24385454736,-24.0653634869409 -1198.91210781935,-24.0314409721858 -1198.92218662326,-23.828142708092 -1199.35478510119,-23.4165566745728 -1199.77833038283,-23.0132263276156 -1199.25918290688,-23.0852821250063 -1198.75900655221,-23.1474324017773 -1198.13540248471,-23.2701128953823 -1198.11893166946,-23.0878348185796 -1198.10660929292,-22.9055622503002 -1197.18626412048,-23.1781339918808 -1196.29676792443,-23.433436128349 -1196.0928285697,-23.3433034637938 -1196.03180735478,-23.1820129155519 -1195.97627810402,-23.0203949347611 -1195.57514051442,-23.0316102626467 -1195.18951598625,-23.0368516662021 -1194.89233946161,-22.996430833627 -1194.74628819051,-22.8818864744158 -1194.6081646398,-22.7627463339782 -1194.00849957071,-22.8770420643017 -1193.43015103713,-22.9797185045932 -1192.57403234448,-23.2195461870413 -1191.73805524447,-23.4470711539674 -1190.93048466535,-23.6588951679356 -1190.46964056528,-23.6936662455104 -1190.02619797154,-23.7200684038278 -1189.69473672235,-23.689559694513 -1188.99021538041,-23.8471257346004 -1188.3102905064,-23.9902663456182 -1188.00207051828,-23.9453948016689 -1187.70679805403,-23.89497876373 -1187.51092642763,-23.7959301003708 -1187.05937109283,-23.8261181951823 -1186.6249411183,-23.8462321479137 -1185.47564816994,-24.2242994306341 -1184.36415404065,-24.5800703892761 -1183.26534099824,-24.9260518810498 -1182.11363011895,-25.2943275405915 -1181.00000101949,-25.6394814737203 -1180.62191652511,-25.6140018304172 -1180.25914630541,-25.5808472279395 -1179.54874187848,-25.7218040943222 -1178.40662955544,-26.0775536143808 -1177.30246335342,-26.4112635739304 -1176.9904628908,-26.3448146415185 -1176.69197281098,-26.2734607543552 -1176.44469021553,-26.1759460454359 -1176.41124820831,-25.9738533794398 -1176.38300083211,-25.7716175498155 -1175.9338842291,-25.780161911444 -1175.50221326556,-25.7806895316447 -1174.66150587169,-25.9849801361041 -1174.19254694583,-26.0011070479623 -1173.74166597057,-26.0088908886822 -1173.82816466933,-25.7470608403501 -1173.91630303525,-25.486396273571 -1173.95310089365,-25.2557271709113 -1174.32383958354,-24.8606504345041 -1174.68763335512,-24.4727225076779 -1174.81858625839,-24.2047035953678 -1174.949554707,-23.9376259650303 -1174.82062868785,-23.8057057153811 -1174.71745477727,-23.6610320284725 -1174.62110632836,-23.5143191921048 -1173.58853140281,-23.8373049599842 -1172.59023722742,-24.1399246720944 -1172.0285444235,-24.2221010614689 -1171.52767247057,-24.2725853025235 -1171.04546957187,-24.3144746420744 -1170.24431574244,-24.5144664114338 -1169.4707320887,-24.6982119827402 -1169.11623223064,-24.6708271168089 -1168.63355473264,-24.7072762571953 -1168.16910258144,-24.7353773497584 -1167.64470784129,-24.7925414585193 -1167.13977612296,-24.8391149104101 -1166.71959098826,-24.8432073733505 -1166.26558558947,-24.8638431333845 -1165.82898517355,-24.875787289234 -1165.28306222569,-24.9417264200024 -1164.75727779989,-24.9963170426405 -1164.35733121003,-24.9888879570066 -1163.96412162041,-24.9787970328358 -1163.58652365268,-24.9594663041434 -1163.28671787488,-24.9034081525398 -1162.99974466008,-24.8397618425254 -1163.22087086337,-24.5221839017072 -1163.67101949855,-24.0937779161831 -1164.11175000601,-23.6744289159549 -1163.63044944656,-23.7205489312156 -1163.16713441064,-23.7567883490542 -1162.71704132513,-23.7864996150799 -1162.61491288956,-23.6424493847588 -1162.51955694245,-23.495666031444 -1162.36276024279,-23.3814523715638 -1162.21430623626,-23.2642731206531 -1162.14665645512,-23.1072234599488 -1162.22263340871,-22.8795824853125 -1162.30000561579,-22.6542325813878 -1161.70045369989,-22.7711311152719 -1161.12216386782,-22.8744853433644 -1160.2410388691,-23.1283947099929 -1158.91250496375,-23.6045557821829 -1157.62691295032,-24.0541241532654 -1156.99771693995,-24.1708631493164 -1156.39094842164,-24.2746512349916 -1156.11972374521,-24.2096355353598 -1155.73807729924,-24.2009813903929 -1155.37156147634,-24.1854018952225 -1155.05666954878,-24.1435626989946 -1154.75492848232,-24.0946506927424 -1154.76345338555,-23.8913893870697 -1154.71150518666,-23.7210615968543 -1154.66486685754,-23.5493480797066 -1153.82428709709,-23.7766588384021 -1153.01229844365,-23.9876851517039 -1152.28417921428,-24.1541717436097 -1151.37863177158,-24.4064510198045 -1150.50374302346,-24.6418771995175 -1149.3802272019,-24.9999437003078 -1148.29388381138,-25.3358123407226 -1147.45151293193,-25.5462038210373 -1146.99811876484,-25.5594523871158 -1146.56224756511,-25.5649207054384 -1146.45769540313,-25.4041941960714 -1146.3603312118,-25.241306715227 -1146.16603784103,-25.1276327401114 -1146.09593931932,-24.9538765559157 -1146.03192821943,-24.7788592375839 -1145.38333079016,-24.8979154793269 -1144.75787705331,-25.0036477564093 -1144.64129940251,-24.8550342835288 -1144.4174162041,-24.761195211843 -1144.20411464104,-24.6631900369446 -1143.7539494624,-24.6843736197472 -1143.32102816503,-24.6971311193845 -1142.78073016485,-24.7627313383209 -1142.62441462403,-24.6356427035807 -1142.47667031311,-24.5054425509562 -1141.41501083498,-24.8344070182283 -1140.3886576245,-25.1422986709966 -1140.19257193011,-25.030871499343 -1140.69732854959,-24.571328178852 -1141.1911241955,-24.121325576029 -1141.50608774971,-23.7652775235136 -1141.81554335677,-23.41560198049 -1141.43945257427,-23.41312176709 -1141.13936871959,-23.3723079138016 -1140.85183539985,-23.3248838010168 -1140.67808021128,-23.2216214812926 -1140.51312221806,-23.1152485586639 -1139.95548079753,-23.2063695540836 -1139.21573720081,-23.3872288342513 -1138.50152353555,-23.5531807402813 -1137.97392480777,-23.6249844179182 -1137.46563341885,-23.6857821342603 -1137.38156507492,-23.5339168322019 -1137.51777165667,-23.2727684439591 -1137.65365576481,-23.0154596866102 -1137.15240442711,-23.0779200172892 -1136.66960688912,-23.13202855335 -1137.05704285254,-22.7490703601331 -1137.47730040873,-22.3546945669721 -1137.88865794661,-21.9671654393779 -1137.21656287869,-22.1262886479664 -1136.56776292485,-22.2725118954254 -1136.1054410183,-22.3231641994804 -1135.63902554707,-22.3754461448681 -1135.18989354982,-22.419136409982 -1134.37057695606,-22.6470619010449 -1133.57900592966,-22.8589444052963 -1132.67894676928,-23.1224066286128 -1131.09413508237,-23.7261443606349 -1129.559862431,-24.2985375579714 -1128.94938554072,-24.4037496686888 -1128.36082366563,-24.4964060926153 -1128.19127087427,-24.3797967178008 -1128.32509695898,-24.1111222995544 -1128.45883852788,-23.8460842877448 -1128.32088355927,-23.7198149094262 -1128.19076416131,-23.5904746821134 -1127.02279737337,-23.9809769134022 -1126.41526898445,-24.087535925999 -1125.82951411842,-24.1825783544657 -1125.82084786399,-23.9889168930798 -1125.81624277292,-23.7943629999347 -1125.66034663864,-23.6773865976627 -1125.50590353271,-23.5613396761359 -1125.35974606328,-23.4418197450497 -1125.37043500086,-23.2448049723847 -1125.38449062284,-23.0469725925549 -1124.81642304944,-23.1433754472612 -1124.27749939956,-23.2240037134816 -1123.7581575663,-23.2941862417486 -1123.64524130717,-23.1605316046502 -1123.53932076655,-23.024015717929 -1122.72242076295,-23.2452084289365 -1121.60273154841,-23.6149877235381 -1120.51983965323,-23.9628264641366 -1120.02492449402,-24.0134261483643 -1119.54844260528,-24.0543369116217 -1119.15858380286,-24.0535349534813 -1119.05924646551,-23.9061247398316 -1118.96663674267,-23.7560562802297 -1118.61428267478,-23.7376953747167 -1118.27609720134,-23.712389262184 -1118.03192093968,-23.6396219066478 -1117.96656380393,-23.4775495042273 -1117.9068836674,-23.3152915545106 -1118.06701693017,-23.0445456084646 -1118.22607398084,-22.7784486984769 -1117.64572653658,-22.8847036117495 -1117.22936665865,-22.9066694152793 -1116.82891012785,-22.9206201062294 -1116.27301412236,-23.0114208526242 -1115.73716994584,-23.0910018371174 -1114.74268657771,-23.3998732544421 -1113.8959564298,-23.6312434424509 -1113.07798053993,-23.8470861491691 -1112.45333824053,-23.9625304501563 -1111.85096976115,-24.0671911111677 -1111.52342664738,-24.03370764656 -1110.8686624146,-24.1636085054804 -1110.2370752861,-24.2798463668353 -1110.20693971201,-24.0947578776356 -1110.18154237507,-23.9089476017298 -1109.41654852917,-24.0937945815597 -1108.94908404787,-24.1285955284468 -1108.49928008355,-24.1545626325039 -1108.64753326238,-23.8813374174344 -1108.7952236874,-23.6113266888941 -1108.06040153834,-23.7851586418177 -1107.92311766945,-23.658134274537 -1107.79365756517,-23.5289690405198 -1108.0857591992,-23.1907445836863 -1108.37290680548,-22.8568826725598 -1107.19879892949,-23.2583410990703 -1105.89638234716,-23.7192185439467 -1104.63617728574,-24.1551508933995 -1104.30719230193,-24.1210396700899 -1103.99176226764,-24.0794324269677 -1104.10050388272,-23.8280533523453 -1104.50071320766,-23.4324742605682 -1104.89283172619,-23.0448005088054 -1103.01142363921,-23.7982184803492 -1101.1893078832,-24.5146306385948 -1101.03879486686,-24.3878280687366 -1101.22059019023,-24.0961768227265 -1101.40086164594,-23.8073349933368 -1101.12815826404,-23.7480426910918 -1100.86728690915,-23.6823029044456 -1100.26549509776,-23.789620933503 -1099.75467739269,-23.849607045055 -1099.26273612793,-23.8993466509303 -1098.79144437626,-23.938286151725 -1098.33788368291,-23.9685753931854 -1097.97526470828,-23.9525733436925 -1097.18701436653,-24.1495295632825 -1096.42588658627,-24.3310739525354 -1096.38420278943,-24.1510220413983 -1096.34761325276,-23.9698868032987 -1095.45407931793,-24.2204340075661 -1094.59271201478,-24.4517409619087 -1093.76067410644,-24.6657325775601 -1093.53171908919,-24.5763376663929 -1093.3134591748,-24.4816119676386 -1092.50255712317,-24.6849263734124 -1091.77573128221,-24.8438117713479 -1091.0743511143,-24.9884294360962 -1090.2216764116,-25.2070621960004 -1089.39823381234,-25.4095878209122 -1089.21717210323,-25.2879003366321 -1090.01901870706,-24.6756937328524 -1090.80118901004,-24.0787129496064 -1090.53368446858,-24.014016154948 -1090.27791195966,-23.9440872374316 -1089.30214981685,-24.2346033953135 -1088.83546744523,-24.2673778927786 -1088.38645386399,-24.2911219736812 -1087.74859963955,-24.4087401781393 -1087.13349550037,-24.5152876264016 -1086.39747545425,-24.6808823217344 -1085.72501395204,-24.8126928281843 -1085.07638676724,-24.9309452359338 -1084.96767942392,-24.7770831545688 -1084.86619107011,-24.6228420127293 -1084.60411275244,-24.5499132749691 -1083.98641962028,-24.6550003556713 -1083.39092685414,-24.7477437653204 -1082.79839586664,-24.8394599470922 -1082.22733557201,-24.9186941697001 -1081.28745336559,-25.1820232337307 -1080.33083843085,-25.450509939511 -1079.40657310424,-25.7015209417523 -1078.94971505322,-25.7155197466231 -1078.51050137172,-25.7202955935425 -1078.06043565323,-25.7305772359316 -1077.94937199276,-25.5728346039588 -1077.84569428069,-25.4132180432791 -1077.41854318687,-25.4156411258917 -1077.00809409195,-25.4090206302976 -1076.2987327539,-25.5514138683489 -1075.24218716056,-25.8658213886193 -1074.22102704326,-26.160797872746 -1074.29704722461,-25.9038282011041 -1074.37502453893,-25.6483459693406 -1074.00563961298,-25.6189209662733 -1073.08870139409,-25.8640323451524 -1072.2030062381,-26.0912760370442 -1072.09404478591,-25.9266872334676 -1071.99251840938,-25.7607912779196 -1071.54892964425,-25.7676041546988 -1071.2326147453,-25.712019210589 -1070.92977063761,-25.6492338186034 -1070.88246870279,-25.4592106558379 -1070.84067292045,-25.2685220515146 -1070.17845076744,-25.3896884360667 -1068.67337220398,-25.930402762997 -1067.2169173919,-26.4415538714343 -1067.0203175875,-26.3177096764194 -1066.83380621126,-26.1901333747218 -1066.40186111335,-26.1877764396134 -1065.92638238327,-26.2063203292204 -1065.46919080063,-26.2165423878015 -1064.09327844571,-26.6852089930683 -1062.76230970014,-27.1260824661511 -1062.63691129007,-26.9591170341839 -1062.11287217554,-26.9941057638347 -1061.60870825646,-27.0191275391306 -1061.25687846602,-26.9676380616504 -1060.91983330522,-26.9086490224824 -1060.67145728547,-26.8064748045877 -1060.52006145775,-26.6583116080198 -1060.37744892296,-26.5040533313643 -1060.02433090831,-26.4578037861247 -1059.68594734497,-26.4055651217831 -1059.51262572044,-26.2706264269495 -1059.34934045437,-26.1326554196597 -1059.19510881409,-25.9911050865019 -1058.45757854799,-26.1415317556315 -1057.74607621585,-26.2800450930072 -1057.59529077989,-26.1369388704438 -1056.94143632672,-26.2446390068079 -1056.31114991013,-26.3399530832644 -1055.8697289266,-26.3399851297454 -1055.44561540888,-26.3318140732743 -1054.6660212044,-26.5007643416278 -1053.65256714317,-26.7848648797704 -1052.67339131539,-27.0482729551818 -1052.58494570594,-26.8651141669046 -1052.50348758473,-26.6796423614723 -1051.49669883622,-26.9586493984696 -1050.84083316061,-27.0596359563699 -1050.20874338823,-27.1466137502328 -1049.82431574158,-27.1093431663787 -1049.45567765648,-27.0657262251276 -1048.99484624699,-27.0674531596537 -1048.36098394355,-27.1565063484536 -1047.75026410213,-27.2331875020611 -1047.78546558118,-26.9849882991596 -1047.82405615968,-26.7384496111705 -1046.70497531454,-27.0724660200905 -1045.85470460901,-27.2694769569709 -1045.03398722704,-27.4487770310342 -1044.28861784109,-27.5900850125491 -1043.56975898327,-27.7159504985617 -1043.53430828344,-27.4995508817107 -1043.38504025444,-27.3417139165766 -1043.24465797677,-27.1811017556448 -1043.05963969322,-27.0441985703349 -1042.88450666628,-26.9035790458767 -1042.50505175,-26.866812587678 -1042.38976619028,-26.6990914797006 -1042.2822238637,-26.5295374470535 -1041.9649299564,-26.4665365222015 -1041.6612877312,-26.3954505617612 -1041.07251278888,-26.467616853625 -1040.34048452666,-26.6117314497411 -1039.63438975681,-26.7413428638282 -1039.51953188566,-26.5741453358922 -1039.41239041701,-26.4052730042335 -1038.98902742939,-26.396596808512 -1039.36784950214,-25.9866063366601 -1039.73969628715,-25.584295815655 -1039.2431666161,-25.6207025718057 -1038.76540624891,-25.6459771867449 -1037.94339200267,-25.8416764818519 -1037.75693505334,-25.7192727195596 -1037.58014115256,-25.5928443541796 -1037.21861682686,-25.5606234115529 -1036.87188699241,-25.5222375532601 -1036.11503464129,-25.6877609077312 -1035.07555928313,-25.9934621028016 -1034.07096737745,-26.2780560445516 -1033.76019851892,-26.2122859497294 -1033.46287870768,-26.1414998956846 -1033.14253149594,-26.0836668931634 -1032.62150138581,-26.1258454404882 -1032.1200903302,-26.1586323490793 -1031.54951839331,-26.2247609289715 -1031.00004782295,-26.2801316824577 -1030.39352779039,-26.3631014033823 -1029.47303980313,-26.6018554208754 -1028.58405622671,-26.8241234982188 -1028.34876791448,-26.7161732697436 -1028.12477958839,-26.6042147146397 -1027.66665183775,-26.6101269957385 -1027.03704223544,-26.7014238676125 -1026.43036523291,-26.7819326303625 -1026.12744359802,-26.7083217796548 -1025.83781398781,-26.6280368243525 -1025.54607294255,-26.5504101935315 -1025.5855079163,-26.3078679183636 -1025.62805729211,-26.0672700757439 -1025.41026454016,-25.9573878272268 -1025.20312290014,-25.8438394357098 -1025.42975822666,-25.5140262309564 -1026.32995741473,-24.8520701614841 -1027.20757988083,-24.2070184201382 -1026.62828711439,-24.297412374097 -1026.06997137891,-24.3759236752024 -1025.8018234723,-24.3095734940479 -1026.28024728367,-23.8705095199616 -1026.74834910172,-23.4401797294597 -1026.16019656961,-23.5422351038051 -1025.59314437561,-23.6326491634082 -1025.62480126918,-23.4236097445793 -1025.91883096961,-23.085471972802 -1026.20782937724,-22.7530471053104 -1025.88328081269,-22.7312981800552 -1025.57187569454,-22.7027670572256 -1024.67768185053,-22.9645276840577 -1023.99193338352,-23.1211699979846 -1023.33006305164,-23.2645115524471 -1023.39039726673,-23.045372751476 -1023.45257670978,-22.8252536941037 -1022.72577931497,-23.004241179506 -1022.29418808384,-23.0323374000723 -1021.8789796191,-23.0516032156501 -1021.97573270409,-22.8163806730976 -1022.07321209803,-22.5814105194805 -1021.69024511622,-22.590802476895 -1021.12172782663,-22.6928842362581 -1020.57354047186,-22.7822448856566 -1019.90358037617,-22.9318766828161 -1019.25701406754,-23.0676957025725 -1018.61826889448,-23.1991805856079 -1017.73424963529,-23.4523423573541 -1016.88002799446,-23.6886615896711 -1016.19026416873,-23.83927682235 -1015.52465173523,-23.9762107309236 -1015.05734695521,-24.0125327657535 -1014.1780127145,-24.2551464159469 -1013.32849508356,-24.4801142838518 -1013.22467730727,-24.3290647647832 -1013.12783275531,-24.1768531997508 -1012.96316044719,-24.0600397771475 -1012.86036135914,-23.9134254943627 -1012.76441032612,-23.7649110354925 -1012.69561551395,-23.6039289042179 -1012.63261154157,-23.4409703766751 -1012.4240404205,-23.3521709096405 -1011.87736951404,-23.4344591923716 -1011.35055229496,-23.5064012979928 -1010.85747288955,-23.5613283357386 -1010.38267162129,-23.6067873205431 -1010.41247316798,-23.3978467946776 -1009.85503102487,-23.4854535125554 -1009.31776271049,-23.5621309419025 -1008.63897537131,-23.7078709389733 -1007.98400271877,-23.8418498994824 -1007.70786668093,-23.7845463782864 -1007.07180243604,-23.9074340049767 -1006.45831683527,-24.0188981137639 -1006.55872800189,-23.7716881849394 -1006.65995239161,-23.5262500705953 -1006.57962531168,-23.3744323896403 -1006.3474459483,-23.2988841419342 -1006.12582203941,-23.218225555862 -1006.1336008867,-23.0252716341553 -1006.14478249029,-22.8322984021623 -1005.48718339936,-22.9754252887945 -1004.29421013224,-23.385736649692 -1003.14012879021,-23.7706988295268 -1003.07237432554,-23.6094926563186 -1003.01037421388,-23.448043810927 -1002.46129168855,-23.5303542869794 -1001.76629369841,-23.6855055461272 -1001.09556516829,-23.8263605863417 -1000.53705396177,-23.9100480707619 -999.998833813065,-23.9828858154381 -1000.39398798539,-23.5881151795379 -1001.17859126357,-23.0023196411525 -1001.94368684055,-22.4321518872495 -1001.95294507588,-22.2450311064148 -1001.96543597234,-22.0587067715955 -1001.61587499665,-22.0560000413059 -1000.63522709739,-22.3682485100832 -999.687030219523,-22.6609114828043 -998.980365079513,-22.8301271712807 -998.298156608261,-22.9847118823578 -997.167134881266,-23.3629825034813 -996.245973083625,-23.6322263552018 -995.355756230265,-23.8832506068314 -993.910311491387,-24.4086551558237 -992.511446456021,-24.9058013971074 -992.132320883003,-24.8886562504816 -992.227339253015,-24.6335058506783 -992.323534879767,-24.3799197521094 -992.188761152701,-24.2456525596195 -992.06185194447,-24.1084805402547 -991.910888986042,-23.9852343905587 -991.426032420862,-24.0296980596676 -990.959332637941,-24.0657033112213 -990.502614799858,-24.0965414313373 -990.063212252631,-24.1179495163117 -989.105474852304,-24.3983207848693 -987.655869912959,-24.9210912128359 -986.253058415002,-25.4156856973688 -986.164920827347,-25.2482191781259 -986.083457110892,-25.0782918173348 -985.939880014896,-24.9419351094441 -985.841323498309,-24.7839101154576 -985.749667951819,-24.6244483294409 -985.110169163182,-24.7405386116285 -984.493514303282,-24.8443338103649 -983.677428884577,-25.0462269100049 -982.801740499736,-25.2761021782408 -981.95597054917,-25.4875882590637 -981.890350525024,-25.3083923983442 -981.830746848904,-25.1287612193569 -981.13056351187,-25.2696328640905 -980.709046192738,-25.270550149657 -980.304038907739,-25.2622804468726 -980.515464348233,-24.9453402366421 -980.724690074242,-24.6338026451603 -979.511421057173,-25.03670844308 -977.594896357427,-25.7862157768395 -975.739116054289,-26.4978146915997 -975.404862265851,-26.44215386474 -975.084784109239,-26.3805860267321 -974.762071151748,-26.3200184780751 -974.284398473807,-26.3375658646708 -973.825118116422,-26.3458762213019 -974.06333652022,-26.0055059497372 -974.298754886986,-25.6702298276736 -974.343076931258,-25.4342866421522 -974.307227887012,-25.2398687846614 -974.276520375911,-25.0459681220198 -973.180739591989,-25.3858720827133 -972.121392758257,-25.702765107223 -971.597449380876,-25.7500305690781 -970.549887415034,-26.0580922989363 -969.537480617354,-26.3466085489837 -969.407790629542,-26.1905652094412 -969.286184273674,-26.0309930981524 -969.472154040236,-25.7196948300624 -969.462068488677,-25.5088796429846 -969.456429373599,-25.2987358920006 -969.099837899962,-25.2665686966741 -968.757846468046,-25.2269071470691 -968.403579142791,-25.1931890942073 -967.344368656462,-25.5127199133879 -966.320549688111,-25.8117887422575 -966.659302288451,-25.4259987055816 -966.992185691115,-25.047464949079 -967.028019095755,-24.8209859149626 -967.57996338036,-24.3385243328863 -968.119536859565,-23.8680800975611 -967.830177273631,-23.8172805935823 -967.553139607204,-23.7605863191063 -967.453187318267,-23.6156400976955 -966.863099146458,-23.7168938230172 -966.294202613369,-23.8065011901036 -966.117580814237,-23.6983930915081 -965.949961725555,-23.5872274657714 -965.667457949072,-23.535846592727 -965.681140958892,-23.3353273930494 -965.698140596145,-23.1361382914055 -965.244598187251,-23.1740319128769 -964.808110983773,-23.2022361001693 -964.152345434131,-23.3408139043094 -963.570880347803,-23.4404437780843 -963.010299993309,-23.5287960062514 -962.872635253535,-23.4052278838742 -962.742742797764,-23.2788846911233 -962.158949717375,-23.3803329665696 -961.763730530571,-23.3854900691151 -961.383908758743,-23.3835163149859 -960.626112904496,-23.5723298717383 -959.894401961492,-23.7435895275649 -959.688373584072,-23.6525223707438 -959.088554115551,-23.75845536392 -958.510217933236,-23.8519303663085 -957.807359112293,-24.0080696069003 -957.129058989068,-24.1496407864657 -957.062440680594,-23.9823374141046 -957.242150158155,-23.6936176376079 -957.420361223357,-23.4095788623003 -956.812246500421,-23.5210606385666 -956.225833695641,-23.6221219399431 -955.67227354737,-23.7061635837958 -955.881436434243,-23.4078065375064 -956.088131230787,-23.1121202467762 -955.222319409256,-23.3548695824739 -954.385791377213,-23.5824735435842 -954.165309168223,-23.4993679772098 -953.777029669773,-23.5012537588774 -953.403938342726,-23.4940223349943 -952.631429088806,-23.6875762194982 -951.885490568161,-23.8660899813952 -951.80968317316,-23.7079491711561 -951.525875663255,-23.6563154779875 -951.254188406012,-23.5978344062405 -951.325752548056,-23.3694710866491 -951.398898850031,-23.1404127239575 -951.140823052201,-23.0806403638253 -950.592741025399,-23.1653411864618 -950.064521657011,-23.2395913589028 -949.115702734786,-23.5251809033878 -948.198599094904,-23.7907373260616 -947.126622235038,-24.1313919730336 -946.281145546044,-24.3549414583025 -945.464524248128,-24.5620497061503 -945.162015947309,-24.5093401327463 -944.872381829575,-24.4514429086348 -944.597563409849,-24.3862538763068 -944.558149766353,-24.2036544285035 -944.523790323439,-24.0209169829896 -943.75922679361,-24.2047099898302 -943.021110008934,-24.3735736466266 -942.319342882877,-24.5216932586622 -941.875724451332,-24.5404325055757 -941.449140173504,-24.5504577582463 -940.25598795906,-24.9431818019168 -939.102072640606,-25.3117560745608 -939.187722217883,-25.057549310366 -939.413468530607,-24.7357630489325 -939.636546729344,-24.4187504114733 -939.406322770285,-24.3314036162888 -939.186804313009,-24.2390031931012 -938.486613267207,-24.387974991452 -937.783327294218,-24.5379664432101 -937.104734902236,-24.674245407746 -936.527573882161,-24.7579174379126 -935.971435474582,-24.8288127608095 -934.846928176246,-25.1849102697127 -933.734360061148,-25.5316097152477 -932.65875354547,-25.8556324675499 -932.955885507511,-25.4894593430852 -933.248403259095,-25.1303438328857 -933.10162696408,-24.994107660068 -932.845085208753,-24.913434885866 -932.600152627243,-24.8280511328862 -931.784977157509,-25.0287669767674 -930.997907737183,-25.2139619676781 -930.706466910629,-25.1484435653543 -930.319119880743,-25.1313688834731 -929.947288800745,-25.1078134644131 -929.801929568984,-24.9702452057101 -929.664913345487,-24.8310803657507 -929.306464835171,-24.8030292714591 -929.087367011917,-24.7068867751434 -928.878707451995,-24.6052168678213 -928.338403120042,-24.6720904306453 -927.817999048794,-24.7283943722977 -926.66090194062,-25.1015023226266 -924.914389961292,-25.764378773775 -923.223620875199,-26.3937726226683 -922.911639103544,-26.3268141565418 -922.613176772907,-26.2538459628603 -922.496475367683,-26.0911972788419 -922.504113335241,-25.8679879585552 -922.515740964712,-25.6448829169115 -922.360152191062,-25.50858519229 -922.213283110868,-25.3672493011103 -922.356556631688,-25.0838189313733 -922.534670763529,-24.7853232575711 -922.711536888092,-24.4905644131989 -922.501465949813,-24.3937125256572 -922.301492962946,-24.2906553639463 -922.216677687459,-24.1318353517959 -922.955363803484,-23.5624161803108 -923.676027941558,-23.0090375076801 -923.920279214942,-22.6990359604008 -924.160910343578,-22.3932299593293 -923.829449807998,-22.3773472589369 -922.827023063921,-22.697293484498 -921.857753369445,-22.9955625236002 -921.894707171345,-22.7898856009426 -921.934164264554,-22.585241084499 -921.510382162913,-22.6125659484835 -920.805459051087,-22.7802549024704 -920.12495364066,-22.9352311601292 -919.876521269083,-22.8708660863117 -919.639066737496,-22.8030246187735 -919.061794119091,-22.9058630975469 -917.655942738099,-23.4200683443198 -916.29533381178,-23.9086459398968 -916.636098622054,-23.5402916878391 -916.970580293483,-23.179442403676 -916.426242869793,-23.2617920869353 -915.621718352005,-23.4731105027711 -914.844678523728,-23.6684828151169 -914.405127114338,-23.6942024415874 -913.982316257462,-23.7096186066938 -913.483909200074,-23.7627931418767 -912.7059143415,-23.9547616351734 -911.954735770885,-24.1312659482637 -912.426925083862,-23.6946316570751 -912.888990169396,-23.2678569848673 -912.751907780935,-23.1461920292542 -912.226707206234,-23.2200440809761 -911.720680577862,-23.280987947415 -911.296062857746,-23.3017715952035 -910.887694990162,-23.3138360659084 -910.669518318267,-23.2321065409138 -910.23562299874,-23.258354291878 -909.818236308557,-23.275595727131 -910.014976634298,-22.9870586732041 -910.209547258317,-22.7014223299523 -909.836677902315,-22.7014825729497 -909.099994385336,-22.8836815938579 -908.388695070145,-23.0520229669147 -907.836715459405,-23.1388819161598 -907.304709860901,-23.2155836190401 -907.204669645927,-23.0752420974119 -907.166088792111,-22.9047307806783 -907.132297202132,-22.7350424985066 -906.789462772755,-22.7197903860501 -906.460363935614,-22.6990634579734 -906.340210853853,-22.5727837035933 -906.370827541101,-22.3722515298891 -906.404097136943,-22.1735466788573 -905.273838149644,-22.5575150119984 -904.180518267904,-22.9194622824667 -903.411922453655,-23.1156921972432 -902.71347238513,-23.2755599657344 -902.03933650084,-23.4215228010269 -901.871573665707,-23.3126781338982 -901.712480335506,-23.2011040730309 -901.469392317862,-23.1317834105258 -901.091762330665,-23.1306188113048 -900.728961563895,-23.1227467715178 -899.754682485926,-23.4195964877429 -898.812900607752,-23.6965702136617 -898.756714222925,-23.5283912002495 -899.152882030394,-23.1373077084564 -899.541031112471,-22.7536578481396 -898.631342435929,-23.0231050761943 -897.752144935463,-23.2747690205666 -897.845171459511,-23.0368057725013 -897.857307314123,-22.8415489497477 -897.872719339207,-22.6478527232224 -897.446931141942,-22.6740642260587 -897.037334390939,-22.6933609425366 -896.637165741439,-22.7073979581563 -895.828614211823,-22.9259933855604 -895.047565436919,-23.1288108609107 -895.11750476704,-22.903696924793 -895.189027526331,-22.6803649545022 -894.931161376203,-22.624728076863 -894.684729985956,-22.5636998866817 -894.449133856486,-22.4971620235808 -893.746634817937,-22.6645535245074 -893.068464148865,-22.8203428275032 -893.194057546591,-22.5713530583354 -893.48295729867,-22.2421613708925 -893.766854996633,-21.9193293318885 -893.149327754542,-22.0499215838532 -892.553504271623,-22.1700398482506 -891.954391466737,-22.2887862931995 -891.386687445769,-22.3923442311475 -890.839253105457,-22.483824884046 -890.81223206125,-22.3133292198121 -890.789546720891,-22.1433016612948 -890.344938771653,-22.1863179427861 -889.969687167637,-22.1937293740384 -889.609006732534,-22.1944577465299 -889.264872687625,-22.1859983471587 -888.934394665346,-22.1705911169688 -887.969399619363,-22.4736791979785 -887.377139036525,-22.5859608536274 -886.80594336195,-22.6863744883689 -886.682659578824,-22.5621841515484 -886.566596159886,-22.4369397094812 -886.052809993804,-22.5107583120105 -884.824042181034,-22.9415224884978 -883.635176777382,-23.347545470175 -883.154103774125,-23.3947819163622 -882.69098591883,-23.4340423019954 -882.349641818523,-23.4118280287281 -882.32299052083,-23.2317421650746 -882.300844712623,-23.0517917277277 -882.474279443243,-22.7765503394667 -882.646202795797,-22.5033402086473 -882.31663414158,-22.4855343679276 -881.680531539927,-22.6208958781212 -881.066769390696,-22.7426659699034 -880.240746031908,-22.969837029423 -879.442745709218,-23.1797701334164 -878.963923262141,-23.2299610612648 -878.840035285392,-23.0998649820898 -878.72350484679,-22.9676598451761 -878.658250990947,-22.8114420601101 -878.598557583558,-22.6537730183341 -877.884230495972,-22.8247707052708 -877.583619605621,-22.7882289743092 -877.295497822989,-22.7446868549738 -877.087346101437,-22.6628101357897 -876.888929319098,-22.5766522143181 -875.740503329182,-22.9659419487527 -874.56446835071,-23.3647039893103 -873.426883077818,-23.7407504994828 -873.008910057214,-23.7533592712364 -872.6070834378,-23.7575384891262 -871.86916527044,-23.930277973152 -871.217608564802,-24.0581754451479 -870.589141693249,-24.1743943702009 -869.830926590344,-24.3523750764677 -869.099020999293,-24.5154534307233 -869.265321256912,-24.2280757342787 -870.058020100333,-23.6304644898519 -870.831120864344,-23.0490529205194 -870.167798943728,-23.1916164718579 -869.527746349869,-23.3214164812806 -868.544831039661,-23.6208610948333 -867.541396471743,-23.9279549692452 -866.571405438348,-24.2146186351327 -865.69517106427,-24.4516987776294 -864.848738085227,-24.6715014238496 -864.594251120721,-24.5934491571776 -864.367605335924,-24.5025308783051 -864.151593381906,-24.4064948141201 -863.664348536756,-24.4476417145379 -863.1954178525,-24.4786419316364 -862.464217367122,-24.6408630730558 -861.969020253291,-24.683398370747 -861.49242242901,-24.7169874348142 -861.815294753846,-24.351002429182 -862.132539975796,-23.990295199028 -861.62427341676,-24.0461893599977 -861.282776647832,-24.0175901210993 -860.955219497313,-23.9833518824839 -860.503738509896,-24.0103205543036 -860.069441831389,-24.0291872434295 -859.927703674943,-23.9015977354334 -859.719953275069,-23.8084260738023 -859.522139119991,-23.7104089242476 -859.113504836446,-23.7196986285976 -858.720714561496,-23.7203885974273 -858.321594413032,-23.7249653243675 -858.2145563229,-23.5829500518467 -858.114444125057,-23.4383669690824 -858.004276471286,-23.2997501894241 -857.901092114981,-23.1599773813074 -857.296147339745,-23.2716271447156 -857.270384614335,-23.0943296908025 -857.249038956034,-22.9153058299398 -856.453961561832,-23.1253212254738 -855.686023474757,-23.3200676135821 -855.079084536043,-23.4310041148239 -854.6375762176,-23.4598513292181 -854.212825082809,-23.4790052707469 -854.05139283678,-23.3673556425638 -853.898435773364,-23.2517695956085 -853.779838639112,-23.1204693806136 -853.416652448984,-23.1137283076937 -853.067836295562,-23.099265128339 -852.324364902044,-23.2820367109976 -851.606532860179,-23.4492193927479 -850.837877854157,-23.6410752272107 -850.203381212126,-23.7638354634646 -849.591404196547,-23.8747263700529 -848.613254884181,-24.1663663221822 -847.667854632987,-24.4387149939121 -847.497322441115,-24.3212146891839 -847.621641315542,-24.0571615407052 -847.746159649716,-23.7964706218045 -847.349213770334,-23.7992658874566 -846.967778393996,-23.793866547136 -846.79042125209,-23.6860792605329 -847.005301865802,-23.3844615780151 -847.21755285331,-23.0854691957777 -846.485710411641,-23.2631188892371 -845.779149772557,-23.4261184337706 -845.172088690249,-23.5378436865277 -844.75945017832,-23.5501312270408 -844.362755074636,-23.5545449038895 -843.83356594425,-23.6262996629676 -843.323747452302,-23.6878785889222 -843.318255626811,-23.4961330921277 -842.660149945214,-23.6326492774702 -842.025225267043,-23.7552731364519 -841.253160828933,-23.945650874826 -840.507710715098,-24.1209901206662 -839.876274421606,-24.2374358368712 -839.333102293685,-24.3085409495602 -838.809861559898,-24.3689137605439 -838.583753385712,-24.2798696036369 -838.368221949877,-24.1886038166594 -837.861845811085,-24.2415019825043 -837.264882110257,-24.3389725757745 -836.689452333009,-24.4251713322884 -835.966618203959,-24.5840965138568 -835.269072468778,-24.7290314024116 -835.262472796029,-24.5272144527758 -835.736391546871,-24.0878154038989 -836.200171386184,-23.6575563223677 -835.47165649221,-23.8270750777535 -834.768449170433,-23.9820342563989 -834.276944608442,-24.0296528174921 -833.671528200147,-24.1339476277798 -833.087846012618,-24.2266023165917 -832.571512199805,-24.2846813377494 -832.074307759719,-24.331835760173 -831.519973748292,-24.4067506138849 -831.080233089964,-24.4240510847708 -830.657402185407,-24.4333568889066 -829.870143325448,-24.6244382329664 -829.110081041487,-24.8012924765082 -828.45358319442,-24.9241897543183 -827.875236731596,-25.0061277179893 -827.317992683862,-25.0762727899507 -827.384149344272,-24.8343245046724 -827.452361237544,-24.5942920028042 -827.030105348819,-24.6020367317027 -826.499116497504,-24.6645448557157 -825.987746533048,-24.7149864603939 -826.030335583462,-24.4895270346106 -826.075587104195,-24.2638379892494 -825.416505653786,-24.392078718174 -824.650068501445,-24.5729801116242 -823.910207123516,-24.738627996314 -823.636904064725,-24.6704197637732 -823.375627872964,-24.5956090110117 -822.963987580239,-24.5981769648876 -822.304768408988,-24.724092598277 -821.668977599105,-24.8371794011501 -820.734490310125,-25.0978294640581 -819.831635593419,-25.3402270159335 -820.152172747636,-24.9684370969881 -820.275208319872,-24.6991100233991 -820.39859501273,-24.4335201490354 -819.791388345496,-24.5352649070636 -819.206035096237,-24.6249064015454 -818.702454366784,-24.672583395634 -818.593655590454,-24.5223788921414 -818.492009105415,-24.370647126267 -817.615665943327,-24.6077859982231 -816.76912731331,-24.8282436793285 -816.123259040225,-24.9455761089363 -815.353447048595,-25.1221263427502 -814.610426769577,-25.2828462636717 -814.442028461748,-25.156607906161 -814.282658809387,-25.0272351011474 -814.014223647864,-24.9529344739049 -814.057366263374,-24.7241462283233 -814.103213609901,-24.4966236429726 -813.615545318789,-24.5378245860863 -813.14620675338,-24.5695625083666 -812.766428152629,-24.556160029903 -812.358176395111,-24.5574422137643 -811.965907518297,-24.5503193862115 -811.996316150113,-24.3320143953473 -812.029727367289,-24.1139692088947 -811.791212348777,-24.0349989477846 -811.809335197091,-23.8274614824951 -811.830735448721,-23.6200213669044 -811.782844747231,-23.4494061694644 -811.740110344114,-23.2768329088844 -810.689902023891,-23.611029505423 -809.777751318874,-23.8737258317116 -808.896318049864,-24.1175338056544 -808.855276692474,-23.9384129782203 -808.819286513721,-23.7597402354299 -808.052169387762,-23.9483380961468 -806.932033386508,-24.3103543797965 -805.848861395565,-24.651649778514 -805.200985951184,-24.7703205833652 -804.576233296732,-24.8763814948793 -804.699141573995,-24.6082506666893 -804.955376982911,-24.2757630627355 -805.207954437682,-23.9482666237631 -804.579844850772,-24.0644252493732 -803.974131309632,-24.1683892948955 -803.818597484626,-24.0456488040054 -803.314392401633,-24.0999837576943 -802.828913070095,-24.1437132871921 -802.611244579828,-24.054025257069 -802.403834281119,-23.9599433129674 -802.273638021756,-23.8281513532525 -801.971210112916,-23.7832580370801 -801.681503039349,-23.7317070903625 -800.672981838369,-24.0408648547643 -799.698063959089,-24.3298576695732 -799.301349852614,-24.3266848553891 -799.049284035179,-24.2520208637143 -798.808536426818,-24.1729327874369 -798.642606787625,-24.0568573431446 -798.485413719075,-23.9370274656408 -797.897475871982,-24.0342009728584 -797.376785630122,-24.0966897382007 -796.875310839455,-24.1482353492451 -796.861602559655,-23.9557164384557 -796.852131185606,-23.7629495704342 -796.303759779626,-23.8415225791177 -795.000362372375,-24.2968756482953 -793.739321099414,-24.7262188320896 -793.487651026624,-24.6473117652615 -793.247365179883,-24.5639698327976 -792.312352062452,-24.8273262476769 -791.480775257661,-25.0364593743073 -790.677785852483,-25.2299098581103 -789.79340012327,-25.4610481785291 -788.939249579952,-25.6762049321221 -789.009125866567,-25.4271924722203 -789.181999353121,-25.1290231805142 -789.353824045987,-24.833940232466 -789.157007100157,-24.7259952486986 -788.969981580488,-24.6141551877886 -788.769595694746,-24.5102384355436 -788.422751097507,-24.4811404549605 -788.090065390321,-24.4442718427789 -787.849008316799,-24.3624196253278 -787.6189759279,-24.2764093597015 -787.491144772568,-24.1395071375117 -787.749964832642,-23.8115398752502 -788.004938732617,-23.4891220798874 -787.398655400552,-23.5982961854611 -786.814046521696,-23.696175699968 -786.188082350263,-23.8136832859436 -785.147121527667,-24.1376613396719 -784.140751198011,-24.4419632031396 -784.314628730447,-24.1526898064559 -784.487247158882,-23.8668163537837 -784.360568736728,-23.7333595438421 -784.773901802053,-23.3297825680389 -785.178783165903,-22.9367776196326 -784.267185545936,-23.2047166526715 -783.386182932741,-23.4535181585078 -782.647091629788,-23.6291548142807 -782.029274514762,-23.7440272227949 -781.433474594197,-23.8468556255808 -780.573943771169,-24.0790146390572 -779.743653961709,-24.2962139140721 -780.043108889929,-23.9454294841466 -780.746436112595,-23.3971072383696 -781.432722382364,-22.8618239356684 -780.702807984411,-23.0393242972646 -779.998102660134,-23.2026873700348 -779.583695928566,-23.2205894701676 -779.001007121116,-23.3212723835138 -778.439230792508,-23.4104344118747 -778.528571421762,-23.1730888619801 -778.618969797055,-22.9386192532782 -778.32721209039,-22.8973622339664 -778.202405682449,-22.7724037961108 -778.084894100372,-22.6458585883094 -777.47628588779,-22.766275979323 -776.889227238053,-22.8742760928861 -776.407937108752,-22.9283729351693 -775.916376478062,-22.9859288140994 -775.442983918199,-23.0348850845722 -774.360873417353,-23.3874034954416 -773.314418459215,-23.7192016509884 -772.923400722463,-23.7191500173511 -772.438283720085,-23.7653216980169 -771.971300890876,-23.8040582415867 -772.045242789237,-23.571139055943 -772.120761160511,-23.3393894740031 -772.004267425929,-23.2057467095411 -771.852002761043,-23.0910004036013 -771.707913323787,-22.9730560407757 -771.850516127529,-22.7139859635484 -771.992505725898,-22.4570116506927 -771.060289238823,-22.7401291618753 -770.399171202565,-22.8858387594016 -769.761175625134,-23.0171612237363 -769.054482292657,-23.1814559691722 -768.372341294227,-23.332920429639 -768.446173163559,-23.1051646724329 -768.396332681127,-22.9409053122511 -768.351602815316,-22.7761312221425 -767.894231412076,-22.8198497816089 -767.453953417963,-22.8536419584704 -767.016835632908,-22.885414406479 -766.525171611241,-22.9445805274526 -766.051648772261,-22.9937467648114 -764.960508068038,-23.3507258835959 -763.905291263999,-23.6873210984905 -763.756250789199,-23.5669174441951 -763.311187744906,-23.5962441392607 -762.883012051175,-23.6151180685837 -762.605291187291,-23.5605550612064 -762.339508208282,-23.5002325085372 -761.827344862045,-23.5626319619596 -761.907589582766,-23.3285152178508 -761.989186655283,-23.0962832244636 -761.35453030763,-23.223901018534 -760.742306506607,-23.3405471831237 -759.844940779313,-23.5977214667094 -759.452338999359,-23.6005567425725 -759.075076621828,-23.5950449461998 -758.459234702182,-23.7098580411619 -757.865333669501,-23.8119226063599 -757.42918130423,-23.8355531752008 -757.267681896215,-23.7206828236552 -757.11472219301,-23.602848187898 -756.781786852066,-23.5754011387953 -756.462433296372,-23.5419612878959 -755.936888289173,-23.6110705898562 -755.560110649734,-23.6048681980289 -755.198225615458,-23.5926857794496 -754.40827597103,-23.7927114855136 -753.645456534959,-23.9782461891724 -753.173240299536,-24.0163681999276 -752.423954407948,-24.1934351355768 -751.700645473386,-24.3553466586165 -751.224620740465,-24.3912070763734 -750.766571812733,-24.4184065089957 -750.440571055931,-24.3789533636881 -750.015278564383,-24.3890719880003 -749.606467320077,-24.391949693199 -749.360075643427,-24.3133746986149 -749.124854846299,-24.2296342443847 -749.096424120805,-24.0432781987383 -748.706036840762,-24.039737515585 -748.33102465194,-24.0290201362076 -747.388342105917,-24.3019345180121 -746.477377798825,-24.5572451535599 -746.091924503667,-24.5467449322462 -745.665230734575,-24.5569180813357 -745.255072108968,-24.5583284424995 -744.866929245412,-24.5498043456884 -744.494169229973,-24.5324806217595 -744.374163043444,-24.3894029587905 -744.108121623855,-24.3204148160315 -743.853837329601,-24.2467976209426 -743.316508679155,-24.3140791706764 -742.798955773384,-24.3716466943931 -741.903514877845,-24.6183182178979 -741.238050369435,-24.7466368533955 -740.596212925955,-24.863080459399 -739.998051845288,-24.9541837851645 -739.421593989518,-25.0352958838425 -738.475291621936,-25.3002080849386 -737.47117155227,-25.5910004527736 -736.500835142113,-25.862297134386 -735.873340640688,-25.9594592211802 -735.268583101303,-26.0438118332358 -735.274649589691,-25.8219713708418 -734.988971108997,-25.7480026602643 -734.715915426843,-25.6678595050727 -734.096735880352,-25.7618885140624 -733.50002747178,-25.8450695475748 -732.615222333937,-26.0707474475479 -731.891144426378,-26.2153079195707 -731.192679710552,-26.3448821965799 -731.250238280515,-26.0946163436527 -731.310349042509,-25.8451559365719 -730.935911585995,-25.8167137647151 -730.823256407153,-25.6563041920037 -730.718100827423,-25.4934538160188 -730.503671579502,-25.3876723137256 -730.299682761673,-25.2767719447691 -730.360841342321,-25.0353092276585 -730.291497705318,-24.8608043313558 -730.228226278263,-24.6855232421291 -729.953010501409,-24.6176925702875 -729.689889333976,-24.5457073554731 -729.848932764457,-24.2641830137763 -730.177214462172,-23.8984875889373 -730.499651391394,-23.5406961721502 -729.804962015154,-23.6956071063852 -729.134534616247,-23.8355486753636 -728.443302152304,-23.9844006726426 -728.031594642298,-23.9920263661418 -727.635883617154,-23.9920669776632 -726.95444233502,-24.1355940622713 -726.296962323299,-24.2651299474217 -725.801596507881,-24.312135893211 -725.511788711725,-24.256421425658 -725.234414854328,-24.195193318075 -725.291499946786,-23.9657839787468 -725.350755021663,-23.7392367913572 -724.977775865521,-23.7299837522244 -724.553246582513,-23.7469460288369 -724.145037115135,-23.7557262926558 -724.18794358575,-23.5398349180373 -724.23331622289,-23.3245208991117 -724.048658877858,-23.2251354630504 -724.549971213431,-22.7842703197316 -725.040098709379,-22.3535005583831 -724.469810449593,-22.4564780894809 -723.919904351243,-22.5490734534955 -723.120131237531,-22.7639115253696 -722.46433136144,-22.906889849317 -721.831497903152,-23.0360273187381 -721.359383941766,-23.0844816081685 -720.904850443191,-23.1225416129535 -720.556159493247,-23.1083570640573 -719.521133611746,-23.4368942500085 -718.520377907237,-23.7464657707103 -718.137844402717,-23.7419611919754 -717.770396565532,-23.7304357687961 -717.696335571605,-23.5726685499595 -718.427682621521,-23.0126705280357 -719.141114422742,-22.4684639462801 -718.508272676685,-22.6016295828956 -717.897685720632,-22.7229750979901 -717.779362371112,-22.5971170815752 -717.415680587087,-22.5947647590679 -717.06630393861,-22.5854659391577 -717.002715206915,-22.4327364545731 -716.944554603798,-22.2796227600499 -716.22764693467,-22.4557918814312 -715.713204667813,-22.5305463990669 -715.217497173286,-22.5961383285807 -714.162907939586,-22.9386118372546 -713.143088162749,-23.2613200629067 -713.02016733792,-23.1326660172891 -713.180192192251,-22.8635201311463 -713.339114338737,-22.5977435753971 -713.195599701885,-22.4855554674848 -713.059868046936,-22.3698551569742 -712.34962567711,-22.5446596679739 -711.516527955839,-22.7782684767226 -710.711606949344,-22.9941931912455 -710.070986055153,-23.1272836482949 -709.452926415381,-23.2469736946908 -709.099182489017,-23.2348219224855 -708.75268538873,-23.216779099517 -708.420121119454,-23.1936555929406 -708.045439412554,-23.1912384734474 -707.685495392426,-23.1822500554599 -707.66982926717,-22.9997207427287 -707.594450154189,-22.8493864973222 -707.524915443257,-22.6980090736851 -707.060388224111,-22.7454271027164 -706.61316390479,-22.7832992750132 -706.278022421665,-22.7653703592396 -705.51347626266,-22.9624870211067 -704.775120142988,-23.1434271067287 -704.288338971346,-23.1977026752396 -703.819601502116,-23.242824756329 -703.539847953128,-23.1927984005262 -703.185613204924,-23.1790401898849 -702.845532348029,-23.1607931089972 -702.402443818445,-23.1914102635062 -701.976140421648,-23.2145427510921 -701.726816622082,-23.1489160193871 -701.869313695011,-22.8884671278184 -702.011228203285,-22.6314938878028 -701.643468415664,-22.6320245997793 -701.290118261967,-22.6242982790885 -700.511135498114,-22.8296746424838 -699.968954401044,-22.9160284331572 -699.446372824298,-22.9899303098908 -698.877199917964,-23.0860762632677 -698.328496714389,-23.1711492930303 -697.392560996069,-23.450528589101 -696.613125003409,-23.6481054254815 -695.860454036652,-23.8305157153908 -694.792096596521,-24.1689454272219 -693.759126168327,-24.4860142868947 -693.297889742651,-24.5137797000346 -693.40583173447,-24.2566587648144 -693.514482114265,-24.0022101067672 -692.711940485986,-24.2054772605232 -691.936960509733,-24.3935320901262 -690.615811534297,-24.8522497916044 -688.617054422828,-25.6456545803466 -686.681422509496,-26.3992901874155 -686.552326432726,-26.2418185120271 -686.431318147315,-26.0829257542862 -686.056147517134,-26.0513369033351 -685.45647319681,-26.1330075682609 -684.878742691528,-26.2038181760058 -684.160487662335,-26.3430094368793 -683.467720683975,-26.4674438589216 -683.464031529655,-26.2465334158762 -683.557245431802,-25.9784071374994 -683.651956685637,-25.7127923656876 -683.081646581472,-25.7811695288668 -682.532384369065,-25.8405021708501 -681.770445823687,-26.0038602879269 -680.775447644392,-26.2832104964229 -679.814095326273,-26.542101279849 -680.114189255551,-26.1665670920457 -680.409732716208,-25.7982796702704 -679.945290610362,-25.8143803119063 -679.564668879708,-25.7874140692075 -679.199489474765,-25.7535766238091 -678.279204095615,-25.99694316144 -677.39032654978,-26.2230261948466 -677.155656624342,-26.1188373780226 -676.869629141003,-26.0414464271946 -676.59630390166,-25.9582309537834 -676.688174824942,-25.6939096508994 -676.781522642353,-25.4317959519905 -676.640578122624,-25.2889631371023 -676.228911386148,-25.2824364436386 -675.833511485267,-25.2669852870344 -675.718956311151,-25.1142094766953 -675.611828545948,-24.9587022799789 -675.367728943266,-24.8713719061832 -675.274715189619,-24.7105153487039 -675.188439485537,-24.5480403160242 -674.460629787399,-24.7075076993991 -673.758293155956,-24.8534628708749 -673.769059914731,-24.6425880102308 -674.468466600406,-24.0873333461689 -675.151119269101,-23.5465910504959 -674.60778150063,-23.6233308044081 -674.084273346898,-23.6902605181896 -673.783408790796,-23.6440599686808 -673.865123480998,-23.4081478217909 -673.948167385715,-23.1745071931563 -673.386753534343,-23.264466241426 -672.845624040145,-23.3441373200772 -672.42759579383,-23.3608525807974 -671.809806888786,-23.4769500844244 -671.214010530906,-23.5824144472271 -671.218651393176,-23.3863530518129 -671.22687776448,-23.1904726775665 -670.809143808338,-23.2089301834395 -670.092446481557,-23.3763957123057 -669.400632815499,-23.530266996202 -668.814399218808,-23.6293102217685 -668.249248599778,-23.7173182129662 -667.729694181236,-23.7805570244253 -667.14956074831,-23.8745984732524 -666.59036721926,-23.9559369681719 -666.367251569929,-23.8695654390684 -666.154543965603,-23.7787479150506 -666.092716001097,-23.6132984234184 -666.36250103065,-23.2845962422187 -666.628024086581,-22.9597735492912 -666.055411796189,-23.057596248018 -665.503371846525,-23.1442630208047 -665.044792293622,-23.1832558974316 -664.479622583395,-23.2751894479226 -663.934846555625,-23.3567715257875 -663.457715690361,-23.4043151066369 -662.998379500304,-23.4409448065251 -663.022163934059,-23.2369452721456 -662.83097821873,-23.1419599031346 -662.649114100077,-23.0422311981325 -661.34493321405,-23.50431887779 -660.083009771515,-23.9421615957685 -659.29631869837,-24.1370913611695 -658.639679401104,-24.2644933219452 -658.006338747581,-24.3795435755502 -658.002279592242,-24.1792277944465 -658.002228824366,-23.9796667085741 -658.141351349969,-23.7123559726628 -657.730621984734,-23.7218144333341 -657.335815533291,-23.723675932036 -656.891805620459,-23.750473082619 -656.464690372214,-23.7670892211576 -655.981509206955,-23.8129909246924 -654.976799067048,-24.1182241381637 -654.005618230833,-24.4042481020694 -653.576745039622,-24.4177401855703 -653.164428670879,-24.421768865917 -653.179695434435,-24.2128571996864 -653.170555780658,-24.0167071134156 -653.165543673118,-23.8219612563561 -653.455713368783,-23.4798624778852 -653.741079236046,-23.1438576977723 -653.090571109836,-23.279218003 -652.537233687731,-23.3645049502861 -652.003953724816,-23.4391280785454 -652.352050072181,-23.074681955521 -652.693500713882,-22.7152978889887 -651.911554786496,-22.9212873978774 -650.444957384737,-23.4667485486209 -649.025383677037,-23.9839937150921 -648.83990691902,-23.8785500850869 -648.663728873785,-23.7672514291168 -647.786243038364,-24.0097944814475 -646.966045193026,-24.2208954172952 -646.173950766175,-24.4165617357046 -645.429207200858,-24.5862463130739 -644.710404346246,-24.7401687678013 -644.815861433013,-24.4803186101969 -644.894972130386,-24.2375766401433 -644.975645385151,-23.9968721988979 -645.827540617399,-23.3714234065037 -646.658051605345,-22.7629252214452 -646.353056121032,-22.7292333123228 -646.309345214646,-22.5658115176026 -646.270488490201,-22.3999669814092 -645.829894990304,-22.4365564212531 -645.405874031028,-22.4663735239945 -645.152546584975,-22.409298718423 -644.370590393085,-22.6177644398648 -643.615288805253,-22.8087156731551 -642.989266741477,-22.9355818855363 -642.385353116994,-23.0497081391593 -641.698330360973,-23.2040348421197 -641.011964590337,-23.3562235215517 -640.349586739431,-23.4951110100226 -639.696423821457,-23.6294673082262 -639.066289605502,-23.7496019369168 -638.894953177502,-23.6381420473855 -638.701372423424,-23.5404154474904 -638.517259850249,-23.440450603996 -638.468499885346,-23.2719234438817 -638.424890179254,-23.1026023209987 -638.757925176445,-22.7463396460733 -639.276639317915,-22.3010565528545 -639.783571190785,-21.8673738796834 -639.590396282594,-21.7870145051572 -639.406339916964,-21.7029228463328 -639.450264326048,-21.5067736854541 -639.88239635727,-21.1168669251374 -640.305076896912,-20.7366796879135 -639.781992672067,-20.8318964580617 -639.27758887145,-20.9167722149792 -639.041001757525,-20.8675864159222 -639.637969691505,-20.402395729081 -640.220469572283,-19.9485286669113 -639.357622576302,-20.2223240715321 -638.523346544135,-20.4787554668385 -638.687226134116,-20.2326384245731 -638.547433724504,-20.1424729316729 -638.414855166361,-20.0487629810523 -637.905308091636,-20.1445298245797 -637.413900080462,-20.2305561245422 -636.722125496895,-20.415575653579 -636.001799807768,-20.612667183975 -635.305930759793,-20.7961458510503 -635.135911189559,-20.7145324454537 -634.97412634014,-20.6295872784374 -634.14611912105,-20.8782160920932 -633.109450021983,-21.230094342537 -632.106667013075,-21.5607145092838 -631.966473997414,-21.4569687019071 -631.833771497582,-21.3499886691948 -631.104722256299,-21.5437227361945 -630.760038848435,-21.5414209281098 -630.428914680627,-21.5329960759196 -630.144359551605,-21.5014741796905 -629.87156752503,-21.4634055975871 -629.072305485386,-21.6902970938724 -628.513706556555,-21.7953189337594 -627.974992168393,-21.889241008519 -627.583443187379,-21.9077132528587 -627.206891851742,-21.9183155126179 -626.00654176293,-22.3397489917947 -625.274922053013,-22.5233476077345 -624.568461099072,-22.6929168191235 -624.164422005965,-22.7092846487366 -623.775910732551,-22.717894313455 -623.364131850105,-22.739035379358 -623.010106968147,-22.730629312432 -622.670124902927,-22.7147761860511 -621.81555855904,-22.957237082919 -620.989840612942,-23.1817293898582 -620.813625087246,-23.0801936416146 -620.774478051252,-22.910748005503 -620.740122001146,-22.7400993671866 -620.379855338467,-22.7332802544773 -620.033845737654,-22.7207887029094 -619.289880135848,-22.9071186698579 -618.52197052773,-23.1019352105888 -617.780427038189,-23.2822854042357 -617.247883989603,-23.3574110827761 -616.734778311401,-23.4218222053852 -616.30782875235,-23.4418820991865 -616.060326873481,-23.3706647431424 -615.823898022152,-23.2970929694653 -615.667305748956,-23.1838359875076 -615.519029770013,-23.0672681162272 -614.792431625893,-23.240166094704 -613.637954361021,-23.6270818178172 -612.521309161981,-23.9903615391227 -611.592583821729,-24.255698362879 -610.695175068335,-24.5026049356497 -610.422136014032,-24.4351595558816 -610.413121008061,-24.2355720347214 -610.408294713963,-24.0379105988226 -609.918983594603,-24.0822562941911 -609.448006187176,-24.118473099477 -608.992571193661,-24.1460393361346 -608.321330002978,-24.2815403742136 -607.673804364854,-24.4035658439491 -607.416858049817,-24.3286257054066 -607.171426614162,-24.2482885593306 -606.169502796055,-24.5491729192546 -605.20730477149,-24.8267301834127 -604.277500969512,-25.0848927274472 -603.803393604125,-25.1127801336952 -603.347340071906,-25.1310676380076 -603.133404275994,-25.0286590696772 -602.685912179887,-25.0429481089385 -602.255691637883,-25.0502204826062 -602.683097022811,-24.6272375629036 -603.101871832501,-24.2135642441904 -602.554625175015,-24.2856782419175 -601.905553728174,-24.4082233154394 -601.279577519247,-24.5177974094658 -600.549214608095,-24.6795506633773 -599.844380950081,-24.8264266323145 -599.416918598951,-24.8337158659038 -599.107449386934,-24.7819234021535 -598.811109671779,-24.7246064791793 -598.184461593439,-24.8318102779629 -597.580324329411,-24.927012840947 -597.061455384134,-24.9789861951048 -596.693729357996,-24.9541903725181 -596.34089831166,-24.9228402840649 -596.907694711105,-24.4330217015657 -597.461679325571,-23.9543296405013 -597.056864656317,-23.9579903397719 -597.016542166192,-23.7797258939358 -596.981226211915,-23.6013889332562 -596.591045079074,-23.6032389876109 -596.216127367097,-23.5957551225287 -594.980611156131,-24.0189900721226 -593.423110385173,-24.5984595587401 -591.915544124706,-25.1479841754727 -591.663803632834,-25.063976145583 -591.423548147231,-24.9749934026418 -591.235998931296,-24.8615814687139 -590.916102025209,-24.8143504230055 -590.609655833733,-24.7601888788802 -590.395052847802,-24.6605912544648 -590.190778276047,-24.557876260436 -588.637141081971,-25.1308612957104 -587.038090904745,-25.7203671576579 -585.490411529924,-26.2792413661134 -585.090464116837,-26.2575314172286 -584.706615784032,-26.2289297713208 -584.384456098789,-26.1694839704956 -583.584712100325,-26.3505580713788 -582.812846516345,-26.5150870224171 -582.599995705896,-26.3988112646018 -582.397725090663,-26.2771751487369 -582.840542520581,-25.8337546860374 -583.447242565427,-25.3143146396463 -584.040135406709,-24.8074094927452 -583.977774299336,-24.6318408269799 -583.921232058664,-24.4562329566062 -583.535296218933,-24.4465435797047 -583.422401737414,-24.3003988879141 -583.316742126925,-24.1511814507205 -582.924815910074,-24.1470617355981 -582.548336252598,-24.1351859257651 -582.595610400212,-23.9122087483711 -582.541880557079,-23.7409419166991 -582.493548486272,-23.5698545288463 -582.160654454806,-23.5430623172569 -581.841328005621,-23.5088815006074 -581.20789413497,-23.6310880970657 -580.66150404517,-23.7087175927268 -580.135046154285,-23.7763535940141 -578.902270139401,-24.1959765918494 -577.709767781601,-24.5921324858713 -576.953992577413,-24.7659393477903 -575.957913740124,-25.058106185475 -574.995276854723,-25.3303981028531 -575.013317542822,-25.1089059310801 -575.034907006605,-24.8887338200172 -575.393791180501,-24.50162257352 -575.480007959363,-24.2549858566274 -575.567583507409,-24.0099125809839 -575.121004953799,-24.0343775305882 -574.691466596089,-24.0489370444978 -574.276968608233,-24.057641924421 -573.948615895048,-24.0222639284102 -573.633817682147,-23.9802892222284 -573.087053233484,-24.0545268062777 -572.560300840618,-24.1192272870239 -572.612796434797,-23.8932195566669 -572.935632271649,-23.5345633529047 -573.252701607503,-23.1825788663582 -572.775540427068,-23.2307969718439 -572.316162148963,-23.2699754748745 -571.399304216924,-23.5362092427185 -570.567357101936,-23.7581869183986 -569.763765088088,-23.9635139200578 -568.857598740084,-24.2178967930293 -567.982074931593,-24.4553390456094 -567.687035252622,-24.4002979397973 -567.319056324998,-24.3821091912682 -566.965855333199,-24.3564019120921 -566.474291156253,-24.3999058485172 -566.001165208521,-24.4332904900516 -565.56136083864,-24.451110694324 -565.662668787101,-24.1974012152218 -565.764879689986,-23.9449077507777 -565.922671389796,-23.6672358910379 -566.07961177699,-23.3940094672871 -565.4120313774,-23.5352920862656 -564.846021950007,-23.625068724447 -564.300480577112,-23.7019996738324 -563.940775220191,-23.6856737726484 -563.595487596943,-23.6634486977893 -563.169053299138,-23.6813025624773 -562.802573958158,-23.6696027249338 -562.450689064704,-23.6509294541231 -561.954164258816,-23.7033614269211 -561.476100628632,-23.7472163057108 -561.188214220396,-23.6954788920614 -560.519521212211,-23.8347159024688 -559.874372052849,-23.9597844385433 -559.104754980917,-24.1467193241964 -558.361722429401,-24.3181426435804 -557.933042544187,-24.3314238818361 -557.710557733046,-24.2408446102679 -557.498537086939,-24.1455889445928 -557.160699754086,-24.1157009942944 -556.836683317069,-24.0787937098948 -556.702618372854,-23.9458688363409 -556.217864754799,-23.9898877937125 -555.751272427946,-24.0245302535564 -555.580007941272,-23.9119900894592 -555.417621270945,-23.7960844351917 -555.024273718573,-23.7963751554119 -554.614502709116,-23.804812273453 -554.220636662316,-23.8051923665614 -553.875525938006,-23.7814260776997 -553.544403666,-23.7505987995679 -553.195960245852,-23.7293769027446 -552.954469353379,-23.6553650133244 -552.723869497347,-23.5752140117332 -552.275092565327,-23.605647047316 -551.843327345892,-23.626351693362 -551.058728093548,-23.8235339763715 -549.819899727467,-24.2453819050556 -548.621539576846,-24.6435243339179 -548.518725360896,-24.4913901047836 -548.422865863327,-24.335770016068 -547.473102139454,-24.6081266650346 -546.820101512271,-24.7302518464922 -546.190358254412,-24.8385791009784 -545.642111302064,-24.905814480981 -545.114069087327,-24.9614720021957 -544.830252808003,-24.8955962854161 -544.25032210574,-24.9779787815395 -543.691547394422,-25.0485014502791 -543.549470372128,-24.9099126958552 -543.41562727257,-24.7701376625398 -543.09764844325,-24.722951604307 -542.863998005921,-24.6335834547103 -542.64122626426,-24.5405450824755 -542.410965777896,-24.4523955185612 -542.191427651393,-24.3592886701542 -541.68970365465,-24.4079094070218 -540.778069650003,-24.6617769291191 -539.897302474131,-24.8970763697038 -539.814082021467,-24.7311904761952 -539.737312266539,-24.5654460682872 -539.263737282746,-24.5982245624178 -539.028016969253,-24.5125393057536 -538.803185741369,-24.4214924991703 -538.482954823493,-24.3801904757879 -538.176073785888,-24.331853030832 -538.711670915394,-23.8628570561871 -539.166998484656,-23.4386399155067 -539.612624368602,-23.023634222383 -539.879290918418,-22.7006293149034 -540.141708292271,-22.384118584766 -539.690790681618,-22.4276494384402 -539.106534366434,-22.5376400515013 -538.543073137035,-22.6361648622165 -537.742977312979,-22.8511278647242 -536.970122496051,-23.0508503187685 -536.563510996426,-23.0656822050238 -535.965191348887,-23.1766857432405 -535.388198745106,-23.2743271478293 -534.934619722151,-23.3094065221975 -534.49815141826,-23.3370754141391 -534.309338891656,-23.2399994897856 -534.766382402861,-22.8218690567079 -535.213539985837,-22.4116827973113 -535.371022188279,-22.1508660691444 -535.527341328607,-21.8935278158434 -535.415296117784,-21.772414790316 -534.93385668222,-21.8373546029294 -534.470046578024,-21.8924918286065 -533.584735556417,-22.1587918126021 -532.729020341795,-22.4078573322594 -532.363129433638,-22.4094095608088 -532.123316176189,-22.3487049364215 -531.894072465481,-22.2824445366712 -531.159732102604,-22.4701799409944 -530.450577680583,-22.6425669855536 -530.564432067251,-22.4017064685287 -530.496960451005,-22.2541741478806 -530.434969343259,-22.1042770549502 -530.358285892498,-21.9627447194249 -530.287328851012,-21.8215201169681 -529.990568500845,-21.7939851906712 -529.689484699209,-21.7701608954682 -529.400664172384,-21.7391177267418 -529.177308814599,-21.6755612815588 -528.963932490642,-21.6070211799518 -528.114968847551,-21.8573934249845 -527.297447476363,-22.0897456024681 -526.507516219681,-22.3056179021141 -526.181344732481,-22.2878776125856 -525.868303297198,-22.2640971589907 -525.462481405148,-22.2861832623196 -524.760890826238,-22.4571943921155 -524.083523442106,-22.6139897390637 -523.224341760855,-22.8594718752596 -522.394131388868,-23.088806541022 -521.62471537666,-23.2847848177846 -520.934023380442,-23.4393769643694 -520.267442750366,-23.5796543331175 -519.592263562047,-23.7236883279491 -518.940790367257,-23.85351408823 -518.650310970262,-23.8011803688419 -518.649551684307,-23.6061249253724 -518.652570316596,-23.41093972362 -518.87260526786,-23.1090709384609 -519.089813316894,-22.8110664442208 -518.148641428978,-23.0956854015439 -516.963756274012,-23.499338664226 -515.817573850588,-23.8798790502795 -515.128055407489,-24.0277868771196 -514.462730760168,-24.1622642280396 -513.976603210828,-24.2065191256151 -513.50887028898,-24.2403718468848 -513.058826630568,-24.2649019199358 -512.810141281423,-24.1897587666462 -512.572650800934,-24.1086377160367 -512.591855888831,-23.8995337043192 -512.406976313076,-23.7948979184332 -512.231356511261,-23.6869735622199 -511.861992152829,-23.6763285254387 -511.507315094385,-23.6591841501251 -511.309873468847,-23.5627762008722 -510.91305542859,-23.5670630350982 -510.531714217129,-23.5641962817025 -509.981935338243,-23.6455905354315 -509.452149189578,-23.7158196874027 -509.391186897325,-23.5506200133273 -508.870165686624,-22.3668041298999 -508.392321647234,-21.3938396295586 -507.713684028197,-20.7003681584925 -507.074981346347,-20.1251761823384 -506.450995981964,-19.6541403910146 -505.724215752759,-19.1066063884348 -505.036453823211,-18.6506025153499 -505.290578509437,-17.8120417111741 -505.550852604994,-17.0504406727013 -505.291239469595,-16.6145761779781 -505.080032191225,-16.2097086673088 -504.884886187173,-15.8434949649782 -505.10230510247,-15.3104961018302 -505.321441039819,-14.8133318161711 -505.417163485227,-14.4102107537984 -505.576239427214,-14.002320830864 -505.736915946017,-13.6188647581997 -505.249605101948,-13.5815662601302 -504.782118397799,-13.5520396919533 -504.214027915226,-13.5871194966381 -503.398473330168,-13.7572182688994 -502.611627991173,-13.924213094729 -502.177991118864,-13.9232103924232 -501.761376381507,-13.9242489931545 -501.666536938132,-13.7722760159867 -501.389862589852,-13.7195252126166 -501.125050269702,-13.6690342164755 -500.789452713121,-13.6606280427816 -500.467175441368,-13.6513604313118 -501.023551096375,-13.207958336695 -501.512991601771,-12.8091361494157 -501.990904871956,-12.4230302274209 -502.242743873243,-12.1575947747005 -502.489808842342,-11.9011143334589 -502.205456935278,-11.9160515878199 -502.239244098896,-11.7754437079733 -502.274408363642,-11.6381454162843 -502.25406955607,-11.5325253307618 -502.23655780613,-11.4285461218057 -501.68421009173,-11.5956898278104 -500.849253144054,-11.9043464941186 -500.041103706532,-12.1989614616145 -499.932483201005,-12.1427205208127 -499.829202411608,-12.0854821682049 -499.761482286053,-12.0124415855457 -499.614925869133,-11.9835827842533 -499.474670462647,-11.9510863219555 -498.928888676621,-12.1232930125382 -498.401197861354,-12.2861647789706 -498.559873225472,-12.1047292129751 -498.848019081933,-11.8617920979271 -499.129534993715,-11.6259162472177 -499.679620329543,-11.2584701767899 -500.215197633954,-10.9027301204258 -499.712669708358,-11.0703850418291 -499.236866314528,-11.2242905160789 -498.776761716815,-11.3692584214898 -498.8325805924,-11.2557167119371 -498.888392609283,-11.1431756294856 -499.234055601064,-10.8892753129429 -499.859267535865,-10.4980677292057 -500.467482327812,-10.1186302345239 -499.976535814725,-10.2940721117262 -499.50146801901,-10.4604944726707 -499.390109450531,-10.4428709425497 -499.370884271481,-10.3814399754424 -499.353593355446,-10.3184460784272 -498.707542065989,-10.570842283854 -498.081972400728,-10.8108220850259 -497.682951382958,-10.9354517040262 -497.368006794084,-11.0176827906409 -497.06383102121,-11.0939380695996 -497.25713218797,-10.9208279141462 -497.446180481778,-10.7532167891644 -497.226493648191,-10.7910177166012 -497.331902888855,-10.6660570191866 -497.435580261558,-10.5425930714867 -497.423353379557,-10.4787167102541 -497.412833348109,-10.4150121638649 -497.499307807414,-10.3032756505501 -497.145617728765,-10.4141155838513 -496.803665931762,-10.5169003720203 -496.90647124027,-10.3968628613863 -497.007552177808,-10.2783231700301 -497.063381810031,-10.1829079790451 -497.008910466029,-10.1457485417588 -496.957288987461,-10.1078718026745 -496.010781450553,-10.5187578350454 -495.093490894303,-10.9093342320866 -494.48922558909,-11.1402834587658 -493.635237386875,-11.4933019402667 -492.807950460949,-11.8299441837039 -492.76674692724,-11.7709405056706 -492.728292783777,-11.7109489868567 -493.057647959281,-11.4682527971369 -493.389683096209,-11.2261960738129 -493.713350475834,-10.9899949767655 -493.872865515516,-10.8395555483658 -494.029016797405,-10.6921311208088 -494.412212666842,-10.4335952382857 -494.703498725865,-10.2233056386148 -494.987404364939,-10.0179662245148 -495.552480109651,-9.67451380189323 -496.10199899303,-9.34365182616265 -496.050084074574,-9.31620256233863 -496.084872782171,-9.24464811335991 -496.11967240341,-9.17430608726421 -495.932232125272,-9.2167751455543 -495.751325288513,-9.25518156532534 -495.821258897169,-9.16855761930953 -496.146885663216,-8.95452462365264 -496.463857445282,-8.74711490676532 -496.429653343111,-8.71759565718288 -496.397357617106,-8.68686432445813 -496.670706852689,-8.50412233208117 -496.992407477437,-8.29942618903254 -497.305427646784,-8.10067666096763 -497.651641316411,-7.88688637658422 -497.988388127316,-7.68037122273536 -497.460589612467,-7.9088821808921 -496.432756589381,-8.38460929253007 -495.436083339474,-8.84070381717511 -495.056753721771,-8.98132612342132 -494.689595417829,-9.11612610218042 -494.564448454242,-9.12763450432612 -494.064584789343,-9.32839545704716 -493.580462956295,-9.51761635398885 -493.500804674029,-9.5045136270564 -493.424521566067,-9.48891161189037 -492.843334560751,-9.72656024501974 -492.081108559777,-10.0514897376968 -491.342525598927,-10.3619894170775 -490.947211161201,-10.4978223634909 -490.564786832145,-10.6258372651023 -490.433342648355,-10.6277685506945 -490.624426341067,-10.4678072115237 -490.811091442764,-10.3113619996427 -490.639698874974,-10.3342979007718 -490.474585864389,-10.3546752545242 -490.331487919729,-10.3634441984811 -490.778079509695,-10.0779693210209 -491.212645907594,-9.80184538428024 -491.918229053329,-9.39235344750247 -492.60401505593,-8.99848220028925 -492.484766923151,-9.00950859893791 -492.926741742679,-8.74015304343504 -493.356562647649,-8.47942083922208 -493.126154160889,-8.55157468407659 -492.903393478577,-8.61890326275721 -492.989352346782,-8.53098134264792 -493.041844869526,-8.46172078949842 -493.093610061682,-8.39199546183711 -493.393503054212,-8.20053079395946 -493.685316413462,-8.01486075402306 -492.93529417157,-8.35150665842843 -493.121205941374,-8.21710485210733 -493.302410763936,-8.08665881092571 -493.489349924711,-7.95403766667596 -493.671507637477,-7.82468824643683 -493.768967321288,-7.73955529906307 -493.791544376824,-7.6913756653545 -493.814161998093,-7.64467670719647 -493.578750552886,-7.72874140311684 -493.350954201177,-7.80808673281769 -493.060476947792,-7.91755635372624 -492.882688299597,-7.96886714751206 -492.710884752105,-8.01698969065548 -492.546198600414,-8.05982886961265 -492.38714659045,-8.10023903029529 -491.353039685941,-8.57888101506305 -490.320195622876,-9.05050267034728 -489.318786705102,-9.50325732661904 -489.537062412472,-9.34134530787067 -489.749890815968,-9.18343742304687 -489.036259560316,-9.49047776636733 -488.637746189279,-9.63798343111565 -488.252024056191,-9.77714923145714 -487.615720413732,-10.0392359551964 -486.999329979929,-10.2905582984343 -486.900569741508,-10.2799023080289 -486.031462492686,-10.6535384457511 -485.189253151975,-11.0106508647229 -485.071457188446,-11.002058619655 -484.95844510214,-10.9907953932196 -484.886604478951,-10.9589987511138 -485.187469805935,-10.7409888861498 -485.480727461722,-10.5293715818729 -485.314565598412,-10.549394777526 -485.154534166773,-10.5659501839237 -485.092549954435,-10.5337352117341 -485.332238092273,-10.3510125305028 -485.566039240107,-10.1730621115746 -485.515293430422,-10.138468585697 -485.467202102223,-10.1028585792848 -485.123752888824,-10.216094915375 -485.405059983732,-10.0157516309893 -485.679186806657,-9.82111588424092 -485.439361327311,-9.88505236049128 -485.207710795266,-9.94442843786463 -485.30514385575,-9.83855928683893 -485.262530293628,-9.80416336685397 -485.222248551058,-9.76938309655248 -485.118181128883,-9.7648711690193 -485.018280882348,-9.75956224010379 -484.350554695896,-10.0382692242747 -483.628258102586,-10.3418369451268 -482.928449404075,-10.6310378431562 -482.457178640253,-10.8021305239309 -482.001098682535,-10.9656569345354 -482.023632827768,-10.8867294225773 -481.892659963776,-10.8862194447765 -481.766832334981,-10.8826337408875 -480.830228192697,-11.2849247305291 -479.922617880393,-11.6694554164436 -479.573410324555,-11.7704977421915 -479.083487954452,-11.9392803668168 -478.609532108031,-12.0992844657126 -478.500623613081,-12.0759047620746 -478.396434671289,-12.0492801392782 -477.927817547906,-12.2043352609758 -477.282994196683,-12.4473213917026 -476.658785144423,-12.677207851971 -476.320909124545,-12.7612857014888 -475.99466557322,-12.8389740389237 -475.139840918986,-13.180952674028 -474.324104753823,-13.4998675340279 -473.534225334048,-13.8019223199793 -473.710763916389,-13.6184358876875 -473.883906273856,-13.4381789809663 -473.81266321665,-13.381459574845 -474.377098059602,-13.0085024496441 -474.92656812744,-12.645946067326 -475.766159550251,-12.1419908645006 -476.582514563437,-11.6536194347458 -476.579828933246,-11.5819923235374 -476.59468589223,-11.5007470269775 -476.610521504534,-11.4204173983662 -477.034784282095,-11.1366330243758 -477.447864894166,-10.8613899922417 -476.882327652658,-11.0779073849683 -476.434612682857,-11.234863919854 -476.001436535727,-11.3825313930805 -475.828012564472,-11.3978344520526 -475.661094472773,-11.4096723600161 -475.47924689645,-11.4296534211854 -475.487398260029,-11.354036605159 -475.496683047025,-11.2791237653557 -475.934323953118,-10.9904034971846 -476.360352985529,-10.7095096610384 -475.999371787862,-10.8245374295442 -476.13130724461,-10.6928251370107 -476.260600479887,-10.5644583670585 -475.90880202402,-10.677518411793 -475.5686250182,-10.7840781752073 -475.403218900779,-10.8013080213611 -475.618345104377,-10.6276011171985 -475.828374144071,-10.4581054690062 -475.959010879477,-10.3313354546197 -476.086961346337,-10.2065522314398 -475.956086937547,-10.2129179228722 -475.44837496239,-10.4069541862003 -474.956841771001,-10.5911408662818 -475.07944690861,-10.4652021755444 -475.199664721433,-10.3433523341707 -475.307542817661,-10.2268662500039 -475.250459123983,-10.1966330687472 -475.1961946322,-10.1633600659384 -475.234743561591,-10.0844896324704 -475.273296549133,-10.0055590305706 -475.503832994842,-9.83273975437169 -475.306655121565,-9.87366276345561 -475.11642220857,-9.91134975632336 -474.561017109959,-10.1326613414648 -474.023136721515,-10.3426615493363 -474.235316651782,-10.1757517252224 -474.069004381345,-10.19956488475 -473.908755612835,-10.2196727543597 -473.660786901272,-10.283360764445 -473.421317206973,-10.3424684398968 -473.597392044485,-10.1946917007425 -473.946508232269,-9.96076899850799 -474.286430614371,-9.7323140317077 -474.414892279918,-9.61369643846929 -474.540596305928,-9.49719997678494 -474.269742776404,-9.58096035249128 -474.173679064225,-9.57429643247438 -474.081510055113,-9.5668429396505 -473.746572117236,-9.6820664729625 -473.42255295667,-9.78893891039197 -473.416887276114,-9.73637389391513 -472.923180792635,-9.9289907415938 -472.445131213921,-10.1115445610847 -471.794076217221,-10.3781475851612 -471.16342604427,-10.6317714099117 -470.564874370059,-10.8677249749919 -469.760057898444,-11.2033797477473 -468.980348341059,-11.5229239342389 -469.568937564981,-11.1555068101538 -470.141508466873,-10.8003474543128 -470.312233468477,-10.6493814013761 -470.725981471236,-10.3773537335804 -471.128733677453,-10.1141078460286 -471.268312386338,-9.98569810374937 -471.404885721294,-9.8599802943387 -471.548646973897,-9.73021330219971 -471.965547520223,-9.4669314373053 -472.371160601412,-9.21135115656656 -471.408566533766,-9.64180875184733 -470.475444115096,-10.0536146456452 -470.285432687363,-10.0896237275261 -470.155725783257,-10.0952776410289 -470.03099603205,-10.098901026834 -469.735938393499,-10.1875251719653 -469.450746957466,-10.2698904989029 -469.15663499548,-10.3566368916487 -469.030019754422,-10.358440963968 -468.908334420184,-10.358371874216 -469.246259598905,-10.1275661060062 -469.575369876132,-9.9039883291743 -468.816141443472,-10.2272320185283 -467.395799988674,-10.8767192141394 -466.018669592101,-11.4993980142519 -465.937659423643,-11.4673425208377 -465.860441629439,-11.4337670694886 -466.181190587376,-11.2022338951131 -466.369678011854,-11.0376549083325 -466.553937376586,-10.8772985129735 -466.775304881589,-10.6998257943571 -466.991402864902,-10.5260564836509 -466.665061601278,-10.6258015046659 -466.791187115773,-10.4987300272396 -466.91480903919,-10.3740051161089 -466.118983491055,-10.7102950392685 -465.347900118834,-11.0302632136427 -465.5710616664,-10.8503970330023 -465.736092925895,-10.7016455051758 -465.897511702696,-10.5564032238122 -465.967150027651,-10.458776780876 -466.035933809789,-10.3609527401252 -465.327312755542,-10.6537346197253 -464.791417311702,-10.8573031761413 -464.272622552541,-11.0510698076345 -464.398014821853,-10.9222402773714 -464.520966032966,-10.7945795068914 -464.220173633732,-10.8792598426486 -463.472645257051,-11.1873034206975 -462.748508104203,-11.4806255565075 -462.53889802878,-11.5124001701142 -462.336896173048,-11.5394389665754 -462.156881799425,-11.5574721664852 -462.268010823884,-11.4280871794435 -462.377268724386,-11.3009926601912 -462.592945993516,-11.1225996088313 -462.803594539581,-10.9486205231674 -462.586159444293,-10.9901821998333 -462.340792079588,-11.0448224866943 -462.103995592799,-11.0943738008661 -462.053391338699,-11.0509840740212 -462.005605041755,-11.0073126486696 -462.210159456535,-10.8369062494537 -462.033051082709,-10.8598835224188 -461.862445587396,-10.87781814885 -461.802580798005,-10.8416911977419 -461.745757510562,-10.8035795988665 -461.881161862894,-10.6696966159807 -462.100870684429,-10.4954374639387 -462.315313269863,-10.324506160287 -462.196010680531,-10.323193150273 -462.081411166765,-10.3200071055362 -461.83260933712,-10.3828913050634 -461.152678949706,-10.6616443837432 -460.494052114773,-10.9273040436168 -460.307292237997,-10.9534057520582 -460.127353635863,-10.975983563592 -460.071901971077,-10.9362306257354 -459.448730245957,-11.179680726392 -458.845314945711,-11.4119117915708 -458.738562605559,-11.3935373757273 -458.636349095291,-11.3728796777315 -458.890225460763,-11.1740221585135 -459.53540195872,-10.7813241315587 -460.162827144953,-10.4037390207061 -460.148375235514,-10.3483573287725 -460.135554187898,-10.293706516393 -459.636877653866,-10.48166797252 -458.848584239981,-10.8130025153373 -458.084832889231,-11.1290224319435 -457.569779713938,-11.3169327120569 -457.071310885964,-11.4950403307347 -456.308847276139,-11.8037900855888 -455.110851897701,-12.3276235315042 -453.949763943066,-12.8279764105769 -454.483830233312,-12.4745885674381 -455.003746457535,-12.1321102813457 -454.833311235389,-12.1393798759427 -454.810580522979,-12.0720966779072 -454.790033980575,-12.0048540623162 -455.04145827647,-11.8022699716555 -455.28691706144,-11.603164143211 -455.421739855934,-11.4615505812195 -455.42642619162,-11.3873703508791 -455.432354209045,-11.3135204688749 -455.753190302616,-11.0821285112221 -456.065892820461,-10.8567771913262 -456.437212664462,-10.6037897852199 -456.823042007849,-10.3468232143183 -457.198680832056,-10.0978191777326 -457.265740705711,-10.0061811037684 -457.33193206611,-9.91526391264466 -456.932695767118,-10.0586829355525 -456.265201660456,-10.3345351768686 -455.618579222612,-10.5960532411845 -455.243285013681,-10.7205175659208 -454.880314379019,-10.8374420935595 -455.312438348004,-10.555363040254 -455.877802134479,-10.2094653607827 -456.427644753098,-9.87466084952204 -456.672541498015,-9.69651658079862 -456.911259045992,-9.52293361787616 -456.452684497405,-9.69887501556606 -456.296387539084,-9.72171972962579 -456.145779992557,-9.74163972516706 -456.26996096321,-9.62395077368345 -456.391534295436,-9.50906585152228 -456.156201595672,-9.57466091220691 -456.001900505292,-9.59853600157885 -455.853190769395,-9.61908274097772 -455.271158229841,-9.85556623158179 -454.707402919969,-10.0815171413338 -454.413854163929,-10.1701839781729 -454.162079554048,-10.2366964224763 -453.918898916634,-10.2987086228018 -454.107951937602,-10.144166345194 -454.29256185842,-9.99284622020799 -454.702337050816,-9.73045953923254 -455.032938848292,-9.51086445497133 -455.354797471192,-9.29685761075063 -455.145918617416,-9.35082088638161 -454.944192939261,-9.40019839394318 -454.457416049582,-9.59204894937054 -453.934754033758,-9.80069426229001 -453.428576267007,-9.99841837162873 -453.057173431856,-10.1265233596828 -452.697871632255,-10.2466647789168 -452.313661129313,-10.3787619239199 -452.469239016373,-10.2406899239774 -452.621369871028,-10.1049386513316 -452.813186530896,-9.94978553581258 -453.000463466294,-9.79863517362128 -453.020920484043,-9.73217355124417 -452.902485230323,-9.73659211782505 -452.788608907169,-9.73822112194915 -452.858248374371,-9.64898930116781 -452.926871944574,-9.56088008703551 -453.069932068412,-9.43672699602424 -453.134578363245,-9.35231346386706 -453.198311955693,-9.26886379740302 -453.132177779415,-9.25029127037499 -453.068993604917,-9.23087843606024 -453.701278554059,-8.86489881784776 -454.541589055782,-8.39890136193495 -455.357905564319,-7.94931641203555 -455.850276279441,-7.66474176981743 -456.328809507903,-7.390903533359 -456.11590461074,-7.46625133396493 -455.738642575991,-7.62240273558285 -455.373172381223,-7.77101717110499 -454.486927520425,-8.17815102706712 -453.627608846632,-8.56786261095144 -453.025416708512,-8.82522706419953 -452.486052459298,-9.04866691129779 -451.963543063566,-9.26236070897533 -451.200148389283,-9.59364955337683 -450.46032037867,-9.90877957220773 -449.328660270912,-10.4164258885076 -448.370339076445,-10.8335596429739 -447.441578020218,-11.2321124176659 -447.336947984284,-11.2149748744897 -447.236749795354,-11.1945534395636 -447.106231417668,-11.1897098309976 -447.725543772338,-10.8101448287538 -448.327866584684,-10.4425300870196 -448.308961298207,-10.3896133756183 -448.291814123533,-10.3360744948788 -448.415405963387,-10.2109988274224 -448.244041701519,-10.237050164702 -448.078896021381,-10.2601534922707 -448.021293052299,-10.2278666498364 -447.966569108606,-10.194027102583 -448.542806138096,-9.84550246460952 -449.572934970979,-9.27253972805115 -450.57368247264,-8.72149636190153 -450.001719601524,-8.9609955502386 -449.447581180143,-9.19084225998142 -449.719509684406,-9.0040193095768 -449.870278433915,-8.88087746667376 -450.017501821986,-8.75993514147232 -449.959739858878,-8.74270741499096 -449.904573782317,-8.72443524439865 -449.786973405955,-8.73779753459708 -449.411458771237,-8.87910523875223 -449.047952694631,-9.01455109239266 -448.543112737629,-9.21883236366813 -448.054142086752,-9.41271915682574 -448.275329296117,-9.24943479246866 -448.821893596587,-8.92630124806404 -449.353236424447,-8.61293071164358 -448.907502878836,-8.79190784711439 -448.475807320921,-8.96165826496441 -448.251894704974,-9.02648154595306 -448.551349317213,-8.82835009762676 -448.842869592559,-8.63582765406587 -448.768337056698,-8.62829304003907 -448.696871719281,-8.62017552143767 -448.638463759372,-8.60504021184432 -448.859458338832,-8.45066268858681 -449.074754226291,-8.3003299042508 -448.410810861029,-8.59139508817783 -447.76730761141,-8.86802713626576 -447.678774391421,-8.86548128604851 -447.881682463932,-8.71737307256232 -448.079480545127,-8.57272383835853 -448.061433049634,-8.53804734163296 -448.044759531684,-8.50314330671855 -447.599515788282,-8.68207944017806 -447.641656188176,-8.61539233947197 -447.683425712442,-8.54838800990711 -447.522269339893,-8.58501455488948 -447.366728087454,-8.61860811534414 -447.526701281285,-8.49339580891918 -447.672582627181,-8.37658450280659 -447.814988600007,-8.26295624209911 -447.718191464887,-8.27071175711027 -447.625040709288,-8.27538352628642 -447.684766925476,-8.2031658006039 -447.206159817727,-8.40241379282367 -446.742490146665,-8.59154150233078 -447.123723085941,-8.35669830572204 -447.494520612305,-8.13031427572746 -446.976042404515,-8.34987975718432 -446.214391256727,-8.68730079373612 -445.476120574085,-9.01067707823408 -445.035757867027,-9.18196355906416 -444.609370339606,-9.34441048403093 -444.468976486246,-9.36221833839516 -444.240008927011,-9.42508417469082 -444.018811150099,-9.48383918947498 -443.782701364104,-9.54937189756716 -443.554590160494,-9.6092694463324 -443.098476914245,-9.78285428959665 -442.762178058182,-9.8949785469521 -442.436910895996,-10.0004723686705 -441.805397637928,-10.2586819804766 -441.193684259739,-10.5038368416367 -441.083264574338,-10.4964764767193 -440.341272196108,-10.804541131167 -439.622453570651,-11.0970832253769 -439.568617857869,-11.0535853913549 -439.517728884846,-11.0101051781555 -439.781031895428,-10.8099832262989 -440.203262857887,-10.5325936334117 -440.61426844132,-10.2638265545096 -440.069198310239,-10.4762793685011 -439.541417884461,-10.6775844850285 -439.646528774889,-10.5598774941921 -439.402417543818,-10.6180320695741 -439.166760407891,-10.6715246873521 -439.262587738612,-10.5585415912793 -439.356828748085,-10.4466650344731 -439.224879391503,-10.4505416560607 -438.434489108105,-10.7832818254822 -437.668696095687,-11.1004030808043 -437.33747253083,-11.196358026967 -437.017392364363,-11.2856205569451 -436.383675188576,-11.5314824034498 -436.323909609796,-11.4875883573095 -436.267330893882,-11.4430760847052 -436.56795759836,-11.2202412561344 -436.861078703554,-11.0044535271649 -436.94714628209,-10.8938740704719 -436.800186535135,-10.8994620793898 -436.658881690081,-10.9035426443115 -436.845111063257,-10.7424242456619 -437.027134416724,-10.5858811173745 -437.048924844317,-10.5102550166536 -437.056513033343,-10.4432373146617 -437.065091488945,-10.3771832141636 -436.591257480834,-10.5516525274924 -436.132649898732,-10.7173042396676 -436.658793586551,-10.389253282448 -437.186283643048,-10.0641366952167 -437.699338232279,-9.7491325031897 -437.752495226062,-9.66824735684552 -437.805122211277,-9.588356875673 -437.347017155858,-9.76330317286335 -437.202592263612,-9.78046248195001 -437.063500530008,-9.79558959752605 -436.986219463111,-9.77937937409221 -436.912280073129,-9.76119789795228 -436.674064458279,-9.82458596029615 -435.77823157019,-10.2155012115639 -434.910012468382,-10.5890424680824 -435.323690089404,-10.3184673690046 -435.726346761276,-10.0551733161694 -435.652767592153,-10.0334742179939 -435.941681556355,-9.83092118014858 -436.223159446021,-9.63432851925061 -435.448456618917,-9.96752740141082 -434.697727144347,-10.2858631497598 -433.990861973529,-10.5787858571632 -433.00678056807,-11.007611811294 -432.053044681685,-11.4160459430401 -432.04565518938,-11.347378185463 -432.039874944485,-11.2793301550589 -431.828306430446,-11.3139650343026 -431.228439784751,-11.5433198109607 -430.647686626572,-11.7615831600587 -430.524156545891,-11.7485487795773 -430.405720535904,-11.7324714773562 -430.113587213019,-11.8022620567462 -429.49395182195,-12.0371390656702 -428.894098935208,-12.2589246457271 -429.037500099151,-12.1068415891153 -429.17820091272,-11.957161250008 -429.294829806396,-11.8218562930777 -429.700609783914,-11.5437185767768 -430.095823800006,-11.2722424526607 -430.322095906579,-11.0891195265214 -430.543014755691,-10.9099064759349 -430.011642815295,-11.1089153898777 -429.522125525884,-11.2843069639957 -429.048431880711,-11.4497640242991 -429.398019422792,-11.2028897255047 -429.738643552737,-10.9621649852891 -429.460644155843,-11.0335848127179 -428.978960540912,-11.2071376010329 -428.51282874621,-11.3715036528533 -428.360960500922,-11.3753519180381 -428.214973049935,-11.3771556741024 -428.449927543623,-11.1872024450531 -429.147737400186,-10.7689687617102 -429.826222883333,-10.3644276452381 -429.729234425175,-10.3518611320746 -429.63629035236,-10.3374113320924 -429.897326206957,-10.145530258095 -430.750156369494,-9.65964126977829 -431.578883875681,-9.19121345485158 -431.326689875864,-9.26831766801446 -431.08290276343,-9.34021197572759 -431.607735227131,-9.02733888856512 -432.178344060818,-8.69454173292244 -432.732974331698,-8.37249885577687 -433.26981082295,-8.06354038166612 -433.791534882877,-7.76425631417504 -433.948630665901,-7.64995037396198 -434.211770631546,-7.48365324244663 -434.467788432782,-7.32231952196641 -434.067266970072,-7.49089047400844 -433.679210696045,-7.65161815330985 -433.259978123011,-7.82729760216226 -432.293410072537,-8.2748749403167 -431.356140521008,-8.70311907678745 -431.486717022718,-8.59300023987974 -431.614289651919,-8.48549582795872 -431.439973701826,-8.52914452884822 -431.562345750364,-8.42406137345824 -431.681938857691,-8.32208814581029 -431.187107112337,-8.52850809721571 -430.707711155473,-8.72501532746894 -430.328235209057,-8.86916011848216 -430.335374454233,-8.81890581420646 -430.343199446915,-8.76829326270063 -429.673280062015,-9.05743233129362 -429.024072123863,-9.33450811977954 -428.68361691163,-9.45233154549122 -428.552054805864,-9.46566439971372 -428.425395038305,-9.476118778572 -428.418982385833,-9.42603958146151 -428.413783484869,-9.37657494310906 -427.800050253872,-9.63088162491997 -426.734891671043,-10.1080747970733 -425.702328222089,-10.5652437195698 -425.790156135327,-10.4561364027686 -425.876636907634,-10.3503797047126 -425.533493676955,-10.4607375097543 -425.311302651109,-10.5088973924236 -425.09689828694,-10.5518074686723 -424.36960848388,-10.8513137356612 -423.665080403068,-11.1360975031182 -423.294965482102,-11.2522700549353 -422.727330029895,-11.4646328565025 -422.177870797096,-11.6665897227795 -422.08718896552,-11.6386538466967 -422.00059957159,-11.6067474443906 -421.674833760411,-11.6946015853301 -420.810592997262,-12.0509593544416 -419.973391345412,-12.3916662364011 -419.623270242405,-12.4856661245167 -419.285071076759,-12.5706900948646 -418.859614731609,-12.6988474281952 -418.728669779737,-12.6786843335102 -418.603246619025,-12.6564561722051 -418.534131197281,-12.6057108826449 -418.468700897134,-12.5533405137367 -418.518192616457,-12.4450981649303 -418.421903288377,-12.41026862904 -418.330058734632,-12.3734235859771 -418.550943617085,-12.1799719985655 -418.766884948211,-11.9932219621545 -418.834745887747,-11.8823413475656 -419.026926913136,-11.7093409448293 -419.214896877242,-11.5396811587445 -419.438441931298,-11.3537968253049 -419.65679371806,-11.1727280218473 -419.481429337201,-11.1898561957443 -419.02747006281,-11.3473183117971 -418.588284734629,-11.4939584234762 -418.590935422242,-11.4197804937791 -418.594907564984,-11.3448343660977 -418.865894249332,-11.1385719106191 -418.920815541773,-11.041105889663 -418.975456262434,-10.946405152291 -419.010051973726,-10.8614458058127 -419.044923751879,-10.7765540814132 -418.669899553604,-10.8974913970273 -418.77439645048,-10.7788339748644 -418.877076129835,-10.6628530987783 -418.843091398869,-10.6154848720376 -418.811349424944,-10.5678396740758 -418.761725821564,-10.5303349880668 -418.493179736606,-10.6023023277717 -418.233780412128,-10.6685230993681 -417.373675681834,-11.0356569428826 -416.540240818411,-11.3834707472407 -416.342668586178,-11.4109818241276 -415.248396224315,-11.8858791589746 -414.187904661639,-12.3395079512485 -414.595905842526,-12.0542781764202 -414.99339024837,-11.778726690961 -414.814567452664,-11.7925577208407 -413.742306115129,-12.2523332639185 -412.703253103619,-12.6918619667349 -412.681764767953,-12.6182045331316 -412.662534374847,-12.5442687641956 -412.618397856208,-12.4845747086325 -412.677126491981,-12.3723007518892 -412.735709816699,-12.2616921249734 -413.19545447796,-11.9514566730454 -413.643134010563,-11.6518759299463 -414.017351794589,-11.3906293182555 -414.265851381264,-11.1941570430743 -414.508382691196,-11.0042934743546 -414.040780070684,-11.1716595706396 -413.588296037978,-11.328420965721 -412.842172914735,-11.6314459159779 -412.313841516242,-11.8232429767292 -411.802540415537,-12.0033196021341 -411.750205532455,-11.9524006607859 -411.700901144244,-11.8997335752836 -411.894048324611,-11.7275678787876 -412.072717766994,-11.5637148617667 -412.247530161838,-11.4029197105633 -412.664606848403,-11.1237032198695 -413.070695359994,-10.8532425822895 -413.673063016194,-10.4863329465945 -414.155965302091,-10.18175527461 -414.625785731936,-9.88756532800177 -414.020774305729,-10.1335366024388 -413.434758794146,-10.3685027540054 -413.480645466284,-10.2840093655586 -413.726009966915,-10.1007633883994 -413.965274963359,-9.92224477833109 -413.955625602151,-9.86906322376179 -413.947376517829,-9.81735324182437 -414.035132360334,-9.71634123341332 -414.42287984593,-9.46873763300233 -414.800181685159,-9.22723764293983 -414.8705189179,-9.14161925635984 -414.939743459277,-9.05799482869097 -415.317182288798,-8.82063053627829 -415.900344945655,-8.4837965399065 -416.46711437643,-8.15763356299411 -416.63403045523,-8.03447707802211 -416.796768318456,-7.91467060653842 -416.730331700722,-7.91131144281452 -416.562559161746,-7.95938483627033 -416.40044120187,-8.0036229653758 -416.429863462088,-7.95153307071674 -416.459133026907,-7.8987526541577 -416.498460531736,-7.84270806297062 -416.878284399995,-7.6165589743778 -417.247561040649,-7.397703646242 -417.089082673774,-7.44527783891509 -416.935904054794,-7.49008331559185 -416.368211218348,-7.74177907300059 -415.638101718398,-8.07168913580993 -414.930280267476,-8.38756118371022 -414.505685529367,-8.55780069836805 -414.094467828383,-8.71951747958587 -413.467404681436,-8.98873500054076 -412.481960596939,-9.43333891317504 -411.526612275932,-9.85885610064234 -411.48069992064,-9.82640104590091 -411.437211435035,-9.79134227614149 -412.189784928047,-9.35973903461566 -412.25713813143,-9.27536737108434 -412.323471690219,-9.19191146696842 -412.300360258429,-9.15349696553761 -412.278893189475,-9.11516140863015 -411.804432717107,-9.30240198705896 -411.597915704064,-9.35467003860269 -411.398491834145,-9.40383147421649 -411.271307299093,-9.41574202319182 -411.148880788784,-9.4243777592108 -411.429881583713,-9.23118873174561 -411.925372591944,-8.93371115596292 -412.407151707283,-8.64540047071434 -412.891213293868,-8.35961834364613 -413.36178639685,-8.08308607036498 -413.498068708592,-7.97662441774991 -413.880880194691,-7.7480325483619 -414.253074248919,-7.5258007851879 -414.015938873037,-7.61112445095187 -413.786461993722,-7.69036982323383 -413.504747915304,-7.7968108578283 -413.577475136289,-7.72583405237154 -413.648714604943,-7.65560279928233 -413.126379620857,-7.88244413398334 -412.620166411812,-8.09978579038061 -413.203597585417,-7.76878714459367 -413.562641750413,-7.55339114466879 -413.911746829096,-7.34585067181327 -414.170744739302,-7.18473880619576 -414.422683255721,-7.02890904416035 -414.162576073389,-7.12927558280226 -414.144394855832,-7.10872723158484 -414.127321375407,-7.08796278164942 -413.674687957365,-7.28524741527598 -413.236011277216,-7.47332203810311 -413.361834822477,-7.37844195239561 -413.806146279194,-7.1241449467797 -414.237922839889,-6.88014338812392 -414.089645702972,-6.92742939427059 -413.946273862272,-6.97202261076528 -413.48471880733,-7.17455951861663 -412.801226239929,-7.48522808716652 -412.138563616081,-7.78415920169876 -412.162775392287,-7.73566167106488 -412.186969745603,-7.68799224751272 -411.724078234454,-7.8854517272711 -411.004015395251,-8.20823570698535 -410.305983609707,-8.51775920694565 -409.907029828053,-8.6746445434032 -409.520704314901,-8.82350981531441 -409.22022187222,-8.92705637170045 -408.733695484261,-9.12387877881604 -408.262463656898,-9.31093162579876 -407.886585483749,-9.447918864036 -407.52281314424,-9.57805996883442 -407.082385320564,-9.74481953077972 -406.322443743191,-10.0700412616451 -405.586050018284,-10.3792552933889 -405.429029121042,-10.396944747521 -405.277825083633,-10.4107542626778 -404.782471076161,-10.596479329233 -404.102586982134,-10.8729433229662 -403.44404861203,-11.1368326089607 -403.94575881026,-10.8170970530672 -404.433940966583,-10.5072942984818 -404.568956884573,-10.3768088881489 -404.784645305279,-10.2094440472738 -404.995092649764,-10.045020837483 -404.714573822826,-10.1274753822766 -404.443469686575,-10.2054593868924 -404.304868196471,-10.215626100056 -404.282104675671,-10.1665656030513 -404.261176447485,-10.1172329796716 -404.606158165605,-9.88609843168545 -404.94205461365,-9.66186717504081 -404.457518772258,-9.85042932878689 -403.823826539415,-10.11154453076 -403.209963790634,-10.3598064407462 -403.496213972902,-10.1563941297573 -403.775149038932,-9.95853165666426 -403.606767797469,-9.98688214743742 -403.785857106043,-9.84066177566962 -403.960734078745,-9.69735024524001 -403.976985449546,-9.63543289574213 -403.993789396896,-9.57356705908458 -403.657890336806,-9.68866548175819 -403.561316757589,-9.68377188897949 -403.468623855028,-9.67679414613457 -403.327991742099,-9.69390754702796 -403.192544955401,-9.70773266434628 -402.455253110052,-10.0226094157198 -401.50561765485,-10.4396565123091 -400.585203435946,-10.8378980063564 -400.456130985236,-10.8358680456669 -400.33215846236,-10.8338174474149 -400.173811817424,-10.8485779721351 -399.799082042695,-10.9712914335444 -399.436687355059,-11.0863791482368 -399.025256074523,-11.225288357452 -398.627287729923,-11.3558910339148 -398.277881694689,-11.4603707462437 -397.875136449124,-11.5910622536562 -397.485671470482,-11.7136120217677 -397.912161444061,-11.4264279422799 -398.327447252037,-11.1475689027915 -398.326883587011,-11.0799706040477 -398.239258621296,-11.0561431691899 -398.155527286768,-11.0309238477058 -397.857360102162,-11.1143105270336 -397.56928168723,-11.1897442750819 -397.607688146018,-11.1011486330613 -397.773137471393,-10.9510247133966 -397.934984293353,-10.8034528275772 -398.294070151114,-10.5595627368964 -398.643762824586,-10.3219643978753 -398.676537491616,-10.2451792449508 -398.588513769164,-10.2292529326635 -398.504247486716,-10.211065743734 -398.057389916622,-10.3746731452823 -397.624909748891,-10.5311623478914 -397.569915072521,-10.4955161664122 -397.879255443708,-10.2807214243421 -398.180594056726,-10.0709632596168 -397.903750869159,-10.1508812081708 -397.636226993484,-10.2262684468404 -398.107525050756,-9.93115784967658 -398.506427793059,-9.67601013931328 -398.894592458387,-9.4286341439967 -398.685115028213,-9.48266509870031 -398.482812943286,-9.53318560462083 -398.429595719421,-9.50695840273959 -398.878748393467,-9.22927836864224 -399.31562567138,-8.96069430409839 -399.038432549658,-9.05258231338356 -398.770342446405,-9.13819145552314 -399.087458851634,-8.93196387557527 -399.018062085024,-8.92019591224522 -398.951612490953,-8.90675716973275 -398.698339580717,-8.98676497083893 -398.453460067087,-9.06137276438469 -398.124747439803,-9.17823860501092 -397.634716885887,-9.37483343774408 -397.160122663658,-9.56172592663448 -397.589687486315,-9.29481632057062 -398.007537988524,-9.03576609283942 -397.488259887641,-9.24771728149233 -397.263093813604,-9.31146988878482 -397.045531425943,-9.37082703763157 -396.891148884214,-9.39732387044604 -396.742310511768,-9.42105840292072 -396.7157121614,-9.38296169712711 -396.77944597164,-9.30105247173174 -396.84225473568,-9.21877763633445 -396.559122356684,-9.31074401864727 -396.285324367961,-9.39778590196944 -396.499077288869,-9.24094619999161 -396.097158510282,-9.3925729923481 -395.708085304633,-9.53715522065047 -396.336612005206,-9.17150353330253 -396.947520514188,-8.81882245666243 -396.814380514361,-8.84130788144731 -396.774278870073,-8.81600087259852 -396.736235902525,-8.7892305210212 -396.322244115451,-8.95198241174129 -395.921357505333,-9.10720998111827 -395.883137958639,-9.07846529522767 -395.507058005427,-9.21954384892478 -395.143013179728,-9.35260218992786 -394.863801454058,-9.44148135715353 -394.59382971347,-9.52494912358609 -395.07765918201,-9.23149176199015 -395.400293192268,-9.02246665118629 -395.714293333738,-8.81833158610072 -395.436243389055,-8.91406561799179 -395.167256154394,-9.00297307620457 -394.790415629067,-9.14484780313079 -394.507826768168,-9.23905981722585 -394.234507834626,-9.32694393593185 -394.118400514773,-9.33497430638118 -394.006691443678,-9.34097861618344 -393.72388997287,-9.43277258972282 -393.534970418034,-9.47712573986903 -393.352606102562,-9.51746281042565 -393.001622533658,-9.64149447786762 -392.662017634622,-9.75717135155299 -392.912133051604,-9.5787916993644 -393.158943701174,-9.40382287423541 -393.39943909106,-9.23302929717373 -393.296152650859,-9.23547743155998 -393.196869020886,-9.23612628117956 -392.745374076477,-9.4124071744239 -392.599820596989,-9.43422389235532 -392.459555032115,-9.45451323142619 -392.148958401971,-9.56025377567169 -391.848508351638,-9.6591002622095 -391.581370341444,-9.73898910904773 -390.783435272846,-10.0836387084279 -390.010164456411,-10.4115059024214 -389.575587961688,-10.5669685585178 -389.155063837155,-10.7160165162147 -389.279365411515,-10.5892381777199 -389.449181766666,-10.4432708276335 -389.615144515695,-10.2986537195362 -390.327621600957,-9.88398210975305 -391.020130763835,-9.48249661528881 -390.625566107493,-9.62899979817821 -390.39283871123,-9.69287897375235 -390.168009048074,-9.75308157472706 -389.711491615949,-9.92752196014969 -389.269522184141,-10.0931010942087 -389.513210392942,-9.9140074206115 -389.823524528747,-9.70385662314597 -390.125709488031,-9.50019996666276 -390.199556505626,-9.4112932852443 -390.272216400692,-9.32480739006615 -390.497236622154,-9.16248477591328 -390.416669143246,-9.15411482216926 -390.339421544139,-9.14334715629588 -389.830814947437,-9.35068385837101 -389.338166633952,-9.54658937146922 -389.096344082401,-9.61621918778435 -388.820438119302,-9.70127504666075 -388.553715990532,-9.78158700811671 -388.475511109754,-9.76506003931397 -388.400690215076,-9.74756238382419 -388.017733799409,-9.88474893594981 -388.393314949294,-9.64259488039825 -388.758822776495,-9.40747974296499 -388.13274264295,-9.67132263584784 -387.526141108892,-9.92212828367074 -387.578227236907,-9.84083094640046 -387.984687563153,-9.58296113519475 -388.38016578751,-9.33337625626791 -388.069971352479,-9.4386627215502 -387.769916452711,-9.5372911563849 -386.933083890658,-9.90429622184064 -385.896186963769,-10.3670491438081 -384.89105451446,-10.8098836180741 -384.500418686472,-10.9409124162973 -384.122581834796,-11.0634328493475 -383.36165105578,-11.3767774274506 -382.625019014228,-11.6751014095814 -381.911537721901,-11.9595155751967 -381.85073261879,-11.9138981116332 -381.793188255058,-11.8670052071786 -382.152537687723,-11.6121239654761 -382.437896193413,-11.396725192979 -382.7162048749,-11.1874756402213 -382.623378471885,-11.1657613961598 -382.534609041345,-11.142812255378 -382.836761918184,-10.9248121501082 -383.311256885586,-10.6228472337288 -383.77294944103,-10.3304650586589 -384.033021638171,-10.1414509057838 -384.286528483636,-9.95622367291833 -383.947684753418,-10.0713794832905 -384.260820626507,-9.85913163861107 -384.565756979425,-9.65277688874402 -384.061465238514,-9.8536874342224 -383.573086079418,-10.0437665006271 -384.04089711392,-9.75339712473292 -384.240823233973,-9.60013266855712 -384.435855366164,-9.45034604922443 -384.427242836891,-9.40432333508963 -384.419852367548,-9.35814608898326 -384.070503079133,-9.48329210282926 -383.446325708105,-9.74396414247797 -382.841613259884,-9.99286904709067 -382.408295228654,-10.1537240867199 -381.988876604388,-10.3062582495834 -381.495587924817,-10.4942870979373 -380.890938725961,-10.7356344820032 -380.305360090586,-10.9652356531987 -379.6568178619,-11.2232416764642 -379.028747129792,-11.4685107068302 -378.969878955822,-11.4283695486511 -379.299879071851,-11.1934920776899 -379.621453268496,-10.9638623025287 -380.23140028792,-10.5928675950683 -380.824560293986,-10.2340771506536 -380.837249409882,-10.1690457200827 -381.160542307727,-9.9492650634853 -381.47538217829,-9.73620112254846 -381.343836726039,-9.74828414372793 -381.217216975555,-9.75790740262947 -381.130623571259,-9.74856489364227 -381.066541690991,-9.72720134910803 -381.005382973776,-9.70474891732131 -380.916610115312,-9.69616986610497 -380.831482886904,-9.6847907938925 -380.783585985184,-9.65446013275572 -380.475031577291,-9.75643279077732 -380.176616076791,-9.85166611918158 -379.611695735821,-10.0801387819414 -379.064535591068,-10.2974740344334 -378.387375670419,-10.5773044338454 -378.015651972527,-10.7015814568044 -377.656115448605,-10.8201644843557 -376.853923977741,-11.1565217410153 -376.076722996246,-11.4775979486792 -375.989200876123,-11.4501841609588 -375.88749635943,-11.4304087752777 -375.790159668623,-11.4092897269242 -375.862381674947,-11.3034487427113 -375.933805681508,-11.1976173382657 -375.661735476198,-11.2661385562138 -375.502520379587,-11.2766475295191 -375.349346155886,-11.28522779253 -375.195859720924,-11.293087571427 -375.048240444899,-11.2978347219596 -375.175112080247,-11.1651167312421 -375.527020258149,-10.9220753587671 -375.869800379217,-10.6856788617198 -376.182675951209,-10.4669364859586 -376.487487007036,-10.2537150445261 -376.212147385839,-10.3325941521965 -376.24091523433,-10.2586595585357 -376.269975810255,-10.1866872740792 -375.883996995939,-10.3226046460355 -375.510540618937,-10.4492970593135 -375.331755168164,-10.4788289076022 -375.520949322992,-10.3234979120033 -375.705709999671,-10.1708371989723 -376.156201046109,-9.88810192748216 -376.594461359377,-9.61408904657285 -376.671964466534,-9.52346943260571 -376.853559304806,-9.38146423589252 -377.030762567618,-9.24326339384529 -376.639111006947,-9.38950728272173 -376.260005879222,-9.52905407238101 -375.975321133244,-9.6203407982952 -376.011378461369,-9.5504995387905 -376.047364040316,-9.48136481720299 -375.960811406867,-9.4736784802995 -375.877800194407,-9.46372757377441 -375.548695871714,-9.57797093448876 -374.626705129205,-9.9853941354643 -373.733036606878,-10.3749864317904 -372.825667782789,-10.7680242992764 -371.94632428034,-11.1440173982249 -371.854304244413,-11.1227019314589 -371.734675278099,-11.1152476726264 -371.619880193584,-11.1052323750252 -371.473072291601,-11.1103790542876 -371.331921818193,-11.112748995224 -370.833328656593,-11.2940403213836 -369.54526586827,-11.8681451868671 -368.296676034094,-12.4174398055994 -368.245436672498,-12.3630522962703 -368.197251501778,-12.3077713466675 -368.783675377695,-11.9355612607339 -369.868796565265,-11.3172098514182 -370.923252355496,-10.7202037883012 -370.890262171597,-10.6729301910617 -370.859473930247,-10.6250695128114 -370.444352314927,-10.7690748856669 -370.447294783855,-10.7026641866784 -370.451398013626,-10.63749139537 -370.353848219016,-10.6237689412891 -370.260387032039,-10.6081327193839 -370.27928367145,-10.5365740162108 -370.357641851554,-10.4358480621552 -370.434863143605,-10.3378048133577 -370.303468770632,-10.3445283726654 -370.177097161976,-10.3479390304877 -370.380948953082,-10.1857378934628 -370.608017971008,-10.0138094022636 -370.829487374602,-9.84638107000191 -370.811801075869,-9.80104694993558 -370.795679386956,-9.75500398272237 -370.639820786055,-9.77892773528714 -371.005012581485,-9.54187684343069 -371.360440358609,-9.31245690086541 -371.081969271224,-9.40236657966896 -370.812689326445,-9.48749581881896 -370.686368868726,-9.49980755405662 -370.346634828793,-9.61911891010038 -370.01792907016,-9.7305700104662 -369.872448520782,-9.74970082322254 -369.732304638256,-9.76548323773279 -369.73041015749,-9.71207326797905 -369.793377630623,-9.6272174669943 -369.855506726386,-9.5430198789212 -369.533190795631,-9.65240553892065 -369.221410913708,-9.75538738797348 -368.612588450964,-10.0055988199768 -368.06254486027,-10.2240317908006 -367.529871070327,-10.4308938568902 -367.776839659059,-10.2467098884839 -368.017663871691,-10.0674549172352 -367.210184918865,-10.4131201293954 -366.067036601619,-10.9237061733318 -364.958899718725,-11.4114507057713 -364.725690436489,-11.4572646107817 -364.500744920727,-11.4986169184734 -364.504128846395,-11.4253677017399 -364.490521832256,-11.3614038596613 -364.478677464556,-11.298138193055 -364.128689780447,-11.4029663174599 -363.790410729116,-11.5017285542176 -363.485636159371,-11.5829681118791 -363.406190855527,-11.5483747667627 -363.330525334574,-11.5139714674271 -363.556917107245,-11.3296544515188 -363.777973875748,-11.1505385206945 -363.98712859615,-10.9772350550114 -363.809615331246,-11.0001419461023 -363.638622173045,-11.0193898140187 -363.74272457749,-10.901162866107 -363.845016960523,-10.7843906823373 -363.497478419194,-10.8923724597424 -362.971839297878,-11.0892907498709 -362.463026501848,-11.276555226522 -362.127227172742,-11.3743499160783 -361.802715305233,-11.4657451343672 -362.040706593931,-11.2749937146328 -361.934475839792,-11.2587631612431 -361.832722268156,-11.2409005676429 -361.588528892047,-11.2943561388878 -361.352883127113,-11.3422541128118 -361.65090009666,-11.1242478918115 -361.699113557454,-11.0326829330404 -361.74719606637,-10.9430449405584 -361.461461966657,-11.02090546548 -361.185435325837,-11.0919558512567 -360.802004460329,-11.216585194347 -361.04165109657,-11.0287163410817 -361.275511257902,-10.844103694146 -361.506995944053,-10.6613818756112 -361.732915280309,-10.4839007733497 -361.67511349396,-10.4509579061368 -361.510276936556,-10.4726486290898 -361.351486802809,-10.4901826837857 -361.132974063197,-10.5379268690745 -360.922111747909,-10.5816558570567 -361.389922016724,-10.2849896799158 -361.730785427359,-10.055491247018 -362.062693607165,-9.83326790161941 -361.798643501396,-9.90998017464809 -361.543472691425,-9.98175624295338 -361.438609419298,-9.97844967079483 -361.679284654495,-9.80208387763326 -361.913912042978,-9.63009906653449 -361.999392132729,-9.53490033273012 -362.08334987495,-9.44165267358783 -361.94911984111,-9.45773795765819 -361.952115943909,-9.40527928664238 -361.956002605171,-9.35330804884579 -362.09500645114,-9.234248022414 -362.230847801227,-9.11853653244001 -361.72206395935,-9.32605276642451 -360.727349205356,-9.77445597004332 -359.763020710642,-10.203238419361 -359.538890032092,-10.2560679990249 -359.322532336875,-10.3051976164141 -359.174882476007,-10.3208298576238 -358.907332997187,-10.395655927796 -358.648836269204,-10.4640562283848 -358.427493703227,-10.5135020691207 -358.213879820168,-10.5588172050231 -357.323723948802,-10.9414177130082 -356.821801522298,-11.1256955363671 -356.336018388066,-11.3009834745394 -356.785776683246,-11.0066559337124 -357.223555731123,-10.7207741701469 -357.678422787266,-10.4312505642428 -358.269004120741,-10.0751903371516 -358.843270789848,-9.73103721101388 -358.614958320502,-9.79168266378598 -358.394432613906,-9.84838131769711 -357.99451393041,-9.99446548509589 -357.538516784353,-10.1660600592002 -357.097101922783,-10.3291976448686 -357.186581984147,-10.2249526308463 -357.274556690939,-10.1237687630446 -357.367373577074,-10.0198963121799 -357.974080919255,-9.66039355690748 -358.563907448491,-9.31336132926503 -358.609631403299,-9.24232701539636 -358.654927506763,-9.17039897177877 -358.310118320734,-9.29468873074263 -358.071286350203,-9.36587982877541 -357.840450968198,-9.43131638024428 -358.118661660345,-9.24105685157519 -358.389619722766,-9.05713922816431 -357.835834185479,-9.28803655901572 -357.484969969904,-9.41533124298914 -357.145417042884,-9.53585541021535 -357.050300861252,-9.53157883219344 -356.9589963554,-9.52516122632849 -356.723512159335,-9.59141201052859 -356.386459879772,-9.70774921028134 -356.060387880697,-9.81788156143553 -356.233208913095,-9.67787879911351 -356.401943911882,-9.540886871815 -356.060155599885,-9.66048459538541 -355.041003048958,-10.1176074261167 -354.053027406759,-10.5542272355562 -354.361428353775,-10.3388938936746 -354.661874726996,-10.1288245108695 -354.216277662981,-10.2947672001711 -354.273415042997,-10.2076877612281 -354.329985372114,-10.1205882867366 -354.741043391688,-9.85832866327694 -355.141023387945,-9.60373492804389 -354.937765779667,-9.65373111423665 -354.964288109234,-9.58690274421193 -354.991054661071,-9.52046097692544 -354.902046467021,-9.51423408148303 -354.816647931959,-9.50631797453897 -355.105287214731,-9.31058428695725 -355.746333092013,-8.94205398967241 -356.36932521658,-8.58507516744903 -356.031765921406,-8.71172554008229 -355.705008610877,-8.83132636393341 -355.404201977014,-8.93814526315743 -355.756691673898,-8.71565461798654 -356.099635613938,-8.50180375365064 -355.98826472936,-8.51675253337456 -355.88097343551,-8.52969143274868 -355.592528281452,-8.63286575446776 -355.691253841092,-8.54124214937578 -355.787869000418,-8.45303054082131 -354.838200265682,-8.88829148934057 -353.917404078366,-9.30531876421081 -353.62000314694,-9.40667816499438 -353.393637121869,-9.46933849326701 -353.174942822174,-9.52934700811737 -352.91913236522,-9.60570611483131 -352.671884914464,-9.67872130494699 -352.785986504072,-9.56928476039521 -352.467931991307,-9.67778955991294 -352.160263363956,-9.77956907816258 -352.011925230517,-9.80076251653614 -351.868996174569,-9.81978235217522 -351.501306631852,-9.95079134337278 -351.513356721234,-9.88933875262945 -351.526115188361,-9.8284504194008 -351.342389401063,-9.86558179434419 -351.165153978117,-9.8992374387854 -350.860531554689,-9.99611618331658 -350.599933156975,-10.0705149196852 -350.348123170322,-10.1400761596834 -350.266105449159,-10.1236598019362 -350.187619089784,-10.1064849833286 -350.025857147524,-10.1304910097613 -349.837316754734,-10.1692393876497 -349.655424434587,-10.2031461767938 -349.212494250835,-10.3679032197247 -348.783765385661,-10.5233039253795 -348.795396682535,-10.4565132760993 -348.634390205034,-10.4762083998665 -348.479318321102,-10.493660236649 -348.366674769419,-10.4899553886099 -348.258519154051,-10.4835851896074 -348.202401897723,-10.4513824729683 -348.377253530075,-10.3048378756792 -348.548065215755,-10.1600085868586 -347.780430014665,-10.4861120341035 -347.036627389527,-10.7978518105116 -346.852716442267,-10.8261828112294 -346.199855190075,-11.0875595978079 -345.56757001111,-11.3365233763942 -345.625209473912,-11.2385973276244 -345.682470625493,-11.1417965893171 -345.322609953437,-11.2541304668991 -344.666487614716,-11.5132537779998 -344.031112518502,-11.7593343593733 -344.270248637844,-11.5663970770041 -344.503715693531,-11.3786099667474 -344.201126153947,-11.4602038734314 -343.721639214724,-11.6289145637528 -343.257711009045,-11.7885790050265 -343.234398225594,-11.7262988464408 -343.213196297696,-11.6645536381805 -343.308907505619,-11.5433462932014 -343.000077920648,-11.6261789088414 -342.701765823999,-11.7038409692068 -342.776870073241,-11.5932549779969 -342.851154489319,-11.4842918632605 -342.804042965454,-11.4373402352653 -343.092406165398,-11.2229276793967 -343.373582776374,-11.0139532390798 -343.004763701822,-11.131890555731 -342.64813973373,-11.2432638130756 -342.288021863384,-11.3545038370314 -341.907847685955,-11.4762496243116 -341.540240664849,-11.5908271482367 -341.292630489901,-11.6436713207019 -341.053713647056,-11.6918747954075 -341.021474706754,-11.636476846086 -341.675940808591,-11.2361745951527 -342.312437475334,-10.8507862211723 -342.279391252968,-10.8036205247678 -342.248547097012,-10.7550859604769 -342.13488514557,-10.7477694365954 -342.454200246064,-10.5249148584451 -342.765277356258,-10.3075030769952 -342.122274326809,-10.5705796685071 -341.499428167343,-10.8205678662301 -341.712143344152,-10.6495143745226 -342.058760544575,-10.414350050441 -342.39630578317,-10.1858623034332 -342.249316867364,-10.2016897196457 -342.107787238749,-10.214684791505 -341.830191487039,-10.2961030260019 -341.194788100229,-10.5546163935319 -340.579331288027,-10.8012722141162 -340.042620440746,-11.0061881172414 -339.523016359701,-11.1997447937716 -339.589620254182,-11.0990927210834 -339.823747655125,-10.9159208473342 -340.052214733709,-10.7361211954968 -340.550406116503,-10.4231193629786 -341.03507803597,-10.1209322535326 -341.309494076108,-9.9274832045377 -341.882603219535,-9.58513473033708 -342.439819299453,-9.25420348042525 -341.82686484646,-9.51198874797107 -341.232990738192,-9.75900073535434 -341.411991758345,-9.61633804367417 -341.648337122731,-9.44677744343156 -341.878673647056,-9.28170735604734 -341.183062342946,-9.58090920403789 -340.508976499318,-9.86563162924899 -340.571448201213,-9.77976102212319 -340.492936232337,-9.76542619500804 -340.4177781667,-9.74970713602448 -340.499269754011,-9.65579617807934 -340.579370637011,-9.56354793551376 -340.332706426716,-9.63636337488178 -340.263274551295,-9.61848520188938 -340.196908637605,-9.59978502733252 -340.495142928276,-9.39876605180705 -340.785546216915,-9.20352447341142 -341.041204591642,-9.02734190416857 -341.5638219333,-8.72079219966668 -342.071838088919,-8.42402315114636 -341.889468329036,-8.47611271572172 -341.713248330174,-8.52304970777507 -341.348220191601,-8.66497471957739 -341.790711217904,-8.40119448053394 -342.220920955049,-8.14635315448584 -342.321165469445,-8.05894679647713 -342.419158987649,-7.97352721989698 -342.49515442779,-7.90119637602842 -342.615976208767,-7.80575430386113 -342.733894573257,-7.71346555781346 -342.592824401445,-7.75141653166931 -342.45655632145,-7.78670795306026 -342.133327380695,-7.91570043544996 -341.632575274328,-8.13097727646252 -341.147320901102,-8.33674667762836 -340.763030398339,-8.49068881500075 -340.390849774011,-8.63642810585137 -339.737221212577,-8.92079983949953 -339.034168804667,-9.22721973799707 -338.352794921699,-9.51989490356841 -338.316864814065,-9.48677328115896 -338.282979981615,-9.4545449046403 -337.884484853035,-9.60376586708516 -338.190277764949,-9.39905081099877 -338.488014325045,-9.20064474271894 -337.527342346595,-9.63403355395718 -336.596010326493,-10.0468977833445 -336.319680828202,-10.1289046679513 -336.250039794482,-10.1061830571018 -336.183565994112,-10.0820648073232 -335.772815632322,-10.2304395551619 -335.375319619786,-10.3712791072319 -335.695491846943,-10.1515763745541 -335.90342916407,-9.98998264073279 -336.106318428683,-9.83331355083787 -336.195802012772,-9.73363855598158 -336.283692287581,-9.63629723732806 -336.13982722363,-9.65531713727908 -335.941995046276,-9.70268095620217 -335.751009719091,-9.74495069986849 -335.593045255779,-9.77018385468819 -335.440789691196,-9.79241102937397 -335.667506241219,-9.62632836124393 -335.861170258087,-9.47897832268214 -336.050072173384,-9.33478038394797 -336.351975191419,-9.1349586031576 -336.645880351856,-8.94236179886335 -336.861774367756,-8.78908632564888 -336.722515971182,-8.81511176912767 -336.588217785486,-8.8388374625439 -335.806194985346,-9.18510114707685 -335.048181502651,-9.51713337363443 -334.769956307127,-9.60487360388771 -334.572112753541,-9.65252056613794 -334.38111105536,-9.69583643021723 -334.426298124489,-9.61966361875403 -334.471177133868,-9.54513057724974 -334.184565675253,-9.63827006592651 -333.551683687763,-9.90375242224209 -332.938515496307,-10.1564079371851 -332.363721037241,-10.3868306474532 -331.80703646605,-10.6055921717015 -331.619071202761,-10.6382837846544 -331.639354018618,-10.5662397868712 -331.660225930049,-10.4950067785331 -331.338611194704,-10.5944741968548 -331.02769560134,-10.6884325531707 -330.437971148819,-10.9214943472667 -330.172853059713,-10.9897002469859 -329.916819598728,-11.0533798435862 -329.542547772739,-11.1755811408344 -329.180602919354,-11.2896206966476 -329.039511172205,-11.2920130573832 -328.919311312031,-11.283394908037 -328.803990083449,-11.2722482105832 -328.833629247986,-11.1894013793921 -328.863698231514,-11.1063072845783 -328.746267606678,-11.0977665338519 -328.806860859509,-11.0003727242445 -328.866949755844,-10.9042265625507 -328.897073075838,-10.8248416843722 -328.927540706922,-10.7467237970589 -328.887413738906,-10.7039653697564 -328.699060696948,-10.7357469777305 -328.51748225369,-10.7627699252799 -327.594787120782,-11.1604007163501 -326.700629996154,-11.5398735758771 -327.040422579771,-11.2985930108198 -327.145134641007,-11.1772455244294 -327.248072739884,-11.0576566697687 -327.292653791159,-10.9684335278577 -327.337201317158,-10.8800808617077 -327.317696777643,-10.8265902879878 -326.979879864175,-10.9318542000283 -326.653285994529,-11.0306940801177 -325.925982040854,-11.3279830854099 -325.221482970731,-11.6104362943065 -325.067267344802,-11.6167122887399 -324.878484227641,-11.63939581647 -324.696667399299,-11.6584137242851 -324.554097104593,-11.6578845854415 -324.417127147615,-11.6541285918 -324.142778701604,-11.7183558242015 -323.668840519374,-11.8832437181254 -323.210316962465,-12.0390074310707 -323.21101647524,-11.9632097722152 -323.213145072949,-11.8877059784872 -323.544240277099,-11.6481669802877 -323.694033113628,-11.5013048714855 -323.840774658113,-11.3576285669721 -324.067680364139,-11.1756277211254 -324.289186407649,-10.9976047245476 -324.103764070649,-11.0261496930199 -324.06208672733,-10.9812859402075 -324.022905642296,-10.9361416276157 -324.93996733973,-10.4139041024678 -325.831106333719,-9.90959627938498 -325.859274925844,-9.84081047109908 -325.283207903929,-10.0758011277931 -324.725212890225,-10.3000522206644 -324.881746180542,-10.1638984274898 -325.034758117289,-10.0321087848127 -325.111662618983,-9.93853995776244 -325.381213361306,-9.74816633944308 -325.64385322217,-9.56327993352729 -325.796927571063,-9.435400003734 -325.946457202287,-9.31029871124959 -325.635407349911,-9.41800179449618 -325.374402640255,-9.50036141687338 -325.122049298313,-9.57626139115288 -324.578087109781,-9.79756028970442 -324.051201199607,-10.0089241862154 -324.458419050717,-9.75104571022346 -325.301238907373,-9.27827435855391 -326.120096545073,-8.82124055809164 -325.326586018826,-9.17368922573846 -324.55741639344,-9.51251682588847 -324.511876900948,-9.48537687345425 -324.680918095909,-9.35002163954535 -324.845932158399,-9.21917274275445 -324.31620866664,-9.43815391323304 -323.803047692077,-9.64660710430257 -322.94608353348,-10.0240750772182 -322.072709077769,-10.4064116732182 -321.226232660732,-10.7715330360151 -321.225537109169,-10.7083513700191 -321.226082916485,-10.6462721162818 -320.94408172438,-10.7250878820348 -320.437865768114,-10.9148886293854 -319.947851325669,-11.0956097658026 -319.411104645432,-11.2992945968973 -318.891489792473,-11.4917055089502 -318.496401753636,-11.6194964857315 -318.549088197283,-11.5212528652862 -318.60159663959,-11.4262958154188 -318.525977071324,-11.3949999368578 -318.4539239157,-11.3630645214135 -318.603809300499,-11.2208162144065 -318.827319918529,-11.0414170972778 -319.04551400087,-10.8663285445272 -318.544604370479,-11.0533068620966 -318.059742428545,-11.2303794629429 -318.122293111058,-11.132149649263 -318.180304185753,-11.0370585664978 -318.23786790221,-10.942862846342 -317.869610243976,-11.0636084207174 -317.513471716189,-11.1755883465397 -317.581632961486,-11.0753780225226 -316.560094573723,-11.5221499422929 -315.570025544212,-11.9470700472217 -315.214634218999,-12.0508350428459 -314.871183831773,-12.1477599982731 -314.926826062291,-12.0429400497873 -315.003011471037,-11.928951524859 -315.078400036854,-11.8172348037092 -315.193862017316,-11.6872945386232 -315.307293649074,-11.5586069359394 -314.959644357531,-11.6614399746549 -314.755770368681,-11.6912787034816 -314.559316887603,-11.7175634028578 -314.347139180528,-11.7519979029657 -314.142619257925,-11.7817687233763 -314.167521878006,-11.6957400446051 -313.920894274098,-11.7457456196227 -313.682976021688,-11.7912793144602 -314.262744992719,-11.4289012609856 -314.826744653352,-11.0766375276446 -315.186986225012,-10.829655870758 -315.519935974804,-10.601048878205 -315.844223658039,-10.3787693490031 -315.201365614945,-10.6415213153567 -314.578664994865,-10.8926396176068 -313.984950877721,-11.1246493489485 -313.429010725765,-11.3364334507502 -312.890799341606,-11.5370318907556 -312.939272195601,-11.4431728325489 -312.987648009892,-11.3506879808975 -313.388929794261,-11.0831177991898 -313.432130803374,-10.9968033732926 -313.475296505243,-10.9101338251947 -312.653057389354,-11.2571016996345 -311.856390937874,-11.587509860239 -311.433864489777,-11.7278621564361 -310.766660517424,-11.9893622141913 -310.120592626457,-12.237034592333 -310.767832533554,-11.8348964402704 -311.39742162239,-11.4467146096078 -312.483880398311,-10.8333751784591 -313.761397378124,-10.1309242320866 -315.002321176928,-9.45331350964065 -314.478998789942,-9.66484284008952 -313.972131126423,-9.86649104263068 -313.314768984119,-10.1399638895855 -313.12722239568,-10.1786541504078 -312.94628602966,-10.2118575983523 -312.884709223318,-10.1850404283007 -312.826062152067,-10.1575367134923 -312.730573066509,-10.1482632826268 -312.537582486695,-10.1882930327749 -312.351389848407,-10.2250346653425 -312.223623445331,-10.2323012015508 -312.100727120425,-10.236777313493 -311.812656635474,-10.3232038386601 -311.760678701281,-10.2907363965446 -311.711362705674,-10.2569704080959 -311.558552104643,-10.2753651771641 -311.411379724874,-10.2899989963901 -310.851133405468,-10.5119857268581 -309.923051817881,-10.9163393411849 -309.023590256596,-11.301765396869 -309.00170620378,-11.2450529474134 -308.98176999811,-11.1870973268027 -308.865185453217,-11.1782398383716 -308.82128785603,-11.1332625066535 -308.779975755615,-11.0882323785161 -308.449478729678,-11.1878684107143 -308.130025879577,-11.2814086626327 -308.780882189934,-10.8870069361331 -308.858305108814,-10.7845840070295 -308.934660419895,-10.6836764545795 -309.133464864637,-10.5225497533456 -309.327570381658,-10.3665864728199 -308.853366846638,-10.5444841874089 -308.485782728825,-10.6683846567144 -308.130230708158,-10.7839736259383 -307.795414068128,-10.8888468598652 -307.471710338629,-10.9849987862415 -306.950127313295,-11.1804555089307 -306.496143925188,-11.3407442280293 -306.056881113346,-11.4919117214496 -305.929319873879,-11.485665931514 -305.806880318312,-11.4769612950736 -306.294764796362,-11.1627564341389 -306.597704017198,-10.9435996294095 -306.892976288991,-10.73087628576 -306.328049649039,-10.9524337543725 -305.781016333284,-11.1604159082669 -305.954484672381,-11.0068190495322 -305.976262354008,-10.930473420687 -305.998653176929,-10.8537951317234 -306.249267621497,-10.6650314967712 -306.493682738212,-10.4812376520809 -306.784424068959,-10.275424942403 -307.316562920938,-9.95321449249839 -307.834028182992,-9.63996729685441 -307.76992412403,-9.62141746081677 -307.708690030082,-9.60027309605922 -308.225752391685,-9.29106922578951 -308.586961658802,-9.06134388858189 -308.938422295827,-8.83965943525891 -308.580690100345,-8.97458553061805 -308.234391842677,-9.10244650909607 -308.226604827932,-9.06044858199879 -308.076343907383,-9.08890890999 -307.931427817544,-9.11527310638017 -307.274953001285,-9.39723213968289 -306.638800441441,-9.66504318070895 -306.347563062091,-9.75855939697793 -305.843147350785,-9.95761019053391 -305.354684818786,-10.1477878337909 -304.892051690915,-10.3227801877306 -304.444195752785,-10.4881418698951 -304.572409338394,-10.3653524927517 -304.64438567659,-10.2706665763063 -304.715359294081,-10.1767058002918 -305.090969086817,-9.931738790033 -305.456558486963,-9.69515173190862 -305.479923664324,-9.63200403263029 -305.896273258595,-9.37358576658767 -306.301263532566,-9.12186444290013 -305.686483072708,-9.38196155343346 -305.090810131244,-9.63085754673153 -304.519615326752,-9.86681883748651 -303.417263897198,-10.3636083665797 -302.34858937037,-10.8397551352375 -302.601660779643,-10.6497570439534 -302.84846024474,-10.4648893462677 -302.164158379724,-10.7472776813897 -301.506603405159,-11.0132945862009 -300.869719380708,-11.2665314493606 -301.056891425836,-11.1057496585793 -301.239814020973,-10.9470776345306 -301.83611634507,-10.5833995359756 -302.537912280879,-10.171772257083 -303.220100602064,-9.77374847318875 -302.847170518592,-9.90797102282691 -302.486283800105,-10.0352054616477 -302.329218900637,-10.0578924434916 -302.607959814809,-9.86284065571125 -302.879519396394,-9.6742981405214 -302.645509097017,-9.74067602943112 -302.419398818497,-9.80142852918741 -301.979636769161,-9.96834822427203 -301.382599504572,-10.2126415411995 -300.804277731664,-10.4439711986814 -301.114037067111,-10.2291428144957 -301.415778863295,-10.021429317599 -301.303096469743,-10.0223556161915 -300.893991748596,-10.1716149028702 -300.498059854141,-10.3135063564648 -300.612045495901,-10.1985483396442 -300.72377078017,-10.085762187841 -300.480869671986,-10.1510486498315 -300.030858551516,-10.3195283130881 -299.595254859454,-10.4797702794478 -298.874324312544,-10.7800323389481 -298.175891618795,-11.0663338750721 -297.186627170412,-11.4951425379003 -295.839067563783,-12.1002822675962 -294.532717417014,-12.6774200368713 -295.019921603823,-12.3528144966498 -295.494260108929,-12.0371978611656 -295.941528383257,-11.7390046585927 -296.086893954596,-11.5942618332681 -296.229341102875,-11.4522861904855 -296.553518687993,-11.2214126688588 -296.869421715605,-10.9970573234417 -297.194327626495,-10.7698912860999 -297.110591465059,-10.7491737425617 -297.030536696049,-10.7267549800263 -297.336800151464,-10.512288452351 -297.63517618743,-10.3023817692026 -297.079771316504,-10.5226784952319 -296.617747911144,-10.6931701048844 -296.170564273762,-10.8555059889248 -296.185465799098,-10.7840679694366 -296.201155775621,-10.7132846282526 -295.796449550527,-10.8536850507346 -295.477708574265,-10.9495849962647 -295.169622611968,-11.0385435516358 -294.569868769936,-11.2730785321111 -293.989124450628,-11.4958621347887 -293.893314900763,-11.4728430705256 -293.57192634448,-11.5638259187436 -293.261391099531,-11.648057790025 -292.615360828228,-11.8993259880094 -291.989833032568,-12.1381442370243 -292.239741327213,-11.9365518458462 -292.462109208006,-11.7505719967953 -292.679331813784,-11.5695958480377 -292.996256455044,-11.3403165914473 -293.305160291068,-11.1167274037207 -293.763231377471,-10.8222329974133 -294.47095427656,-10.4052717524767 -295.158939661701,-10.0027505744716 -294.580728073764,-10.2375547639619 -294.020676165418,-10.4600315817285 -293.859781130496,-10.4798933770795 -293.704172627668,-10.4986143762018 -293.554305782836,-10.5133105838436 -293.15181795255,-10.654198611105 -292.762404361652,-10.7870367881669 -292.87218018383,-10.6696803541337 -293.322124336264,-10.382791867899 -293.759939006551,-10.1051837355603 -293.327168102836,-10.2648152117612 -292.90829866501,-10.4172271934795 -293.138355094523,-10.2429709542692 -293.456822582437,-10.025295747382 -293.766985789104,-9.81456243682823 -293.628381094759,-9.8312003761441 -293.494891368098,-9.84346739354202 -293.206149196436,-9.93411831892393 -292.441197939836,-10.2615928349191 -291.699947675753,-10.5749760624095 -291.78298770673,-10.4727691885703 -291.864735731716,-10.3723574936379 -291.006397291544,-10.7417081091778 -289.811942411758,-11.2748644551078 -288.654076986109,-11.7858088341141 -288.72096500798,-11.6791735940805 -288.787279437456,-11.5738104478623 -288.923325568113,-11.4358819428065 -288.906759043727,-11.3753864249091 -288.892004561311,-11.3135614389316 -288.593924637289,-11.3934612264323 -288.305997064883,-11.4677782597459 -288.120118883275,-11.4917169324581 -288.530093220156,-11.2168692366827 -288.929273914733,-10.9505337189462 -288.897444830915,-10.9012457305642 -288.867810871144,-10.8518301405172 -288.590251951863,-10.9276859633308 -287.863738462465,-11.2267341306626 -287.159965058869,-11.5103799249392 -286.94761619794,-11.5464647337875 -286.742900120408,-11.5772585949524 -286.087486620724,-11.8345457083208 -285.707586409705,-11.9508155705715 -285.340347837096,-12.0588854927566 -285.530398207511,-11.8870083054597 -285.716299475968,-11.719135469806 -285.73236763967,-11.6381890583925 -285.486765945792,-11.6902308678037 -285.249794249684,-11.737022632079 -285.19952049008,-11.6891394779122 -285.152138073776,-11.6400455515133 -284.884382432423,-11.7016490058596 -284.709585252896,-11.7166973739286 -284.5413526904,-11.7277505678157 -284.590799336445,-11.6304405714961 -284.64017707302,-11.5337548925799 -284.822795422896,-11.3713042688269 -284.416654445459,-11.5046692144365 -284.023875509065,-11.6302535736909 -283.734632231409,-11.7025169980083 -283.455341560008,-11.7691868297416 -283.220766051451,-11.8131895872955 -283.329555049548,-11.6834500483792 -283.436571488934,-11.5579220939169 -283.798560586848,-11.3056242781396 -284.151204225836,-11.0601152481666 -284.130167583168,-11.0036619675378 -284.240785195498,-10.8834971780305 -284.349374562813,-10.7654954903344 -284.948059672488,-10.4034660442493 -285.530227072705,-10.0523368974841 -285.823038113129,-9.84928267763331 -286.356023776733,-9.52877254706931 -286.874269973997,-9.2191290371194 -286.519374748836,-9.34867827124692 -286.175905544807,-9.47138566165003 -286.246319311286,-9.38585324373185 -286.66715412768,-9.12568365293146 -287.07648741168,-8.87422537224518 -287.244426776259,-8.7464766278584 -287.408236046254,-8.62171641181583 -287.230500363206,-8.66940449835386 -286.782871952895,-8.85058429738162 -286.349313501828,-9.02349012017606 -286.181598448589,-9.06202936650339 -286.019718926718,-9.09598014128383 -285.830937609876,-9.14384043728146 -285.36583739913,-9.32943589546857 -284.915407365102,-9.50674348279521 -285.019297935448,-9.4045344740393 -285.121078992839,-9.30400544366149 -284.913626050925,-9.35968825534466 -284.74648988898,-9.39496504792871 -284.585229250786,-9.4256377510431 -284.039161655202,-9.65029480084006 -283.510188361251,-9.86254788580209 -283.410974530618,-9.85707299854109 -283.70943690876,-9.65356460771888 -284.000107177687,-9.45657827099437 -284.002986129516,-9.40556750316623 -284.006732410667,-9.35382867863201 -283.534713306532,-9.54139037867643 -282.866788251131,-9.82543799334005 -282.219594281344,-10.0954614050153 -282.213205665697,-10.0413036377754 -282.208108232069,-9.98817664737319 -282.62564517936,-9.72563797848948 -283.38290728473,-9.29397930242562 -284.11877187074,-8.87821736622674 -283.941925990465,-8.92257409734416 -283.771161872926,-8.96290022886591 -283.474520301094,-9.06569484864899 -283.45531406324,-9.03014465011949 -283.437544026003,-8.99404583868375 -283.107256841526,-9.11408853043051 -282.787613474698,-9.22714452905076 -281.934720332576,-9.60508270172622 -281.535100735707,-9.75317279787854 -281.148304521497,-9.89438860431306 -281.310381891617,-9.75893984980715 -281.468706977357,-9.62584374395716 -281.044526817153,-9.78679658222291 -280.988097821093,-9.76220064087362 -280.934354032203,-9.73577673301531 -281.246352009198,-9.52697305760893 -281.550128900363,-9.32439248392144 -281.428218801171,-9.33558061975699 -281.268352956158,-9.36644927311482 -281.114162272277,-9.39403229066328 -280.270672185151,-9.76706219155631 -279.453087208593,-10.122868982676 -279.615910334323,-9.98506665963284 -279.785638776766,-9.84297279259467 -279.951442628056,-9.70656854891786 -279.838714074909,-9.70971683665965 -279.730345102479,-9.71066148339033 -279.305897590473,-9.87008063261336 -278.747987362227,-10.0947554974672 -278.207635441968,-10.3078057085994 -277.698613298326,-10.5039111521685 -277.205781549098,-10.6901814791018 -276.868290926778,-10.7965343783816 -276.940313389154,-10.6975090056147 -277.011414708433,-10.5992011273485 -276.510632115892,-10.7885549620418 -276.025846583198,-10.9680037366341 -276.130025574491,-10.8504639203898 -276.10485624455,-10.8000115734602 -276.081643284319,-10.7477077095334 -276.269331647214,-10.5908496004405 -276.452674918653,-10.4375709678408 -276.011468656357,-10.5988885295376 -275.383379024148,-10.8515298114846 -274.775062031642,-11.0918278810916 -274.644825650951,-11.0902997157948 -274.519725193296,-11.0859351140687 -274.003180077181,-11.2777235518289 -273.352707416347,-11.5339959610096 -272.722815256967,-11.7784380368288 -272.820006627263,-11.6574497009761 -272.915712019527,-11.5369340302016 -273.286910360218,-11.2806120216183 -273.2637282211,-11.2238601801291 -273.242545583937,-11.1669324320222 -272.493552540962,-11.4729320495431 -271.768047427607,-11.765192595979 -272.02755468031,-11.5619279387519 -272.76149893349,-11.1248557087151 -273.475063984215,-10.7021889279734 -272.77715112246,-10.9894517553172 -272.10108338293,-11.2624512239052 -271.78963339039,-11.3509041822334 -271.340013816391,-11.5078245968193 -270.905008438524,-11.6539392743632 -270.388599683496,-11.8405139591385 -269.888854092497,-12.0163776887589 -269.854863787185,-11.9569080145475 -269.54519301505,-12.0358504711484 -269.246147466641,-12.1092063315707 -268.663453527896,-12.324280009877 -268.099474158947,-12.5272493966231 -267.716698279514,-12.6376945953209 -267.48786424471,-12.6702706956143 -267.267376798304,-12.6992360145792 -267.061226589391,-12.7189561149007 -266.862780576214,-12.7343892376062 -267.076821353863,-12.5436896388848 -266.673803646974,-12.6635410555387 -266.284285191228,-12.7758694743537 -266.763163212643,-12.4528752451109 -267.229471058005,-12.1391860293455 -267.461154713682,-11.9459695948308 -267.68732698912,-11.7569641870983 -267.908262958068,-11.5731983254711 -267.65851663729,-11.6264041198684 -267.417540457868,-11.6744030819957 -267.361149710922,-11.6297258247341 -267.054425800388,-11.7110511011615 -266.758165779579,-11.7861812461892 -267.258456368188,-11.4628947809381 -267.74534281124,-11.1496900225818 -267.7996883061,-11.0556940252647 -267.789771647089,-10.9947098109762 -267.78141568005,-10.9333109441104 -268.283689558547,-10.6165111297651 -268.772356880651,-10.3098595705311 -268.986649974968,-10.1449289415823 -268.852874670015,-10.1559542362569 -268.724132824239,-10.1628246411335 -268.216125061699,-10.3597367599977 -267.724252418858,-10.5463351048382 -267.76808725128,-10.4627048965801 -267.440271882172,-10.5664601230084 -267.123316387732,-10.6638297623514 -267.011199699701,-10.6578720884987 -266.903593579558,-10.6493348199933 -267.07599432774,-10.5008763841873 -267.210164663027,-10.3727484876618 -267.341536270392,-10.2471801748296 -267.297498206681,-10.2111016473345 -267.255880149766,-10.1735218136219 -267.131575632696,-10.1793064448746 -266.770906727868,-10.3025774454567 -266.422010870982,-10.4162233731209 -266.329571921396,-10.4034758423794 -266.241002449682,-10.3876177508377 -265.924299636348,-10.4864022668154 -265.298062001948,-10.7396048747279 -264.691513604237,-10.979672578558 -264.479864582569,-11.0202532995397 -264.2757345111,-11.0556195643263 -264.651389904244,-10.8010442374056 -265.275913810715,-10.4247450104858 -265.88318107584,-10.0620565375185 -266.060527331069,-9.91595104373875 -266.233727387938,-9.77457520542667 -265.806910487288,-9.93381068343297 -265.363349766887,-10.099862120818 -264.933990215529,-10.2581339180487 -264.993726742904,-10.1704231043681 -265.052806439391,-10.0834227450783 -265.72427751028,-9.6914928100344 -266.507592393125,-9.2480154166003 -267.268715335407,-8.81867387660898 -267.138398349223,-8.8395825878871 -267.01278930404,-8.85932631933335 -266.672185911881,-8.98548501523939 -266.681433220762,-8.93499719372214 -266.69128810736,-8.88541531767425 -266.738235122085,-8.81686935309201 -266.784658513757,-8.74967490480026 -266.419133858657,-8.88936394802425 -265.924846170747,-9.09201642837171 -265.446045333856,-9.28566846896388 -265.04057798349,-9.43981282324232 -264.648046968308,-9.58467718697776 -264.286933825753,-9.7137709961768 -264.52916642862,-9.53926345890476 -264.765254412635,-9.37032002964746 -264.421358805845,-9.49364437165321 -264.088577542319,-9.608426750225 -263.983500258965,-9.60956380851985 -264.384771832522,-9.35742514158565 -264.775154626239,-9.11268421790931 -263.988776054901,-9.46026095390695 -263.226552359113,-9.79133024959304 -262.773146674299,-9.96481036069848 -262.577217325392,-10.007736771052 -262.388145485265,-10.0463563749491 -262.121553037905,-10.1238494420457 -261.863924567769,-10.1962437534072 -261.69861993694,-10.2217186073791 -261.56728208608,-10.2295195782766 -261.440944079982,-10.2339329608084 -261.950355629445,-9.9212597810739 -262.445801458414,-9.61834905521034 -262.003920042537,-9.7879136535719 -261.60015447816,-9.93602298533628 -261.20937448987,-10.0756939442499 -261.550001232962,-9.84887608357719 -261.881630515597,-9.62932330308831 -261.774813991753,-9.6300899714233 -261.9871051421,-9.47196052025674 -262.194110957511,-9.31819291319679 -262.22675918073,-9.25259798833211 -262.259387728778,-9.18702447087895 -262.353166018635,-9.0924134842467 -262.554250243107,-8.94408912965134 -262.750300142523,-8.80035211525608 -261.897344209117,-9.18278561450674 -261.070483843677,-9.54835901231449 -260.996369591468,-9.53383197974846 -261.156606202945,-9.40240988313999 -261.313085330582,-9.27512938590421 -261.633887283002,-9.06614450325386 -261.94612642846,-8.86258160875334 -261.394221186766,-9.09290435157741 -261.174408979319,-9.15656412454889 -260.961992317452,-9.21581257629347 -260.918836945773,-9.18813552706135 -260.877905529466,-9.16143827673501 -260.412595074292,-9.34724247855132 -260.262532647705,-9.37513091493487 -260.117818258251,-9.39690876056102 -260.547789797543,-9.13232253431652 -260.965986423455,-8.87581649263306 -260.868226513237,-8.88090017007363 -260.911821915632,-8.81342940939259 -260.955004450523,-8.74845790747154 -260.722389660128,-8.82130316186849 -260.497495897181,-8.88930444385748 -260.695169232342,-8.74641901268078 -261.274437572107,-8.41365246206599 -261.837387222422,-8.091640594142 -261.469356701157,-8.2392817744417 -261.112919583689,-8.37882410320674 -260.82782296444,-8.48186916512281 -260.470423139787,-8.6196006519316 -260.124390312869,-8.75049131801801 -259.500327703459,-9.01929154383633 -258.89556932745,-9.27530089531036 -259.336547260074,-9.00650990696113 -259.355599623425,-8.9511838319762 -259.374968080006,-8.89565061700648 -259.410609182935,-8.83364328086576 -259.446044321724,-8.77199840981475 -258.837745420648,-9.03194163365082 -258.350650541332,-9.22854778380522 -257.878876668664,-9.41584955689665 -257.543912160141,-9.5329960890833 -257.219830518797,-9.6443335595048 -257.087695051349,-9.6582932080601 -257.173919058847,-9.56326958107764 -257.258588185042,-9.46952337460886 -257.43232651265,-9.33219367951861 -257.601891474444,-9.19861592911144 -257.495871702286,-9.20431048933662 -256.767444255347,-9.52133946550675 -256.061486424679,-9.82271836052101 -256.110521226871,-9.74395281556437 -256.15914692146,-9.66618484563829 -255.759690482189,-9.81359715061124 -256.089313458733,-9.59509520452639 -256.410210634664,-9.38203898992438 -256.412183383475,-9.33104308763355 -256.415058708104,-9.2806503223281 -256.519787532997,-9.18044889637625 -256.618144943649,-9.08312856300298 -256.71451585628,-8.98850339101904 -256.795796555989,-8.90111706336489 -256.87556944427,-8.81678595585159 -257.225057806877,-8.59755896041001 -257.693903814577,-8.32094044084053 -258.149681854246,-8.05422147618178 -257.711223502215,-8.23668118392743 -257.286450957702,-8.4111840990468 -257.158147281806,-8.43503764866921 -256.735923228498,-8.60605181409316 -256.326968372417,-8.76757933371773 -256.154355053922,-8.80964736183457 -255.987701519014,-8.84907727730462 -255.595223542895,-9.00118131315477 -255.585661668667,-8.95901861842147 -255.577284904743,-8.91689493013938 -255.50753633262,-8.90653424175898 -255.440721685387,-8.89459405278203 -255.314375842636,-8.91228748540936 -254.957806225286,-9.04549265263228 -254.612658030168,-9.17113588146019 -254.541983244227,-9.15839739982578 -254.474324391149,-9.14530183135654 -254.463198900684,-9.10311015918849 -254.255692636648,-9.16108240448978 -254.055208693533,-9.21411015066779 -253.682187836517,-9.35264835251763 -253.321130974993,-9.48477430602801 -253.736596837032,-9.22585105712408 -253.555142275737,-9.26759392072001 -253.380000410753,-9.30685658003001 -253.237486312217,-9.32918585288447 -253.100131105256,-9.34864233859362 -252.491858926376,-9.60466822071217 -252.088211823319,-9.75624250338017 -251.69747906968,-9.89877570891288 -251.421981443334,-9.98177517084239 -251.155691155781,-10.0594940572079 -250.737804737471,-10.2116123010913 -250.275996203745,-10.3845015391688 -249.828972940547,-10.5479506636887 -249.374448651999,-10.7143309334862 -248.934549094348,-10.8712520895191 -248.906794380868,-10.820421555835 -248.685507324085,-10.8673485237075 -248.471995175868,-10.90902275959 -247.70871782529,-11.2252441150489 -246.969292072007,-11.52736403713 -246.233474190004,-11.823889053304 -244.956991442541,-12.3881771064792 -243.719716234663,-12.9267077051205 -243.037986660599,-13.1813420965542 -242.37809464489,-13.4235077233557 -242.708155507719,-13.1682774733011 -242.854901632766,-13.0066605385469 -242.99899945289,-12.8486178302089 -243.125872774219,-12.7011256557426 -243.250605583086,-12.5549826509588 -243.109444983269,-12.543873559757 -242.734143316903,-12.6510174115368 -242.371498343985,-12.7505717959312 -242.795624133056,-12.4555462442768 -243.208789136185,-12.1696618242333 -242.794141057452,-12.300085106024 -242.69352585714,-12.27095822148 -242.597415467253,-12.2404066051824 -243.193025379456,-11.8656994547842 -243.7724817727,-11.5013964387014 -243.790458003377,-11.4221355901874 -244.33114712869,-11.0821245624539 -244.857169460914,-10.7532622426833 -244.736883160537,-10.7503493128879 -244.621369250699,-10.7466801134075 -244.495971561526,-10.7460125045935 -244.471559019478,-10.6947036535219 -244.449089631961,-10.6428181308365 -243.914374995947,-10.8487400130692 -243.396669524188,-11.0438935475968 -243.868789024432,-10.7421861046383 -244.427234664131,-10.3996550806921 -244.970365702974,-10.0680223325053 -244.44802990481,-10.2739942115216 -243.942216936928,-10.4677687586133 -243.692350820195,-10.5328088495034 -243.497992916057,-10.5691968606557 -243.310556545058,-10.6012489630666 -243.209030089419,-10.5908795506328 -243.111683734592,-10.5787333668556 -242.50140016919,-10.8231747236253 -241.844162662244,-11.0881928052928 -241.20760285072,-11.3395725424921 -241.363674723232,-11.1921302004715 -241.516460252845,-11.0484932335776 -241.593775944492,-10.9434135625765 -241.862074621277,-10.7436229837277 -242.12369246444,-10.5496196072114 -241.949372753013,-10.5748412284782 -241.781403449916,-10.5985948700124 -241.704329345708,-10.5751240113517 -242.105910308655,-10.3122458539233 -242.496796728548,-10.0580021391193 -242.191114935339,-10.1546012673325 -241.895562671212,-10.2454854034042 -241.578438238502,-10.3453569519384 -241.360384759259,-10.3956988864189 -241.149913778943,-10.4418049018618 -241.11421794984,-10.3998460227918 -241.080728024849,-10.3567829876466 -241.243500512299,-10.2153711998636 -241.274863359153,-10.1418373221517 -241.306409483685,-10.0693827707625 -240.830418778435,-10.25166688012 -240.369588895546,-10.4241634612866 -240.352120114042,-10.373702872004 -239.996811571678,-10.4920583661837 -239.653160353266,-10.6040456346067 -239.820325870673,-10.4586442704941 -239.983730845221,-10.3159022339844 -240.270962707917,-10.1127509513016 -240.284061221799,-10.0490887472404 -240.297869464276,-9.98551783686985 -240.691530115657,-9.73257188568949 -241.074615923465,-9.48744448800679 -241.144678655067,-9.40088772563177 -240.261449402141,-9.79183719091125 -239.405339090516,-10.1656557348481 -239.022693726427,-10.298411512735 -238.652500847898,-10.4241698360332 -238.449667274857,-10.465239656874 -238.491750294456,-10.3841373706057 -238.53374168765,-10.3034131455755 -238.760579740465,-10.1312118837636 -238.981832476579,-9.96261907071142 -238.973908964281,-9.91202892856812 -239.042737800998,-9.82267180500528 -239.110584933267,-9.7358693627125 -238.768271781602,-9.85372300900087 -238.437116049064,-9.9647098243861 -238.575304887177,-9.83979487117345 -238.666947729381,-9.73898154412514 -238.756934471931,-9.64107039357483 -238.625116177449,-9.65396233994903 -238.498218738711,-9.66467414116219 -238.769312908762,-9.47705285187144 -239.201157205462,-9.21098695143174 -239.621181591238,-8.9517252194757 -239.32227547713,-9.05504956911818 -239.033103987746,-9.15388432447559 -239.245433741558,-9.00070582753974 -239.420042329251,-8.8664782114756 -239.590383819366,-8.73654102176731 -239.052394902132,-8.96183327214654 -238.531171316309,-9.17734280292201 -238.336092884097,-9.22826402876962 -238.138707718581,-9.27867935055508 -237.948093238862,-9.32466335861873 -237.947793932454,-9.27515773731748 -237.948457652024,-9.22538028238012 -237.526900741041,-9.38763694034188 -236.519931887293,-9.84185006900347 -235.543718132734,-10.275186256699 -234.886975909606,-10.5445273699207 -234.250808891345,-10.8022828928382 -233.815524418768,-10.9557144919188 -233.275213794764,-11.1614255766827 -232.752135803901,-11.3559857405101 -232.165000318181,-11.5801145176805 -231.596579553976,-11.7924747516072 -231.256542020438,-11.8886205352395 -230.721948120827,-12.0822764838215 -230.204594351154,-12.2635916594672 -230.321007502586,-12.1266590089339 -230.435487374266,-11.9922640887089 -230.524351740885,-11.8727385910397 -230.816539061497,-11.6521394429231 -231.101508730002,-11.4384529286904 -231.167316094005,-11.3351836188268 -231.232527559077,-11.2328289484307 -230.928476666438,-11.3173354092233 -230.816282197325,-11.3043545360671 -230.708736302292,-11.2887543525999 -230.90974599845,-11.1191258950911 -231.106133667216,-10.9535618031797 -230.887369854514,-10.9985305642966 -229.835989659044,-11.4582738025102 -228.816999662445,-11.8987759648054 -228.756785422318,-11.8544919166712 -228.699783131232,-11.80882909413 -229.586128852992,-11.2924424844738 -229.930715986266,-11.0522733265259 -230.266406928377,-10.8176456522871 -230.168425282931,-10.8042625080756 -230.074542657842,-10.7869071026891 -229.916298348883,-10.8025998806887 -229.915646051467,-10.7404647359031 -229.916213307195,-10.6764562140713 -229.759018888196,-10.6926355904712 -229.607677150159,-10.7061280721879 -229.619984652758,-10.6365071789101 -229.992120883712,-10.38806762138 -230.354439647937,-10.1469746848665 -230.992044852318,-9.77174353886138 -231.611859974674,-9.40867935896109 -231.331209856015,-9.49921333082734 -231.232311276031,-9.49780183170339 -231.137317624578,-9.49431720154458 -230.853383018532,-9.58508990556543 -230.578837195503,-9.67060685980695 -230.066449509179,-9.87444231649155 -230.07091946656,-9.81790781901189 -230.076300512954,-9.76022898269744 -229.726134400719,-9.88218622648855 -229.387354767655,-9.99634103356246 -229.774360904241,-9.74717777913361 -230.187111772188,-9.48733393202881 -230.588671819289,-9.23557230084066 -231.092798629486,-8.93383925794605 -231.582956709895,-8.64348468048005 -231.460110402636,-8.66303676157176 -231.186731836096,-8.75604206246665 -230.922285249966,-8.84435608015722 -229.916806032974,-9.30195218459916 -228.941958500041,-9.74006787278763 -228.058895098364,-10.1273708878461 -226.942118299699,-10.6280407889698 -225.859509456874,-11.1059373840299 -225.796595678583,-11.0705111246661 -225.736829488499,-11.0345975125927 -226.296737779793,-10.6879256241889 -226.822470347585,-10.3623168754352 -227.333845816382,-10.046522425887 -227.601581402302,-9.85594831743776 -227.86248113148,-9.67119825667823 -227.621646646797,-9.73873437989208 -227.790338481492,-9.60098100003074 -227.955062964401,-9.46784432419838 -227.606435404627,-9.59147203517376 -227.269101898139,-9.70849552710427 -227.382981916649,-9.59878170405117 -227.783467895798,-9.34690896908359 -228.173090788105,-9.10265072229141 -227.658555116762,-9.31254712879612 -227.160161020408,-9.51317546516269 -227.272573913934,-9.40695415804101 -227.55691289962,-9.21494052036421 -227.833792672289,-9.02891377068096 -227.799496780635,-8.99949622823565 -227.76711090982,-8.97009256171703 -227.623565620695,-8.99541776722428 -227.474443085523,-9.02461976268911 -227.330606493327,-9.05007684990546 -226.968894246783,-9.18408122726073 -226.618789707088,-9.31126975848132 -226.872794877767,-9.13516524510892 -227.257251513649,-8.8959327676084 -227.631230679282,-8.66439238425613 -227.460368045537,-8.70710746452221 -227.295384117545,-8.74601262863554 -227.196616904998,-8.75175621817603 -227.061400093958,-8.77728504396979 -226.930994566457,-8.79848674879612 -226.72730863102,-8.85762955442265 -226.53047272847,-8.91102899595577 -226.119634471703,-9.07120931884497 -225.76991924616,-9.19984572466613 -225.431444475104,-9.32142140166423 -224.904717671366,-9.53482668861754 -224.394543029997,-9.73777678405447 -223.925184265269,-9.91872869106483 -224.027543406862,-9.81332161810052 -224.127914536066,-9.70943464745318 -224.238620341843,-9.60235205902575 -224.347043059567,-9.49681402142699 -223.949996489248,-9.64429661401672 -223.864538626626,-9.63457938793915 -223.78261828428,-9.62351133703674 -223.773043883027,-9.57710222546808 -223.764736681565,-9.52862282457921 -224.154996833861,-9.28250168665442 -224.103548545346,-9.25956305656747 -224.05455832429,-9.2348746404725 -224.389436579935,-9.02041022053458 -224.715305391591,-8.81154312681021 -224.493439155826,-8.8786726914834 -224.016011825897,-9.07244073749746 -223.553580975221,-9.25718900983742 -223.405636038265,-9.2824838223072 -223.263005950407,-9.30489155770611 -223.208183461435,-9.28385163909473 -223.086568500201,-9.29630244469829 -222.9694827997,-9.30660868969369 -222.872713939726,-9.30699516999144 -222.779731952515,-9.30584214939934 -222.586138256607,-9.35268420512324 -222.516815194664,-9.33782389484411 -222.450495837232,-9.32191910634719 -221.443030230743,-9.77742748691529 -220.466314311775,-10.2123266259275 -220.125751698657,-10.3254736218241 -219.238059415947,-10.7108212422961 -218.377768713518,-11.0780128820991 -218.042992623765,-11.1793011351376 -217.719396742853,-11.2750783041069 -218.111337184406,-11.0112994187507 -218.798340461305,-10.6019074387358 -219.466273189499,-10.2067907034945 -219.89021740101,-9.93680763124403 -220.302726734904,-9.67658045368989 -220.343135028904,-9.60431793195534 -220.718763420177,-9.3660294776663 -221.084242355807,-9.13492764571227 -220.404342188785,-9.42795348556032 -219.745470126758,-9.70796307618438 -219.830925338394,-9.61308541571415 -219.929865403909,-9.51069609614824 -220.026893530186,-9.41122972110541 -220.161142887062,-9.29452004301382 -220.292371007366,-9.18151655694472 -220.208116596578,-9.17694997920785 -220.067809219445,-9.20132130760472 -219.932534968784,-9.22145660244106 -220.00880968191,-9.13622945472448 -220.08373137757,-9.05263193048956 -219.690517215991,-9.20370127539493 -219.326044161206,-9.33818731276127 -218.973277808858,-9.46588092343901 -218.439402519936,-9.68319262228132 -217.922284620081,-9.88978172056566 -217.679169198055,-9.95746933982372 -217.664997168947,-9.90958804794217 -217.652300901377,-9.8611863176839 -218.135724101541,-9.56689067325857 -218.605847443245,-9.28071383885722 -218.77310888964,-9.1495082954875 -218.712748004629,-9.13287777266806 -218.655073433938,-9.11515602073787 -218.672686816252,-9.05962056744716 -218.6906767375,-9.00489598438333 -218.355007309754,-9.12738820099869 -218.004506796392,-9.25598530416802 -217.665278283822,-9.3773467365028 -217.333682526545,-9.49436541722103 -217.012840004749,-9.60477442883237 -216.482498762899,-9.81821083299195 -215.795375158728,-10.1089841858973 -215.12960617329,-10.3871660306918 -214.387294374928,-10.7000370606553 -213.668076495419,-10.9992880652431 -213.295342584955,-11.1211664545158 -212.653772808006,-11.3756998612043 -212.032467867469,-11.6183577215265 -211.674176018811,-11.7267656981214 -211.327849618832,-11.8280736056935 -211.253597651251,-11.7925378282231 -211.554562247003,-11.5690323721126 -211.848020881427,-11.3523688008336 -212.239711913435,-11.0881005570121 -212.621122897417,-10.8314526650597 -212.525779878509,-10.8175413499257 -212.763035819643,-10.6358929539841 -212.994479493758,-10.4599640450866 -212.886610550027,-10.4539933243022 -212.783085871174,-10.4457812025331 -212.785980559833,-10.3852137911003 -213.363331207331,-10.038313885148 -213.924709941691,-9.70251135592823 -213.04215770198,-10.0919680038707 -212.186726543617,-10.4642088166965 -212.140023420535,-10.4282869299533 -211.817274274175,-10.5295002371977 -211.505235201306,-10.6255306752868 -211.504242020885,-10.5652431890203 -211.504446255364,-10.5040274945315 -211.239921014358,-10.5758663443787 -210.781595890029,-10.7447661828986 -210.337996111533,-10.9053336537254 -209.770591054513,-11.1250020498485 -209.221212800268,-11.3338698509873 -208.325813847843,-11.7130854731589 -207.902500525142,-11.8511791220626 -207.493131703949,-11.9821018855585 -207.272055769114,-12.0170397579365 -207.058976844851,-12.0473516321852 -207.82426825255,-11.5896661372647 -208.234511796816,-11.3145027345572 -208.633957209739,-11.047305151432 -208.509223885488,-11.0459784633326 -208.38940683832,-11.0411954707034 -208.591083527974,-10.8761148488903 -209.264458642569,-10.4756885301773 -209.919125285249,-10.0887008779524 -209.709991832342,-10.1384051394264 -209.50810337824,-10.1828375095188 -209.220942075149,-10.2697118579955 -209.31949178273,-10.1635934005691 -209.416216515349,-10.0583989742122 -209.46882098044,-9.97730724124855 -209.520921071295,-9.89819821719575 -209.647883710035,-9.78189940521223 -209.697472460101,-9.70509035887798 -209.746592786622,-9.62800943962783 -209.669557753587,-9.61637162634265 -209.595766887972,-9.60340917458675 -209.608206160454,-9.54648113322193 -209.598293551209,-9.50180222519739 -209.589628155616,-9.45582395159177 -209.115223433904,-9.64334898098564 -208.655816639785,-9.82256691176159 -209.053715485787,-9.57149403747663 -209.024810859858,-9.53542892170296 -208.997732602119,-9.49956671975334 -208.908608436287,-9.49457196416375 -208.82307480013,-9.48667770003067 -208.811753819125,-9.44305338140466 -209.041965134905,-9.27886008723119 -209.266304989092,-9.11861958275316 -209.144130458318,-9.13382477479887 -209.02645420121,-9.14590531727605 -208.971392344181,-9.12667146167194 -208.107374703409,-9.51266127456257 -207.269818021852,-9.8812501037269 -206.808954466399,-10.0585785145838 -206.362753826688,-10.2256087414448 -206.348263890341,-10.1757459460444 -206.028757976106,-10.2780095398172 -205.71981478639,-10.3744615012723 -205.908878116524,-10.2225007175998 -206.093448336811,-10.0724766498336 -206.147259887247,-9.98871202553836 -206.102314519599,-9.95711175084103 -206.059738680846,-9.92379597768591 -206.391578997356,-9.70404827700354 -206.714630509704,-9.48999072304197 -206.794734722662,-9.40078668778684 -206.376388613548,-9.56043807808852 -205.97137799261,-9.7133691623546 -205.835484955108,-9.72898417008904 -205.704620217892,-9.74233830572572 -206.082047635537,-9.50120598010066 -206.345377873581,-9.32007341555728 -206.601863561388,-9.14459693372214 -206.006672940789,-9.3951542243595 -205.430005037832,-9.63626943764086 -205.089464540465,-9.75501324795369 -204.067460447048,-10.213586922243 -203.076717191991,-10.6511556967147 -203.096700301849,-10.5801919850859 -203.117263500165,-10.5096604815034 -202.813472698734,-10.601534188266 -203.01400181447,-10.4407140422555 -203.209758487568,-10.2831423527227 -202.756581957432,-10.4520438829583 -202.317928864654,-10.6115531335918 -202.258891262312,-10.5797807683626 -201.430708206258,-10.9339393839469 -200.628192700178,-11.2711158804953 -199.967756817222,-11.5344052028441 -199.328157257253,-11.7833207902282 -199.4519090759,-11.6494636375007 -199.367328352894,-11.6206080511077 -199.286618516524,-11.5903327125647 -199.287428381044,-11.5189885890697 -199.289577425362,-11.4482299193285 -199.675299372608,-11.1874500440549 -199.829720308142,-11.0440311211817 -199.980842320659,-10.9037974966103 -199.975382356551,-10.8442023109292 -199.971281646465,-10.7829679175021 -199.840892226234,-10.7852694560962 -199.730051807074,-10.776917253741 -199.623717926184,-10.7683027338635 -199.110688287578,-10.9626024468555 -198.614040875505,-11.1470381217376 -198.689426709497,-11.043611202491 -198.732610901032,-10.9569744128181 -198.775766639218,-10.8711039852305 -198.45087043699,-10.9698703994608 -198.136815513155,-11.0636321331542 -197.143074677615,-11.4960234651921 -195.93303488509,-12.0312840003122 -194.760155196206,-12.5431709033365 -194.778034169629,-12.4548249755932 -194.796909747748,-12.3660670951048 -195.145312984467,-12.1133300187717 -195.372927248482,-11.9234847179666 -195.595264804968,-11.7378567807224 -195.705299054736,-11.6102583539997 -195.813470776387,-11.4849720385943 -195.688495255712,-11.4780497873772 -195.8455614318,-11.3295731590583 -195.999322153064,-11.1844731127248 -195.775781645104,-11.2298003562871 -195.560135143336,-11.2700558725022 -195.94541268655,-11.0091219146215 -196.454848351338,-10.6903911710422 -196.950433751018,-10.3797279848149 -196.667379587406,-10.4625528900777 -196.393832408059,-10.5384479653767 -196.198283295988,-10.5755979542321 -196.303316669969,-10.4617002774473 -196.406420328881,-10.35059098975 -195.783695142581,-10.6041027999108 -195.18051552859,-10.8438277185774 -195.234104485066,-10.7534130195282 -195.128295461074,-10.743151810425 -195.026832377843,-10.7302348398103 -194.74999123216,-10.806325340254 -194.482542865789,-10.8761656100661 -194.564048204725,-10.772298456768 -194.894861593466,-10.5450289240532 -195.217070981833,-10.3245424201091 -195.8477266596,-9.95068696142834 -196.460838310791,-9.59017369317082 -196.234434252959,-9.65274865471454 -195.894243775289,-9.77154942344784 -195.565109287151,-9.88427634092063 -195.706666445409,-9.75959582531283 -195.845068994816,-9.63770192015343 -195.350473541256,-9.83462003909989 -195.772587325648,-9.56977359694542 -196.183239298861,-9.3136963353648 -195.933922400175,-9.39014366460346 -195.692912200517,-9.46261023740806 -195.889922463864,-9.31553822497674 -196.064136327688,-9.18024497454413 -196.234119048045,-9.04884305022564 -196.306973602167,-8.96700336153173 -196.378544150245,-8.8872262760132 -196.021789724648,-9.02195838087204 -195.418941346769,-9.27725421720902 -194.834824891631,-9.52200278587379 -195.018644173241,-9.37979265268279 -195.197988597164,-9.24113499572261 -195.495796612944,-9.04532688867605 -196.179218354061,-8.65899924772704 -196.843266778441,-8.28536768762509 -196.630072775299,-8.35362977405956 -196.42392638133,-8.41953284441748 -196.174841852513,-8.50470747508913 -195.503574495352,-8.80033624182827 -194.852946734072,-9.08147890439126 -194.082165791283,-9.42102883147061 -193.335082383838,-9.74535357143286 -193.326911584953,-9.6975964028379 -193.932008964174,-9.3434017252263 -194.520186658002,-8.99972510271032 -194.233522215615,-9.098305916904 -193.956203553814,-9.19054562883493 -193.357641075155,-9.44333302120712 -192.028935932902,-10.0580761895632 -190.740516430692,-10.6465092451465 -190.095506622108,-10.9077469458085 -189.47076770492,-11.1550366140763 -189.161672169796,-11.2434252049205 -188.952538654696,-11.2809431830503 -188.750884310042,-11.3134574048009 -188.491711789757,-11.3751218286061 -188.241516472016,-11.4316442394655 -188.049907354489,-11.4585220330423 -187.970724751801,-11.4285729018737 -187.89522238922,-11.3972043621037 -187.796412931688,-11.3770563589692 -187.701864945146,-11.3541770109603 -187.966211644097,-11.1524794813579 -188.749454097033,-10.6947663092236 -189.510781001276,-10.2502717105954 -189.231486839678,-10.3328495740546 -188.961556980071,-10.4091737658047 -188.628073793523,-10.517601374405 -187.745055295416,-10.8997535259956 -186.889316522363,-11.2632938003983 -186.79360654827,-11.245075809037 -186.701999427946,-11.2237028470582 -186.572808901087,-11.221277763448 -186.414993305745,-11.2323250824727 -186.263153364236,-11.2401457538223 -186.578348597503,-11.0155036713644 -186.885501728465,-10.7968908798109 -187.286286034838,-10.5340960797749 -187.229622536836,-10.5020544223797 -187.17579651621,-10.4683839620563 -187.272319251313,-10.3610560863287 -187.367119728827,-10.2557574922502 -187.458363175011,-10.1529510377219 -187.680994827805,-9.98543632811555 -187.89811604065,-9.82337140865223 -187.755412709501,-9.84194057444416 -187.617947943195,-9.85763070066193 -187.19220825327,-10.0177617961253 -187.194039421051,-9.96236838152908 -187.196863217754,-9.90653447546502 -187.122417316632,-9.8912073050879 -187.051184957229,-9.87282714517483 -186.582663710328,-10.0538961393379 -186.384062553438,-10.0975640493602 -186.192409418197,-10.1377370820376 -186.153618619669,-10.1014985576386 -186.117045157556,-10.0642626281374 -185.766893667412,-10.1835902568498 -185.579802634324,-10.2198436476917 -185.399350787775,-10.2527805640461 -184.632375212123,-10.578080719018 -183.889221784467,-10.8878362694479 -183.596006340933,-10.9703326364675 -182.840664940182,-11.2841542816233 -182.108910081122,-11.5819383154507 -182.72258672403,-11.2048147812161 -183.319447885659,-10.8384323296068 -183.905739547727,-10.4823776807659 -184.37370502741,-10.1883948669741 -184.828970733329,-9.90393909652635 -184.590497713408,-9.96939869676714 -184.360117342912,-10.030582042904 -184.266936364924,-10.0211117185852 -184.674526664411,-9.76159402603056 -185.07112222121,-9.5110918523244 -184.461618963098,-9.76589802460199 -183.871117974339,-10.0090862315513 -183.841478787373,-9.96980687324101 -183.904890860695,-9.88452592177798 -183.967455293515,-9.79932991391856 -183.850460982504,-9.80433986874501 -183.737957738812,-9.80784590085505 -184.105404133327,-9.57234685181772 -184.165253225372,-9.4917686041484 -184.224304014905,-9.41188746812772 -184.21554920836,-9.36651157600279 -184.208009611223,-9.32203724177472 -184.052472857129,-9.35131811908628 -183.572027146282,-9.54211498537129 -183.106753358763,-9.72416820447048 -183.104715253669,-9.672443871862 -183.103750987025,-9.62105183027777 -182.912836718179,-9.66509852633695 -182.117738032535,-10.0109070922367 -181.347170114235,-10.3402975926501 -181.129544952783,-10.3902277723673 -180.91949340815,-10.4376373141016 -180.811719313451,-10.4319737465786 -181.070613090214,-10.2429303519711 -181.322988282973,-10.0607414475829 -180.952911231615,-10.1901026420394 -180.594859092917,-10.311600041584 -180.390655192583,-10.3567592353054 -179.789060525906,-10.5989194225716 -179.20640103608,-10.8282098849133 -179.509626267642,-10.6128086175382 -179.805101170043,-10.4044103677736 -180.1303134371,-10.1816366229001 -180.970804817908,-9.7043454343853 -181.787512131401,-9.24563370207224 -181.41955412859,-9.3815339628548 -181.063412297315,-9.51005269512795 -181.410860381196,-9.28733077232971 -182.021273352626,-8.93560690661493 -182.614510736085,-8.59535354778686 -182.439818889294,-8.64046623315641 -182.271109819491,-8.68324530485623 -181.896421503242,-8.8278871368405 -181.577340632841,-8.94284145773666 -181.26856195853,-9.05254635817886 -180.948132035053,-9.16677032032524 -180.63807123836,-9.27438133365613 -180.301570157758,-9.39404842086319 -179.867165219781,-9.56223878971332 -179.446561352065,-9.72298326425588 -178.815266665574,-9.98604717632893 -178.203670009518,-10.2374363789821 -177.635780446702,-10.4636446251911 -177.432754123078,-10.5057861473575 -177.236878662303,-10.5432631961433 -177.16897537547,-10.5177794454007 -177.104224261803,-10.4900993529092 -176.634129028316,-10.6657247159115 -176.08115416412,-10.8814555388221 -175.545715959613,-11.0854226314827 -175.307959674688,-11.1372052130352 -175.078530750944,-11.1858826440708 -175.265899407418,-11.0264544039167 -175.532092942247,-10.8273224560757 -175.791675529779,-10.6347968079468 -175.769019531373,-10.5854647210116 -175.748199828456,-10.5361254313444 -175.875694226083,-10.4126549261633 -175.890258923835,-10.3467184391676 -175.905519563401,-10.2815878856586 -175.785570443279,-10.2833586767103 -175.670290491434,-10.2826647409635 -175.607241278132,-10.2569768964012 -175.754518008515,-10.1254702956855 -175.898547034779,-9.99727426199062 -175.668677083243,-10.0575230060001 -175.446662586287,-10.1132035192119 -175.245361157768,-10.1576184872825 -174.95612135133,-10.2460814230018 -174.676522728443,-10.329202197845 -174.460828783272,-10.3786744351972 -174.252641531813,-10.4253700610391 -174.039850192126,-10.4734194143368 -173.554551123546,-10.6567470805431 -173.08475780473,-10.8306168154276 -172.613517362184,-11.0043175274444 -172.157416421438,-11.1678874443297 -171.863771829129,-11.2475770869388 -171.202968396778,-11.5118473494591 -170.562996849445,-11.7624867060167 -170.509046531908,-11.7171272883402 -170.458083219594,-11.6722036701784 -170.204451047434,-11.7276418531269 -169.944412960437,-11.7852131087715 -169.693464668292,-11.8396462344707 -169.804012023764,-11.7111387048259 -169.912694201427,-11.5854837503185 -169.621251239025,-11.659783000257 -169.013804457992,-11.8916996967095 -168.425719151636,-12.1130209361705 -168.291281302805,-12.1053474842988 -168.162262202847,-12.0955336109482 -168.384042343591,-11.9090658739947 -168.168425169458,-11.9433917853273 -167.960602727646,-11.9732895259482 -167.803738256714,-11.9783696667073 -167.652926810216,-11.9794756861433 -167.507157096425,-11.978315851889 -167.040457435311,-12.1383593549365 -166.588981666536,-12.2895580277406 -166.09587511257,-12.4588426655316 -165.618850287296,-12.6182854505981 -165.857141230967,-12.4190358223858 -165.980413125469,-12.2791197620744 -166.101540138061,-12.1413004214848 -165.49964952185,-12.3672797182335 -164.91701661543,-12.5804828872972 -164.879846512426,-12.5193427861599 -165.111989152905,-12.324149273344 -165.338780298755,-12.1335452142021 -165.569642261915,-11.9422571292162 -165.795127899775,-11.7566503216024 -166.085239199463,-11.5403706295402 -166.495296774061,-11.2658843603411 -166.89455049751,-10.9996739531339 -166.955969477304,-10.9046464541122 -167.016806253359,-10.8117306300931 -166.812754904868,-10.8511106792556 -166.582459170246,-10.9026689910186 -166.360202578746,-10.9517663739477 -166.514776661802,-10.8117392021892 -166.665980641723,-10.6743976440493 -165.99028536827,-10.9507255183307 -165.386366615379,-11.1895871930481 -164.801537550136,-11.4172482606536 -165.012892325817,-11.2434874230955 -165.219298851356,-11.0743513270598 -165.552363118514,-10.843276885568 -165.810567668493,-10.6529083037045 -166.062306123531,-10.4672873421118 -167.208939305464,-9.83452102794802 -168.322772203611,-9.22500268585541 -168.358771175926,-9.16001580955845 -168.497647095999,-9.04490161035619 -168.63328971392,-8.93323837341357 -168.681948733556,-8.86409965251438 -168.73002839285,-8.79737521985627 -168.955316750988,-8.64384761246738 -169.197206020802,-8.48256141819924 -169.432710075123,-8.32603197689041 -168.903532507035,-8.55390858149523 -168.390725117621,-8.77164797711638 -168.99242374806,-8.43002529642863 -169.390431566534,-8.19264469351398 -169.777394988715,-7.96295393806026 -169.327469635578,-8.15498054391371 -168.891495874543,-8.33647432796473 -168.522110040415,-8.48405381233827 -168.213070722656,-8.59976661821949 -167.913925297612,-8.70982105736056 -167.574490234028,-8.83869100010252 -167.245888053001,-8.96059630781925 -167.139503756831,-8.97064333278332 -166.703167242204,-9.14587441872922 -166.280572241781,-9.31137496556458 -165.906022079956,-9.45265071506273 -165.543443273371,-9.58666203121455 -164.773897862356,-9.92282319997669 -164.490640124657,-10.0110705998785 -164.216793155765,-10.0946549561023 -163.915778672323,-10.1904771394666 -163.624725642737,-10.2804373970701 -163.183003957891,-10.4434027559115 -162.630563398039,-10.6607133954367 -162.095608190404,-10.8686554751788 -162.381065691736,-10.662594358525 -162.659290056711,-10.4636845642646 -162.703724444844,-10.3830091996831 -162.931503060204,-10.2115407222472 -163.153645398439,-10.0449052854194 -162.290681953746,-10.4222603543025 -161.45430405685,-10.782820360808 -161.400100982409,-10.7487083130683 -160.953484096646,-10.9116085030626 -160.521248765671,-11.0660799488046 -160.200694065005,-11.1621716063537 -159.890861810392,-11.2514589441366 -160.272069982186,-10.9939529623243 -160.105404174329,-11.0134240897943 -159.944899166202,-11.0293439024018 -160.058439388304,-10.9089104999542 -160.169841931708,-10.7910092195893 -160.037739761663,-10.7960521189632 -160.289520733772,-10.6091973106116 -160.535019958942,-10.427035663674 -160.476499291563,-10.3980595009902 -160.420830015084,-10.3670543262823 -159.910519909876,-10.5648141439795 -159.434423892169,-10.7433272084909 -158.973565289766,-10.9112769032258 -159.439837183912,-10.6142254309829 -159.893534676379,-10.3270946736818 -160.600430757271,-9.91710891332045 -161.254244908797,-9.53734424616562 -161.889720542015,-9.17008717217537 -161.40657328943,-9.36690404088468 -160.938588208237,-9.55383920677489 -161.22660597033,-9.36111696186915 -161.58331605574,-9.13609974142967 -161.930363453376,-8.9182631376342 -161.878874134741,-8.90091502109971 -161.829737066153,-8.88311633216561 -161.779192277821,-8.86663000211044 -162.202804301605,-8.61354899676945 -162.614669686063,-8.36788159035838 -162.478244921025,-8.39780547779348 -162.346594348675,-8.42573296238385 -162.161926515644,-8.48067509428672 -162.041758276281,-8.50158914341175 -161.925899943794,-8.52187888222852 -161.741396509046,-8.57501710836002 -161.563106345668,-8.62509294965964 -160.549751396905,-9.09185715259086 -158.907889850213,-9.86911516544959 -157.31546992823,-10.6128531148746 -157.0560299098,-10.6821400257493 -156.805431110295,-10.7485027385518 -157.273284054299,-10.4527153763113 -157.987179687928,-10.036699392186 -158.681077611234,-9.63562087949692 -158.553126435654,-9.64927401411761 -158.429929859551,-9.6606566955961 -157.800547147218,-9.92448831649868 -157.807202267448,-9.98374491618871 -157.812457777881,-10.0356690377244 -157.734507247607,-10.1258220403715 -157.657880789205,-10.2097135707341 -157.346631960264,-10.4077723553624 diff --git a/data/Gemini_Portugal_October_2023/Trajectories.mat b/data/Gemini_Portugal_October_2023/Trajectories.mat deleted file mode 100644 index 4f1f675556cc16344ee874bded115e13fac955f4..0000000000000000000000000000000000000000 Binary files a/data/Gemini_Portugal_October_2023/Trajectories.mat and /dev/null differ diff --git a/data/Gemini_Portugal_October_2023/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_configABK_Gemini_Portugal_October_2023.csv b/data/Gemini_Portugal_October_2023/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_configABK_Gemini_Portugal_October_2023.csv deleted file mode 100644 index 62dfad8f2fcf6cf373b9f94dbc785958c2440158..0000000000000000000000000000000000000000 --- a/data/Gemini_Portugal_October_2023/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_configABK_Gemini_Portugal_October_2023.csv +++ /dev/null @@ -1,2 +0,0 @@ -ABK_FREQUENCY,REFERENCE_DZ,STARTING_FILTER_VALUE,CHANGE_FILTER_MINIMUM_ALTITUDE,CHANGE_FILTER_MAXIMUM_ALTITUDE,ABK_CRITICAL_ALTITUDE,ABK_REFERENCE_LOWEST_MASS,DELTA_MASS,ESTIMATED_MASS,N_FORWARD,ABK_DELAY_FROM_SHUTDOWN -10,10,0.9,1000,3000,2990,26,0.4,28.7609345558142,0,0.5 diff --git a/data/Gemini_Portugal_October_2023/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_references_Gemini_Portugal_October_2023.csv b/data/Gemini_Portugal_October_2023/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_references_Gemini_Portugal_October_2023.csv deleted file mode 100644 index c1bd8d271e82315874d6a5937cc8933cc1808244..0000000000000000000000000000000000000000 --- a/data/Gemini_Portugal_October_2023/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_references_Gemini_Portugal_October_2023.csv +++ /dev/null @@ -1,302 +0,0 @@ -Heights,Vz_closed_m26,Vz_closed_m26_4,Vz_closed_m26_8,Vz_closed_m27_2,Vz_closed_m27_6,Vz_closed_m28,Vz_closed_m28_4,Vz_closed_m28_8,Vz_closed_m29_2,Vz_closed_m29_6,Vz_closed_m30,Vz_open_m26,Vz_open_m26_4,Vz_open_m26_8,Vz_open_m27_2,Vz_open_m27_6,Vz_open_m28,Vz_open_m28_4,Vz_open_m28_8,Vz_open_m29_2,Vz_open_m29_6,Vz_open_m30 -0,288.586220863909,287.780740824828,287.00408233524,286.253658863337,285.527984427756,284.827114474373,284.148465770862,283.491180541497,282.855203532413,282.238455642096,281.640096875438,509.609642386787,503.975772807347,498.929569325598,493.990203474662,488.883143431683,484.180912315729,479.565288278894,474.898090580001,470.478637061219,466.080312902626,461.833463566499 -10,287.898662098882,287.099541339876,286.328149014437,285.582935039404,284.862954444093,284.166568782725,283.492625698079,282.840342643516,282.208381468704,281.595813992799,281.001963945753,507.424921668861,501.812982216719,496.767585793179,491.828580812489,486.741683128799,482.038991196189,477.422507290328,472.773971148122,468.352942856281,463.972279403399,459.723202317093 -20,287.212395921,286.41908946379,285.65311322416,284.913421192935,284.198434081014,283.506836151554,282.837793755301,282.189939219625,281.562260246201,280.954020909773,280.364167423016,505.235417304708,499.648909039252,494.605602260761,489.666958150315,484.600222825916,479.89707007665,475.27972630176,470.649851716243,466.227248651343,461.860689190693,457.606208846732 -30,286.526978529206,285.739236554864,284.978883891646,284.244429755096,283.534379190503,282.847805507095,282.183356292178,281.539909875864,280.916672163221,280.312568974875,279.726675443838,503.034943027185,497.469497512945,492.428324061154,487.492085629004,482.445968230076,477.742659780456,473.123872331406,468.510637214189,464.08455458387,459.736625045488,455.480874916992 -40,285.842150970128,285.060124595885,284.30528213538,283.575920557809,282.871004566204,282.189216430438,281.529307088714,280.890414318836,280.271454378861,279.671423260388,279.089546868063,500.834468749662,495.290085986638,490.24854191121,485.311790586231,480.285962312296,475.581900682406,470.962234167831,466.368600777981,461.941433639007,457.612560900283,453.352371830849 -50,285.157978573907,284.381766229303,283.632179971166,282.908058195823,282.208140636193,281.531030314633,280.875785584211,280.241325927553,279.62655520568,279.030647878121,278.452787053187,498.618113944878,493.098968284044,488.060797780013,483.125968992531,478.120421022773,473.415652735453,468.794049666586,464.216840488524,459.785583175471,455.470940138654,451.207945562964 -60,284.474709801636,283.703925394633,282.959677545797,282.240790148512,281.545694905459,280.873357919538,280.222716960318,279.592569002512,278.982028811925,278.39026587633,277.816282874054,496.397486103931,490.899770246193,485.861170501566,480.925769673459,475.940869157335,471.235288880217,466.612747299131,462.055489576499,457.623088497731,453.327842786572,449.063519295079 -70,283.791977088241,283.026621261631,282.287869708741,281.573956089711,280.883739688069,280.21619426805,279.569993139493,278.944182020757,278.337926636347,277.750150735117,277.1800297809,494.170674755293,488.697878078471,483.66154322312,478.725570354388,473.761317291897,469.054925024982,464.431444931675,459.890398594259,455.453396434549,451.172152293238,446.9013447681 -80,283.109777487519,282.350131142252,281.61651221103,280.907578555961,280.222360721676,279.559389255006,278.917630215084,278.29625722825,277.69410297214,277.110297864687,276.544140860887,491.929431719142,486.478444794809,481.442232592133,476.507616943574,471.563729544789,466.856065888781,462.230076354941,457.709303627173,453.271097056847,449.009602185334,444.737405190377 -90,282.428377291984,281.674108281652,280.945601222693,280.241858148516,279.561354743356,278.90293848416,278.265775634798,277.648623041153,277.050553200879,276.470819202959,275.908490738777,489.68818868299,484.259011511146,479.222310257273,474.287062173495,469.364192920549,464.655657167792,460.028668328011,455.528208660086,451.086882853213,446.839164065304,442.559955866309 -100,281.747539886017,280.998549020551,280.275370483399,279.5765256071,278.900717406349,278.247032250294,277.614224214255,277.001274825396,276.40738429282,275.831598272272,275.273054387045,487.429238962561,482.025055141761,476.990654288684,472.056238831795,467.153463101622,462.443131906913,457.813101825328,453.328937568448,448.884334465912,444.65672878177,440.376069073982 -110,281.0671837871,280.323627224707,279.605579582445,278.911576660289,278.240612420036,277.591451883339,276.962971318581,276.354310064864,275.764497027546,275.192601626747,274.637852681207,485.166904498255,479.784923819499,474.749972854998,469.814863263518,464.933489252283,460.222224497445,455.591132908247,451.127655686155,446.681786078611,442.470831109738,438.182614454664 -120,280.387407229044,279.649239567826,278.936187799496,278.247139218565,277.58088607792,276.936183088644,276.312099618675,275.707656621825,275.121844979293,274.55384530893,274.002929286486,482.895793612453,477.538500272555,472.505314347552,467.570493579715,462.708942346392,457.995339187898,453.360655399618,448.91323834398,444.461627332535,440.268064819802,435.978333066578 -130,279.7082773894,278.975267136016,278.267276492646,277.583144220135,276.921484867578,276.281287465598,275.661575574432,275.061249762864,274.479435807885,273.915388848052,273.368183753301,480.611876252549,475.277193456517,470.243395051334,465.307817083727,460.468064568518,455.753464967995,451.117655998362,446.691312843572,442.238371718364,438.065298529867,433.768105887545 -140,279.029579475799,278.301732197976,277.598884142771,276.919488442538,276.26244198327,275.626783533943,275.011309934754,274.415084556813,273.837352673885,273.277120141851,272.733610819396,478.327931291277,473.015886640479,467.981475755117,463.045140587739,458.227186790643,453.511489488359,448.871517365548,444.461002684007,440.001751154888,435.842402615551,431.542968474128 -150,278.351308766089,277.628807399283,276.93084564843,276.256168100405,275.603843711784,274.972550298925,274.361297360169,273.769276939266,273.195467586158,272.63903387341,272.099247551064,476.021923665972,470.734655098985,465.701390357793,460.764715672941,455.966726926599,451.248165420381,446.607002902887,442.217962428053,437.757315593765,433.618845508887,429.315162609588 -160,277.673662898279,276.956251650619,276.263155868095,275.593355544474,274.945528918423,274.318582408503,273.71164584036,273.123678075466,272.553775180759,272.001164817296,271.465072712681,473.715916040667,468.451680035135,463.417739074453,458.480242694573,453.704463666441,448.984841352402,444.342488440225,439.970974423504,435.503427587659,431.378481911032,427.06869309028 -170,276.996448550162,276.284059889011,275.595957609402,274.930839754766,274.287492253421,273.664973748123,273.062231364925,272.478282563137,271.912305222802,271.363501749061,270.83103579488,471.395812860548,466.156091092762,461.122719025851,456.184296859917,451.428231460639,446.705058831092,442.057884100222,437.706333216476,433.237324229471,429.133659598837,424.822223570972 -180,276.319614064233,275.612330822008,274.929115559082,274.268615400963,273.629807561373,273.011637110526,272.413031353518,271.833111869879,271.271062512958,270.725985863209,270.197131110021,469.067190993009,463.850939056993,458.816825595374,453.87751574135,449.144085667753,444.419786311826,439.771354362209,435.441692009448,430.965321528772,426.874987056025,422.554168323409 -190,275.64320194565,274.941031042795,274.262578794894,273.606729280416,272.97243720167,272.358526512,271.764055030573,271.188194026388,270.629976635532,270.0886114093,269.563392853333,466.732253399234,461.540228589503,456.506085128147,451.565241287759,446.851277504192,442.122821379063,437.468952252468,433.155097575502,428.677046732013,424.608409939813,420.285875331563 -200,274.967306359065,274.270050960442,273.596358825189,272.945208312638,272.315304937694,271.705636053157,271.115362233558,270.543443071301,269.989041783055,269.451412060102,268.929778362501,464.380475961633,459.212374179385,454.177422643295,449.235623552527,444.544735949649,439.815085554211,435.15989069906,430.868353506296,426.38603801305,422.330544005007,417.997996134914 -210,274.291745456724,273.59938474878,272.930564696845,272.283937997822,271.658404848606,271.053062066147,270.466846804976,269.89885314671,269.348289074355,268.814350998107,268.29626260467,462.028698524032,456.884519769267,451.848760158443,446.906005817294,442.234505520952,437.50006931669,432.838799015379,428.562868378813,424.075071647066,420.041706610993,415.707372348039 -220,273.616513469937,272.929161250621,272.265034297782,271.622912406729,271.00181969933,270.400678192818,269.81850284404,269.254450288301,268.707692103998,268.177397333938,267.662839564953,459.654402651257,454.53463687772,449.498157497884,444.553168835269,439.905038077806,435.169338357346,430.506672052788,426.253503127138,421.764105281081,417.743717114874,413.398715774185 -230,272.941696876582,272.2592427188,271.599761705541,270.962195019035,270.345458548877,269.748476675393,269.170348199783,268.610224108348,268.067211573453,267.540544984886,267.029530230747,457.278910178872,452.18353726472,447.146181552623,442.20016843275,437.57557063466,432.835355629595,428.165951632717,423.92819571807,419.42992360621,415.432097391687,411.085237207228 -240,272.26725575315,271.58959563136,270.934784323438,270.301742590568,269.689291113532,269.096463410611,268.522395304705,267.966123805102,267.426841336539,266.903815623778,266.396295698718,454.887538834898,449.816316323471,444.777594023167,439.828689744162,435.223552711896,430.481079968165,425.810207844927,421.595673822288,417.095728314616,413.113005727921,408.754800294348 -250,271.593100285433,270.92022328447,270.270121116701,269.641495727377,269.033311047808,268.444681832378,267.874578136411,267.322143173905,266.786602286521,266.267173262644,265.763121490062,452.487752895394,447.441410462969,442.401741918636,437.451742251337,432.870611595354,428.126804306735,423.448869297884,419.249563391382,414.740059746588,410.778064305182,406.417925553555 -260,270.919224108868,270.251223943626,269.60567583636,268.981448055904,268.377589839484,267.793046262921,267.226890437508,266.678300425713,266.146464723144,265.630599327035,265.130001335033,450.078384691407,445.055935850786,440.014229065661,435.060656209248,430.49877406281,425.748777991176,421.068938634538,416.893331475197,412.382080169237,408.436840523143,404.064652831497 -270,270.245723128346,269.582455420936,268.941442092373,268.321657848301,267.722029611709,267.141550398746,266.57934532844,266.034576432697,265.506404053248,264.994087476493,264.496939984352,447.653707006202,442.656643646992,437.61391897076,432.659177986784,428.121793027373,423.370389513974,418.685939264133,414.525385151548,410.003865885364,406.078019928259,401.703822326163 -280,269.57250031796,268.913911323429,268.277459344966,267.662061685559,267.066619783803,266.490199278547,265.931939590842,265.390938184533,264.866413868941,264.357643958781,263.863912175847,445.225368885549,440.251949177349,435.206488601775,430.247466008194,425.729126105576,420.970828527581,416.281232181787,412.144871106741,407.621527836035,403.713579617361,399.326602628489 -290,268.899515387136,268.245605618246,267.61371062969,267.002627096541,266.411353693425,265.839012143103,265.28462885112,264.747379209668,264.226500917526,263.721244382128,263.230907042583,442.775180399902,437.827670599998,432.781118665224,427.820853307689,423.327519596187,418.567739721121,413.875472682885,409.754000694777,405.219652429236,401.330303447683,396.941237737723 -300,268.226761537411,267.577582045634,266.950135162119,266.343347377109,265.756280854825,265.187929679045,264.637406578427,264.103905369404,263.586644062941,263.084875053047,262.597918111934,440.324991914256,435.402736359387,430.352723613938,425.387440561636,420.912958528149,416.145552044849,411.445379236378,407.348612816941,402.812362025971,398.941504395982,394.538900782669 -310,267.55432207993,266.909743915786,266.286726205178,265.684263578742,265.101322844966,264.536945301295,263.990275914121,263.460501976667,262.946825382797,262.448529426716,261.964937045243,437.850504267539,432.95285050882,427.901671024402,422.935068580579,418.486120782154,413.7171550926,409.015285789871,404.933671368707,400.385649997378,396.533176443231,392.128402974053 -320,266.882093464359,266.242084469086,265.623511737382,265.025321323065,264.446472986432,263.886057079912,263.343232745932,262.817145057146,262.307038262534,261.812201207212,261.331949187293,435.374164165722,430.502964658252,425.450618434865,420.47882042872,416.048542394406,411.271188954579,406.559589028234,402.502797442722,397.952792742171,394.118815051323,389.69971569495 -330,266.210056258542,265.574613044018,264.960471345017,264.366497750264,263.791724377611,263.235276678222,262.696244739712,262.173827929393,261.667277836696,261.175875170984,260.698947071046,432.877928543045,428.030463575801,422.973825663568,418.000042309461,413.595846490858,408.816854780701,404.103477908652,400.062575576641,395.500004734178,391.684818374949,387.263465591724 -340,265.538203347714,264.907355096571,264.297560654919,263.707785907456,263.137101753975,262.584560535991,262.049305150436,261.530546199365,261.02752988425,260.53954194944,260.065924056816,430.374773204664,425.554327692776,420.49644565415,415.519760477688,411.134065497594,406.345894874402,401.621984435604,397.605581908303,393.040944538428,389.243625804332,384.807128195535 -350,264.866593677256,264.240238380306,263.634772669723,263.049205800162,262.482555962933,261.933901848479,261.402408695455,260.887288940724,260.387782163065,259.903194830082,259.432867140206,427.855617011788,423.05870631475,417.995746995291,413.013906246374,408.654862350152,403.864972130676,399.139201951021,395.138803852625,390.560773285876,386.783321750174,382.344484588643 -360,264.195146157195,263.57325586138,262.97211886957,262.390724102385,261.828077097049,261.283293590948,260.755550868297,260.244039690588,259.748027889656,259.266823235085,258.799758223526,425.324958904977,420.555654731011,415.491371788398,410.508052015059,406.167627378226,401.367735547331,396.630596803431,392.655034242617,388.07485143771,384.313959783222,379.859126319206 -370,263.523844867759,262.906405848496,262.309589958476,261.732319253666,261.173658069406,260.632738854333,260.108709205376,259.60079159662,259.108258617005,258.630407444013,258.166598760492,422.781642058782,418.03568650418,412.965509084082,407.974700144991,403.661244667588,398.859549539183,394.120465798301,390.160353579624,385.565917412691,381.826686943567,377.369425120258 -380,262.852682461092,262.239713041495,261.647148295271,261.073984109323,260.519302651202,259.982209804136,259.461876788008,258.957537626986,258.468453902402,257.993947707724,257.533381967423,420.222768565629,415.505029529476,410.43344677233,405.441075586097,401.147233977863,396.334681389368,391.583360382145,387.649128235628,383.052451481958,379.327743530001,374.853599700475 -390,262.181690203643,261.573118378208,260.984786682726,260.415720659392,259.864986894425,259.331698488883,258.815046513538,258.314258488532,257.828612176829,257.357437169563,256.900100912352,417.653979025279,412.959417768426,407.881090121278,402.880366126576,398.612975019309,393.798532936544,389.045065524428,385.125123320295,380.513298205257,376.812816640767,372.334239341732 -400,261.510820647948,260.906614615031,260.322502207509,259.757514258141,259.210697781828,258.681197737483,258.168204086994,257.670949515864,257.188726511993,256.720868822014,256.266717248716,415.066151194439,410.400440509303,405.320623479702,400.318251588287,396.07079189743,391.244601633319,386.478106354091,382.585737702724,377.971372011957,374.282801103006,369.788333555992 -410,260.840053368651,260.240194276699,259.660296310172,259.09934385081,258.55642807672,258.030697249624,257.521338854151,257.027603817981,256.548789825832,256.084210271581,255.633245060331,412.470500139337,407.827813754316,402.740366487098,397.728742624518,393.507934438695,388.679765860368,383.909048174233,380.030906726842,375.400669871106,371.739509873449,367.23610658687 -420,260.169380841406,259.573870573813,258.99813621845,258.441202138481,257.902170021435,257.380182758646,256.874444479405,256.384214239492,255.908775914893,255.447466541434,254.99967968345,409.852951360349,405.239774859592,400.150751711569,395.137391749788,390.936102225562,386.095258033548,381.312556411552,377.462630323277,372.8261208609,369.176847740402,364.661002218353 -430,259.498810397205,258.90760719814,258.336014575212,257.783081936486,257.247909042323,256.729647097024,256.22751373551,255.74076074068,255.268680530422,254.810635703311,254.366014071071,407.228967982454,402.63868186779,397.541106363524,392.517557870284,388.343897169825,383.500983084866,378.711123410401,374.87538599312,370.225673053493,366.604455610322,362.074232549361 -440,258.828324585078,258.241392513359,257.673923832175,257.12497274094,256.59363527133,256.079082967431,255.580532414637,255.097230136328,254.628504442583,254.173710635055,253.732227297262,404.580902575784,400.020812195203,394.921571729782,389.896196247959,385.740853899029,380.884298092846,376.084315846648,372.277461016086,367.616810783591,364.007483046097,359.46916218185 -450,258.157898218956,257.57521891055,257.01185827651,256.466859560213,255.939341343186,255.428481308385,254.933479364157,254.453625573923,253.988240454748,253.536676465664,253.098291300009,401.927028450437,397.389716531286,392.280962857935,387.244422879838,383.118523947342,378.259803766554,373.448802641371,369.656124808377,364.985827641031,361.405099032837,357.210451549315 -460,257.487523634052,256.909081828161,256.349799621623,255.808734963668,255.285019735813,254.777814701444,254.286359459099,253.80993978321,253.347880171374,252.899495692831,252.464226725808,399.247620166732,394.741217729261,389.630707295172,384.590649730166,380.482616553369,375.609247768619,370.790866109334,367.027764810637,362.340863471698,358.772183655583,355.196852880719 -470,256.817193933586,256.242966561707,255.687738744592,255.150591359174,254.630646850237,254.127088719904,253.639165356644,253.166165363519,252.707376045896,252.262191996616,251.830026413964,396.562203162331,392.078491918615,386.957466593273,381.906823895303,377.829354760357,372.953724063054,368.119466969215,364.370560767873,359.67852502234,356.266862859669,353.204550288416 -480,256.146905511485,255.576858741918,255.025667985743,254.492412620111,253.976219953076,253.476295949683,252.991889580766,252.522261599335,252.066754964935,251.624758141405,251.195683090579,393.85059358378,389.398534916608,384.275658165644,379.218457192927,375.158832817548,370.267503611147,365.429556785193,361.707708674336,357.402618372581,354.244816266791,351.218475385058 -490,255.476634703717,254.91075064462,254.36357699977,253.834185604726,253.321734073294,252.825428840363,252.344501630319,251.878241519025,251.426009618383,250.987186776666,250.561162026974,391.131881266322,386.702454119557,381.56801771591,376.502114231958,372.473801053634,367.576463790111,362.720358636217,359.015997190965,355.343826537398,352.234551085523,349.257900878364 -500,254.806373725305,254.244634386209,253.701446021665,253.175907830648,252.6671815873,252.174466972112,251.696997382871,251.234103397672,250.785132579276,250.349452172467,249.926451162463,388.387178102351,383.990177519796,378.853792004741,373.777267503892,369.766810001607,364.856324281717,359.997596939581,356.513050610291,353.30878101307,350.239625726892,347.304957638565 -510,254.136114625855,253.578491699191,253.039272948196,252.517571602641,252.012551672162,251.523389620006,251.049381667345,250.589839732211,250.144107897155,249.711526691104,249.29156941531,385.633310586076,381.258912681343,376.109877267195,371.027505475315,367.049137314411,362.126615077498,357.752252960422,354.444015185599,351.280217528359,348.263019943685,345.370743518711 -520,253.465845747367,252.912315001341,252.377050014374,251.859169091512,251.357808275009,250.872207739406,250.401646905049,249.945442907455,249.502891000572,249.073435495806,248.65650940158,382.854585854886,378.513421044129,373.361950065203,368.264177237329,364.303711120833,359.37282139287,355.643259884598,352.389928692661,349.276882900909,346.295128412485,343.45113692548 -530,252.795551856545,252.246097501002,251.714769317279,251.200668167459,250.702967674732,250.220913676639,249.753785402969,249.30085654251,248.861513864104,248.435171126116,248.021263637033,380.063588044822,375.745031468509,370.580157858856,365.480057967103,361.552252731035,356.924008519528,353.563032336174,350.349278816701,347.282954028817,344.352437743769,341.543075715 -540,252.125226709496,251.579831223374,251.052410854964,250.542072058967,250.048022143532,249.569499661254,249.105754775491,248.656113717037,248.219968950798,247.796726019824,247.385796691564,377.249876131462,372.965393482524,367.792829067303,362.676123409413,358.766545193916,354.802676447944,351.489513712271,348.330376013918,345.307198961807,342.417146813778,339.656859732101 -550,251.454862261849,250.913506783953,250.389957945845,249.883378677865,249.392963834091,248.917937603888,248.457563063253,248.01120883377,247.578248620343,247.158076501123,246.750089537913,374.419649297566,370.157818776249,364.975813585916,359.856670512295,356.118626975986,352.70222435019,349.438599461306,346.318810206629,343.348130152361,340.502726553407,337.778404670848 -560,250.784450332072,250.24709098644,249.727415851019,249.224580100759,248.737778948277,248.2662101473,247.809215350779,247.366134174245,246.936342014196,246.519182264964,246.114169093758,371.569944878349,367.343065304472,362.146880666344,357.51847874542,353.984150787671,350.610639257308,347.401290705086,344.334596823535,341.399738209924,338.60171118922,335.921769792336 -570,250.113967765212,249.580594541365,249.064776572066,248.565668288869,248.082425003929,247.614333104532,247.160703841502,246.720881919884,246.294185601789,245.88007943343,245.478027758702,368.698257494081,364.494116625241,359.293629103456,355.338773909569,351.863021348763,348.54696855868,345.37928431873,342.358866041532,339.475590010752,336.713588779879,334.076799315064 -580,249.4434062468,248.914009376651,248.402031992074,247.906601156575,247.42692826294,246.962298601083,246.512020636913,246.075395717766,245.651825585463,245.240760327925,244.841657840182,365.811513316135,361.638642904865,356.786579540237,353.189221740295,349.759003654462,346.490881417375,343.378440519449,340.402524687995,337.559553167718,334.846725768884,332.245332411955 -590,248.77276495004,248.247327298256,247.739157475745,247.247390240082,246.771280773199,246.310098658488,245.863126793677,245.42970055781,245.009254208158,244.6012171764,244.205045556645,362.895991086526,358.750589157854,354.591113001073,351.046941506251,347.675733785387,344.458503475534,341.385746683793,338.462651260183,335.664956257393,332.988253468665,330.433576452801 -600,248.1020356051,247.580539997263,247.076133535446,246.588035682796,246.115474476385,245.657712383236,245.214015180714,244.783799261758,244.366463617944,243.961442116767,243.568122981025,359.971115590187,356.083253109019,352.419525304052,348.929628625834,345.602071381508,342.439910811355,339.420818950101,336.533852132922,333.783937382032,331.151575895097,328.630369705501 -610,247.431209823743,246.913599748953,246.412973479721,245.928529346804,245.459501212963,245.005099453911,244.56470298518,244.137683897462,243.723445871515,243.321366031032,242.930944472824,357.669187933749,353.870967447124,350.256051902301,346.826322911187,343.55695707933,340.436791608121,337.464945855666,334.629706575663,331.915657182216,329.32710765804,326.847945524382 -620,246.760259791467,246.246531132867,245.749669091509,245.268862990681,244.803304016836,244.352291841898,243.915182194437,243.491346439932,243.080150100912,242.681029682704,242.29350221031,355.410468439794,351.676800340081,348.124051781366,344.740048734006,341.52025383352,338.455730371588,335.528037845203,332.734314091479,330.069364534841,327.515492813803,325.077605360227 -630,246.08917461784,245.579326071173,245.086212047702,244.609001755053,244.146912717056,243.69928145389,243.265444701401,242.8447555602,242.436582741802,242.040433728394,241.655788284133,353.180213764588,349.497314314785,346.000248460503,342.675985257744,339.50657766438,336.483562195411,333.608811775095,330.859378007224,328.232014201998,325.724611655581,323.318995802223 -640,245.417961350252,244.911976159481,244.422589557716,243.948934506902,243.490324825531,243.046060100371,242.615479827191,242.19788094829,241.792760211902,241.399570177345,241.01779469964,350.962895103229,347.343904454504,343.900445035594,340.620784858042,337.508427323325,334.537869174044,331.699495400321,328.999551241925,326.414985456923,323.942743139153,321.581011658775 -650,244.746611503671,244.244472889596,243.75874985768,243.288677236261,242.833532070066,242.392619499009,241.965218465812,241.550755903181,241.148674438448,240.758430952326,240.37948520318,348.766270826308,345.19911311928,341.817005015463,338.595737134498,335.524210824103,332.603291362332,329.816606245997,327.150843615768,324.611980173017,322.179778385056,319.852009428222 -660,244.075116486388,243.576777070515,243.094727110568,242.628221588123,242.176526083836,241.738907596495,241.314711727687,240.903372269538,240.504317260929,240.116999339666,239.740830308227,346.590917681332,343.084787525708,339.74864746564,336.580140621484,333.564439611112,330.685641326042,327.943026713935,325.326133939369,322.819821342431,320.43094385193,318.139509108485 -670,243.403462190862,242.908888255162,242.430512878563,241.967559110865,241.519280170026,241.084936553164,240.663951374386,240.255721802898,239.859680433197,239.47520870677,239.101868395437,344.427779629193,340.981515177431,337.705594988865,334.585111424218,331.614215078529,328.788295206994,326.087423977051,323.510830338601,321.050609835677,318.691522656753,316.442179238426 -680,242.731601926257,242.240815276248,241.766098625055,241.306681259482,240.86175856365,240.430717203859,240.012929076868,239.607796171844,239.214695118487,238.833114737822,238.462591322736,342.29469396856,338.89931855407,335.672167569655,332.608898864563,329.687518762723,326.900721646597,324.249770374713,321.713003583164,319.290787806976,316.97509794696,314.754119030829 -690,242.059565272064,241.572549512129,241.101475718004,240.645526760609,240.203994314902,239.776241134374,239.361636417704,238.959551590289,238.569397762742,238.190709206905,237.822990863777,340.171102025203,336.837550191535,333.665467119822,330.643401151023,327.775443224875,325.037583290858,322.421972887701,319.93221745788,317.546743449801,315.267953420163,313.085615153423 -700,241.387343521742,240.904082243494,240.436612605034,239.984127855284,239.545978923896,239.121499840574,238.710056108974,238.310976548053,237.923792719942,237.547983802649,237.183058709229,338.074018706995,334.787055487954,331.6724565405,328.706199719255,325.876707847857,323.186762548123,320.617898701196,318.161250695195,315.819973296134,313.573984937241,311.428382406031 -710,240.71492786862,240.235404656468,239.771485187761,239.322483759271,238.887703799142,238.466484730388,238.058125934798,237.66209798592,237.277871592836,236.904930129541,236.542771066273,335.993080816462,332.766581161624,329.695827451256,326.779096653892,324.002251599742,321.350025578528,318.825356451455,316.412055372697,314.10288866785,311.898405326021,309.781066680681 -720,240.042309409159,239.56645766908,239.106118926007,238.660585793149,238.229160259617,237.81113771521,237.405896716328,237.012907419916,236.631625898799,236.261539709023,235.902070558956,333.92836829332,330.756386365411,327.742809977305,324.870998316338,322.138016341665,319.535314372913,317.046168935459,314.674793161591,312.404701455147,310.232302022199,308.153917700709 -730,239.369462601156,238.897271440744,238.440505051927,237.998425186234,237.57032192888,237.155477384747,236.753359882045,236.363396279377,235.985047070947,235.617735724277,235.261010803582,331.889828096202,328.767725345721,325.800353327532,322.98240187871,320.293425096761,317.730811875001,315.28816058763,312.94903502188,310.719755016769,308.581559645252,306.535979420938 -740,238.696353981009,238.227844274398,237.774634704538,237.335993078427,236.91114650849,236.499514151382,236.100506772341,235.713555908094,235.33808700003,234.973566266822,234.619583319089,329.862030957418,326.798532907807,323.882093165402,321.104478557438,318.466092170085,315.945054485553,313.540238596559,311.244706267362,309.044662786617,306.946040496864,304.929411340923 -750,238.023011537502,237.558167218218,237.108498931659,236.673230048645,236.25167324126,235.843239265676,235.447328640688,235.063368737178,234.690738269782,234.329032118184,233.977779540018,327.860370597606,324.840366491686,321.979053168164,319.251319894511,316.649400946248,314.175787658696,311.80900279502,309.550255602165,307.390024842331,305.32008126909,303.340535745834 -760,237.349426227534,236.888231227246,236.44207494139,236.010159390424,235.59189328707,235.186643889813,234.793816654612,234.412768293394,234.043028153027,233.684124623628,233.335590817054,325.874613766604,322.91108974255,320.089017394159,317.411110122778,314.856432810904,312.417015577294,310.094630641065,307.869583154719,305.746023177275,303.710325859194,301.760885871248 -770,236.675588912774,236.218027165104,235.775315577073,235.34678737242,234.931797715868,234.529719098599,234.139912521392,233.761810049502,233.39494790469,233.038835043371,232.693008417418,323.903524778898,320.993274120755,318.224654092322,315.584438397417,313.075693646298,310.679722307228,308.390517422119,306.207009611332,304.112292863065,302.113867625296,300.192909916966 -780,236.001490361473,235.547507177009,235.108260562674,234.683104971432,234.271377508703,233.872442946698,233.485630966957,233.110485169017,232.746488693385,232.393154552971,232.049992207129,321.959140765007,319.092677366567,316.371285635082,313.781116587433,311.307558055465,308.955127766916,306.704767598947,304.554393684725,302.498531947568,300.526953106362,298.641225167899 -790,235.327121249993,234.876674043144,234.440900780982,234.019103073741,233.610623558555,233.214759691772,232.830986567487,232.458784727815,232.097641601818,231.747074243577,231.406515898564,320.026186963001,317.214416047285,314.535657674968,311.988666499839,309.561893454942,307.241171552625,305.033077802341,302.916419021045,300.894381280608,298.955971408268,297.098696054931 -800,234.65241294126,234.205542161464,233.77322702254,233.35477247598,232.94948183033,232.556717696859,232.175970304987,231.80669971455,231.448397627037,231.100508071835,230.762617872681,318.114139565565,315.347578754911,312.719953450946,310.212938166254,307.826874723073,305.549788275512,303.371695483218,301.294516435781,299.300750525348,297.397402414638,295.567200392841 -810,233.977409799487,233.534102225854,233.105229986559,232.690101112019,232.287960778818,231.898307848968,231.520573072858,231.15422103091,230.798707130262,230.453521712797,230.118289193558,316.221641890452,313.502205752244,310.915527749271,308.456243410031,306.106421226705,303.868811391155,301.728968747046,299.682544721116,297.725663089859,295.848275532871,294.051487864107 -820,233.302104953099,232.862344837073,232.436900281626,232.025015947765,231.626076214753,231.239520945041,230.864785676158,230.501337556626,230.148564805438,229.806107068519,229.473520838326,314.340995797781,311.673828924064,309.131502495596,306.710574689748,304.405269135661,302.199428518757,300.098779544923,298.084911497118,296.16010067804,294.313907580426,292.544789253529 -830,232.626488903427,232.190260503508,231.768202659159,231.359571960933,230.963818837428,230.580347692241,230.208598831738,229.847968873975,229.497996818284,229.158255020612,228.828303697062,312.485037258932,309.857135495725,307.363529035413,304.983053636351,302.714812303555,300.550477391973,298.478838568458,296.502414718806,294.604327239048,292.79192451218,291.047726001189 -840,231.950552057568,231.517839641722,231.099110741477,230.693759751987,230.301179254839,229.920778708088,229.551969161493,229.194177421473,228.846993953582,228.509956362364,228.18262857257,310.643669642517,308.064066030863,305.606959413987,303.271857057787,301.039406049715,298.911836393817,296.876714968718,294.929731666778,293.066599257015,291.279211112881,289.56666614606 -850,231.27428472898,230.845028829771,230.429655561642,230.027569828495,229.638147983837,229.260804520456,228.894881214304,228.539953885752,228.195546906468,227.861201798511,227.536486180063,308.814618092557,306.284539554635,303.871701722093,301.571704447702,299.381497666728,297.284574117147,295.286666804206,293.370144516399,291.538235823968,289.779369058567,288.094419904456 -860,230.59767713789,230.171838516277,229.759827525551,229.360992605301,228.974715450135,228.60035489405,228.237364262057,227.885288862419,227.5436462822,227.211981944914,226.889814714236,307.011480098548,304.516791924138,302.150224053263,299.889671613806,297.734218677911,295.676632849624,293.706717232138,291.825651623645,290.019393480618,288.29257341369,286.631104562626 -870,229.920662894035,229.498280594209,229.089616944711,228.694018404548,228.31086061353,227.939468715111,227.579408799436,227.230172855821,226.891282595829,226.562277230991,226.242632833837,305.22009947073,302.77308958535,300.440135953729,298.22260146551,296.101273260092,294.078871997834,292.142847662332,290.290780844084,288.516364053429,286.814817898427,285.182022013628 -880,229.243279050152,228.82434527043,228.41901403629,228.026637455572,227.646526146388,227.278147302052,226.921005228432,226.57459627872,226.238446271774,225.912023585483,225.594954776929,303.442574801696,301.041069681886,298.750840702749,296.56647651914,294.485151343556,292.491490777567,290.591449388125,288.767025316407,287.023721353192,285.347498265033,283.742792111478 -890,228.56552335899,228.150022655732,227.748008923017,227.358811906924,226.981760038053,226.616380953042,226.26214385801,225.918549451853,225.585089711594,225.261275427317,224.946771016199,301.687972363661,299.320961387081,297.074381863531,294.927273035815,292.879496625373,290.922849353979,289.04992664987,287.259037116926,285.540340813771,283.894428015938,282.312215715301 -900,227.887385823587,227.475302764759,227.076591632958,226.690518924727,226.316552481401,225.95415987173,225.602814903674,225.262022603419,224.931205899643,224.610023126492,224.298071931713,299.945123671914,297.623552897059,295.409180485279,293.302772602113,291.286504749967,289.364387036111,287.522051393918,285.7604198938,284.069908665593,282.450123681913,280.892802042273 -910,227.208856349039,226.800175515805,226.404713404051,226.021788315863,225.650893573226,225.291474166809,224.943008486942,224.604946297829,224.276819746957,223.95825695901,223.648847810288,298.216107290872,295.937455285295,293.763114436141,291.689022356376,289.710573919854,287.816049632873,286.007720963691,284.27128252523,282.611451653885,281.014661946434,279.485119750349 -920,226.529924742311,226.124630730469,225.732374268841,225.352610068726,224.984773313815,224.628313851488,224.282708959521,223.947358357744,223.621921423909,223.305967106243,222.999088844786,296.508474167135,294.262923776859,292.130016519138,290.090078825341,288.144870215238,286.283585570947,284.502985181242,282.797329290043,281.16195524948,279.592570966023,278.08578227164 -930,225.850580711919,225.448614841702,225.05959156115,224.682974073583,224.318181606413,223.96466884287,223.621848518595,223.289260197046,222.966501004813,222.653143654218,222.34878513335,294.812463838072,292.609358722186,290.507948010974,288.506458826398,286.589536888053,284.762756042222,283.008945392226,281.333357139905,279.722180824479,278.180185198284,276.694833342917 -940,225.170813867491,224.772138711865,224.3863550596,224.012870122042,223.651108256603,223.300512774743,222.960480075444,222.630641781347,222.3105484672,221.999776592829,221.697926678569,293.129014681211,290.96742266158,288.90247775248,286.933317230134,285.051994742895,283.251740732,281.530044500463,279.878535987796,278.296344484753,276.77630868744,275.316673821949 -950,224.490572133536,224.095213114661,223.712654442474,223.342287906437,222.983542971604,222.635800676845,222.298593485308,221.971492977994,221.654053691022,221.345855815003,221.046471447522,291.466589464169,289.336791500796,287.310956276075,285.372172517591,283.52449177466,281.753256141675,280.060413325909,278.435302802444,276.879135615405,275.382139461737,273.947072029071 -960,223.809864785023,223.417827613343,223.038479287099,222.671217019114,222.315455414979,221.970572823107,221.636178503633,221.311803555266,220.997006457802,220.69137111579,220.394405204064,289.815552331119,287.724190394623,285.730160645885,283.827656488087,282.00701867269,280.268344612131,278.600119448381,277.004344303395,275.470596198992,274.000134193348,272.585507816498 -970,223.1287021374,222.739971668465,222.363819069138,221.999646951646,221.646810120815,221.30481885532,220.973224785254,220.651563181505,220.339396449714,220.036270066065,219.741753966712,288.176091900361,286.124534912441,284.162770097825,282.293287883491,280.503621083547,278.792894732949,277.153020017868,275.582178656642,274.073390585108,272.626284585881,271.232818827659 -980,222.44707353266,222.06163463717,221.688663161801,221.327550375288,220.977641288678,220.63852831308,220.309721883523,219.990761424193,219.681213248615,219.380561053202,219.088507448347,286.555724327643,284.535848996876,282.610960478297,280.769161062975,279.012526993309,277.326964584631,275.716795384121,274.168838647106,272.686873872351,271.260605909145,269.89146150533 -990,221.764968207574,221.382805772404,221.013000834974,220.654887541235,220.307938341092,219.9716906329,219.645659249372,219.329387748963,219.022401471714,218.724257340296,218.434655260208,284.947681626065,282.96163859996,281.069515802331,279.260362399515,277.531082646623,275.875576301411,274.28952503106,272.768224796296,271.308650807341,269.905212319561,268.557779140647 -1000,221.082375292902,220.703474222046,220.336814966594,219.981693365829,219.63769059585,219.304295147268,218.981026230313,218.667431518566,218.362977410148,218.06734842331,217.780186910873,283.350848596616,281.402309970739,279.538521300158,277.762897231389,276.0597108032,274.433926855317,272.871336904027,271.377061950326,269.938728144236,268.55984939244,267.231767051839 -1010,220.399283812532,220.023629027967,219.660047297371,219.307957046232,218.966887265065,218.636331083637,218.315812069393,218.004842108073,217.702948831894,217.409823694025,217.12509180519,281.769215587879,279.853560167187,278.023812027542,276.275266276236,274.603220837571,273.001389402427,271.466826324594,269.994326920864,268.580288445198,267.22227527042,265.914459666066 -1020,219.715682682527,219.343259125018,218.982740470161,218.633667672209,218.295517454149,217.967787563365,217.650005904093,217.341628456569,217.042305010044,216.751672438951,216.469359243168,280.202123375025,278.315465602951,276.51977036214,274.798645774044,273.155972969667,271.578983631843,270.070869394321,268.620018138198,267.23079263819,265.892477516959,264.607185690952 -1030,219.03156071012,218.662307775088,218.304883450385,217.958814225113,217.623570160744,217.298653600602,216.983569844499,216.67780036372,216.381035110843,216.092883838206,215.812978418822,278.645820383202,276.794312953986,275.025743975339,273.33620917865,271.717991336366,270.169382226073,268.683470879038,267.258180457146,265.88919583134,264.572409654491,263.307201575873 -1040,218.346906592633,217.98079788655,217.626465093276,217.283385576804,216.9510342736,216.628918101133,216.316489692801,216.013346873538,215.719128192555,215.433446964345,215.155938418986,277.100432184906,275.283472157955,273.543388481526,271.883174108983,270.290947145531,268.768469829859,267.305346297014,265.904412521186,264.555478022212,263.261425225117,262.014480956791 -1050,217.66169178051,217.298729745956,216.947474142798,216.60737048851,216.277898571402,215.958564148914,215.648785069977,215.34825692042,215.056573204272,214.773350781155,214.49822822208,275.572220558321,273.78282452051,272.074804303768,270.439556292338,268.876083211434,267.376243129497,265.939022424158,264.558650373666,263.232325564332,261.957819992102,260.72942275116 -1060,216.975885151132,216.616091967219,216.267899230496,215.930757609649,215.604151721547,215.287538103556,214.9804447845,214.682519327946,214.393358984697,214.112584142411,213.83983669685,274.054340469554,272.29422633133,270.61577783291,269.007436717799,267.470040356634,265.993968713652,264.58083101649,263.220866640775,261.917498522517,260.661560787358,259.454031181135 -1070,216.289512208513,215.932873049997,215.58772887431,215.253535476597,214.929782278888,214.61587745551,214.311457532342,214.016122807646,213.72947426088,213.451135790595,213.18075260107,272.546828444034,270.819277718343,269.166316658219,267.587124505956,266.072807415837,264.622949902146,263.230749027219,261.894296160806,260.610136781987,259.373666328154,258.185515416761 -1080,215.602561318168,215.249061378488,214.906951477329,214.575692511412,214.254752340205,213.943570770993,213.641811895722,213.349055957722,213.064907646927,212.78899435558,212.52092373465,271.051456649012,269.354039967788,267.72866722998,266.175762394879,264.685987445794,263.260171453018,261.889034646031,260.575483435648,259.310200555088,258.094783493565,256.923833098952 -1090,214.915020728247,214.564645220181,214.225555326505,213.897217020519,213.579053570448,213.270606500724,212.971496341813,212.681307261736,212.399647642662,212.126148353287,211.860372884871,269.569910587973,267.89851282455,266.302706738189,264.773331607801,263.310100626224,261.905603143337,260.558409967074,259.264219122763,258.019161822738,256.822844732539,255.668934597836 -1100,214.226878568275,213.879612724557,213.543528591327,213.218097193352,212.902698285505,212.596972978619,212.30049922142,212.012865087263,211.733682632271,211.462580616348,211.199096573363,268.098225730654,266.454860096388,264.885822559683,263.381555897884,261.942559190602,260.559769566235,259.235457478923,257.960457000607,256.736651507254,255.557801781652,254.422468197062 -1110,213.538122847845,213.193951921753,212.860859322447,212.538291202596,212.225674683752,211.922658420452,211.628808767612,211.343717684515,211.067000882901,210.798247086465,210.537083196583,266.636394294307,265.023036853127,263.477988558502,262.000615221182,260.583325955134,259.224755815626,257.920133757336,256.665957541712,255.461150705869,254.299599341662,253.183219975501 -1120,212.848741455267,212.507650721176,212.177535450277,211.857802389126,211.547970843602,211.247650922473,210.956413094329,210.67385318492,210.399590543237,210.133175477409,209.874321032926,265.186244206568,263.600413559639,262.080831265685,260.628122314482,259.233000195062,257.897498364715,256.612386333232,255.379673588057,254.192605423192,253.05017434304,251.950364266441 -1130,212.158722156178,211.820696910084,211.493544783544,211.176634419713,210.869574722118,210.571938459997,210.28330019495,210.003259599689,209.731439642046,209.467353932873,209.210798241312,263.748329044255,262.186956985672,260.694637927139,259.264033254174,257.893423409435,256.577947513718,255.314100605621,254.100461983454,252.930954857128,251.807640109172,250.723841530365 -1140,211.468052592105,211.13307815213,210.808859954708,210.494775109801,210.190474153579,209.895508885964,209.609457940838,209.331924818336,209.062498640471,208.800770475334,208.546502859745,262.319735115013,260.783975287075,259.316992344421,257.90882929402,256.56168454816,255.266044732721,254.023886833399,252.828263171441,251.678282779495,250.571543599074,249.503587039996 -1150,210.776720279002,210.444781985869,210.123459721308,209.812212150161,209.510656848026,209.218349929454,208.934874079845,208.659836607177,208.392794528109,208.133413004593,207.881422803848,260.900422372822,259.392317336184,257.947844081136,256.564503890196,255.237727832209,253.96363738541,252.740805859295,251.563011011192,250.432320574232,249.341820404058,248.291207523485 -1160,210.084712605736,209.755795823232,209.437356934048,209.128933105419,208.830110389767,208.540449194187,208.259536234794,207.986982607806,207.72231516824,207.465269296287,207.215545865363,259.491154997511,258.009304954792,256.587361791826,255.228095778323,253.921488857797,252.669327492869,251.464792734953,250.306795881871,249.192839003712,248.118401140529,247.085031739108 -1170,209.392016832555,209.066106947969,208.750539009554,208.444925412545,208.148822235848,207.86179415698,207.583431901934,207.313345717658,207.051048194148,206.79632700038,206.548859710629,258.093807134563,256.634881427268,255.238090410312,253.899543298219,252.614613939436,251.382208678369,250.195776142359,249.057254882605,247.959768940125,246.902925055539,245.884739669399 -1180,208.69862008951,208.375689215967,208.062993234834,207.760176379313,207.466779714508,207.18237216619,206.906548449358,206.63889360044,206.378981111612,206.126573639613,205.88135187903,256.705200700795,255.268979470645,253.896813652762,252.578776359538,251.316031388448,250.10221076903,248.935713902724,247.814235328301,246.733036486949,245.69357963412,244.690261086617 -1190,208.004509374851,207.684525202507,207.374706765716,207.074673182733,206.783970023588,206.502170440108,206.228873115408,205.963640050894,205.706101297335,205.455996607939,205.21300978142,255.325272942356,253.91427870439,252.563464178041,251.267076448028,250.024696239216,248.82925742856,247.68243434533,246.577663518536,245.514192833372,244.490144448812,243.501522141584 -1200,207.309671553395,206.99262145105,206.685666625262,206.388402867448,206.100380228924,205.821176065347,205.550393007034,205.287572297185,205.032395997364,204.784583168924,204.543820698516,253.953950682178,252.567922171643,251.237966397217,249.964034331773,248.740533259943,247.565035283693,246.435715138669,245.347461183263,244.301531558119,243.292545295649,242.319241809179 -1210,206.61409335486,206.299964827921,205.995859702155,205.701352344103,205.415997262704,205.139375995189,204.87109509815,204.610677434911,204.357852325466,204.112320454125,203.873771779274,252.593167654768,251.229562954084,249.921071642059,248.668294193,247.463461252427,246.307848367868,245.195478152655,244.124972214394,243.09480518603,242.10070453285,241.143121608549 -1220,205.917761372171,205.606542063003,205.305272749046,205.013508387691,204.730807921799,204.456757047909,204.190966227939,203.932942425465,203.682457261488,203.439195461435,203.202850039224,251.241508286415,249.899120153408,248.61337253518,247.379775905067,246.194756959353,245.057258996716,243.961640879122,242.908840941452,241.893935663365,240.915180684418,239.972369882881 -1230,205.220662059737,204.912339748071,204.613892380882,204.324857635859,204.044798866071,203.773305905071,203.509986510041,203.254354094373,203.006197649685,202.765195053413,202.531042358795,249.89791485503,248.576647221135,247.313028436067,246.098393561896,244.933484736747,243.813184749941,242.735221559517,241.69866755864,240.698841675725,239.735936226668,238.806910379561 -1240,204.522764978707,204.217344335097,203.921705073198,203.635386587204,203.357956616649,203.089009109802,202.828141667742,202.574899129602,202.329060197023,202.090305955575,201.858335481604,248.562301344165,247.264083012452,246.019954486125,244.8248746501,243.678845729367,242.57553901276,241.515458138942,240.494370284592,239.509818916269,238.562071717789,237.646664380206 -1250,203.824072472411,203.521542134528,203.228697160386,202.94508159952,202.670267554175,202.403853065029,202.145428303318,201.89456407984,201.651031471455,201.414514754665,201.18471601272,247.234574666351,245.958925492148,244.734060223468,243.559329894821,242.430753362834,241.344896427528,240.301674086087,239.295864247782,238.327300930144,237.393507674892,236.491550988859 -1260,203.124573647296,202.824919313536,202.534854833931,202.253928888034,201.981717917036,201.717824031705,201.461832804426,201.213335352754,200.972097900166,200.737807896902,200.510170416905,245.916203964002,244.66108523195,243.455383140494,242.3004526857,241.189117043532,240.121330607885,239.093784009896,238.103081030774,237.150172877328,236.23016230316,235.34197235125 -1270,202.424254500205,202.127461894233,201.840164140623,201.561914523609,201.29229379955,201.030908126991,200.777341415651,200.531199213213,200.292245767799,200.06017168619,199.834685016822,244.606012879332,243.370467364781,242.185369201774,241.048152427351,239.953949754243,238.903764291078,237.891699592807,236.917133118328,235.978352149003,235.071951778008,234.197855126474 -1280,201.723100880725,201.429155751863,201.14461098074,200.869024430914,200.601981150141,200.343091322424,200.091940236712,199.848141781487,199.611461214642,199.38159228231,199.158245991226,243.303185166177,242.086972216287,240.922055979041,239.802334671638,238.726403070386,237.692108590232,236.695329949524,235.736583783619,234.811753972425,233.918939995597,233.05851844295 -1290,201.021098489357,200.729986612967,200.448181106197,200.175244386577,199.910765769479,199.654359442052,199.405615220639,199.164149031419,198.929730234799,198.702055699081,198.480839373113,242.007621702116,240.811587175682,239.665348986292,238.562901586729,237.504874844861,236.4862718486,235.505346277573,234.561347391869,233.650291687234,232.771686846654,231.923881662989 -1300,200.318232875659,200.02994005351,199.750860118676,199.480560017299,199.218633308589,198.964698160541,198.718352171923,198.479206788568,198.247038674327,198.021547802495,197.802451047855,240.719218710263,239.543630710003,238.415150042084,237.330617657084,236.289272804991,235.286159993214,234.321210859832,233.391336286479,232.493877000263,231.629211016304,230.793862738984 -1310,199.614489436354,199.329001496991,199.052633467723,198.784956797946,198.525569266944,198.274093001256,198.030136744627,197.793300728319,197.56337222934,197.340054308816,197.123066751302,239.43796771035,238.282308893216,237.171357735525,236.104939693502,235.079502057666,234.091850050736,233.142392905178,232.226461059726,231.343066855979,230.491429373571,229.668378412469 -1320,198.909853413421,198.627156212513,198.353486448812,198.088420049613,197.831558990513,197.582529334315,197.340954440487,197.106416373973,196.878716444096,196.657560782662,196.442672067846,238.16515116545,237.027519929139,235.93391402862,234.885202570626,233.875465438204,232.903956583992,231.968801962947,231.066630801958,230.197298177767,229.358257498475,228.547344397478 -1330,198.204309892139,197.924389312831,197.653404201385,197.390934937654,197.136587669795,196.889992374606,196.650790606962,196.418539094795,196.193056709042,195.974052635048,195.761252428474,236.898996992354,235.779158937328,234.703890161636,233.671308258043,232.677063830951,231.721384140402,230.800345962153,229.911873608819,229.056216937834,228.229609875649,227.430774830804 -1340,197.497843799114,197.220685752367,196.952371706865,196.692486469685,196.440640337812,196.196467179787,195.959622687212,195.729654104046,195.506378258836,195.289515121403,195.078793108772,235.639399896646,234.537118378466,233.479821026418,232.463156591411,231.484719520663,230.544039560923,229.636931455325,228.762652180962,227.91973641869,227.105400072352,226.319019112692 -1350,196.790439900273,196.516030325191,196.250373786626,195.993059493557,195.74370186808,195.501938648244,195.267429158855,195.039746456972,194.818666170337,194.603933339554,194.395279226912,234.386251635353,233.30165502938,232.261605550886,231.260645588464,230.298212514322,229.371828191278,228.478463842255,227.618110527052,226.787768918254,225.985540901924,225.211386927997 -1360,196.082082798819,195.810407662981,195.547395099948,195.292638695297,195.045756972542,194.806391517025,194.574205265921,194.348801048769,194.129905360564,193.917292227683,193.7106957416,233.139441439905,232.073048593179,231.049140659507,230.063671738485,229.116933480316,228.204654120708,227.325140371945,226.478159702896,225.660225922727,224.870184017795,224.107796129888 -1370,195.372756933164,195.103802232939,194.843420141927,194.591208597023,194.346790199476,194.109810359741,193.879935606548,193.656802612513,193.440080584618,193.229576562248,193.025027449995,231.898856403032,230.850306140701,229.842321585122,228.872765398821,227.940785257126,227.042420400679,226.176971309068,225.342709885877,224.537018265046,223.759307120855,223.008163991862 -1380,194.662436862875,194.396198335684,194.138433241362,193.888753554811,193.646785931367,193.412179584432,193.184604613508,192.963735717057,192.749176433582,192.54077095587,192.338258985594,230.664802999702,229.633321770485,228.641042154083,227.687363935046,226.769669541313,225.885029244913,225.033382452282,224.211670542916,223.418056269889,222.652453404877,221.912407332036 -1390,193.951097946537,193.687580103106,193.432418558604,193.185257756551,192.945728382747,192.713483431403,192.488196552042,192.269560540631,192.057177332376,191.850859855193,191.650374816085,229.437319343151,228.421988008843,227.4451950466,226.507090339576,225.603487101461,224.73265537422,223.894281920766,223.084950584119,222.303465017895,221.549538397932,220.820442626925 -1400,193.238738430699,192.977931496193,192.725360083372,192.480705219752,192.243601597998,192.013705971028,191.790695517654,191.574266350812,191.364067537583,191.159827538701,190.961359241163,228.215600962544,227.216196091104,226.255206896296,225.331843983198,224.442137973499,223.585254577388,222.759577220134,221.962458503113,221.193191366162,220.450477256679,219.732186115414 -1410,192.525341950419,192.267236302813,192.017241632537,191.775079789319,191.540389449126,191.312831101509,191.092085433877,190.877851856711,190.669831135242,190.467658114506,190.271196390314,226.999537753089,226.015836217932,225.070612214591,224.161523413367,223.28552163874,222.442328858828,221.629175391501,220.844102505013,220.086835801667,219.355184875848,218.647553893619 -1420,191.810891964149,191.555478135473,191.308046847865,191.068365135293,190.836075633494,190.610842546612,190.39235004999,190.180300832272,189.974414762897,189.7743355181,189.579870220557,225.789018427924,224.820797788565,223.891039144475,222.996026545102,222.133620680847,221.303783817185,220.502983147355,219.729837139474,218.984311867905,218.26357598808,217.566462001258 -1430,191.095371751415,190.842597996963,190.597759193727,190.360544750555,190.130643671522,189.907723853358,189.691472938716,189.481596875051,189.277818597432,189.079843510062,188.887364514157,224.583930770847,223.631215145587,222.71638407057,221.83525083466,220.98668909752,220.169524674843,219.380906995193,218.619878030901,217.885532922686,217.175565254796,216.488842491274 -1440,190.378764410458,190.128613213786,189.886361954776,189.651601948493,189.424076904346,189.203458389681,188.989437493868,188.781723403857,188.580042102219,188.384135175589,188.193662876293,223.38416186587,222.447112029224,221.546542840428,220.679093437242,219.84412262559,219.039456409548,218.262853349798,217.513727780652,216.790412234003,216.091067348737,215.414859748856 -1450,189.661052855843,189.413510401685,189.173837400667,188.941519860631,188.716358491441,188.49802934204,188.286226927959,188.080663656368,187.881068539236,187.687186015607,187.498748732691,222.189598305321,221.267918929099,220.381410934113,219.527451349953,218.705824715553,217.913483873915,217.14872863499,216.411298251187,215.698863067072,215.009997028761,214.344127228835 -1460,188.942219816018,188.697272321636,188.460108742092,188.230281434212,188.007471408205,187.791419712999,187.581824269779,187.378400686691,187.18088098704,186.989012445311,186.802556520511,221.000126378159,220.093529675542,219.220883617899,218.380420185585,217.571698653457,216.791511903704,216.03853538558,215.312501284232,214.610798763176,213.932269207455,213.276564349626 -1470,188.222247830844,187.979881546248,187.745214131043,187.51786942975,187.297398443494,187.083612318765,186.876212361923,186.674917362889,186.479462338286,186.289597381102,186.105086606535,219.815972782179,218.923837818112,218.064856083251,217.237895893664,216.441647676478,215.67344541569,214.932286011134,214.217248784141,213.526132810926,212.857799012081,212.212090638549 -1480,187.501119249076,187.261320457239,187.029135980982,186.804209834754,186.586122197131,186.374589786677,186.169373858278,185.97019636447,185.776795297205,185.588923551084,185.40634788161,218.63682459929,217.758736775551,216.913223572246,216.09952418951,215.31557507739,214.559189495929,213.829643124374,213.125452793212,212.44477891046,211.786664265104,211.150625787827 -1490,186.778816225806,186.541571242869,186.311856512101,186.089320102944,185.873625077354,185.664334552661,185.461291221473,185.264220179822,185.072862377044,184.886973492497,184.706322906143,217.462361893879,216.598119971079,215.765881490461,214.965206731171,214.193384298755,213.448649479113,212.730517301122,212.037025559528,211.366651031129,210.718625865992,210.092089704992 -1500,186.055320719853,185.820615895332,185.593357748712,185.373198379399,185.159811162585,184.952828858632,184.751946720274,184.556971103608,184.367645897453,184.183729549103,184.004994047173,216.292476275631,215.441880954192,214.622741026298,213.834845301404,213.074979017604,212.341731019704,211.6348193142,210.951879597897,210.291663463123,209.653563054501,209.036402558107 -1510,185.330614491124,185.098436208098,184.873621516579,184.655826520966,184.444728349874,184.240023578666,184.041322426945,183.848431234122,183.661127981831,183.479173868528,183.302343475705,215.127059433994,214.289913509992,213.483962895338,212.708341898361,211.960263221349,211.238456701279,210.542460198019,209.869927744388,209.219730863496,208.591394704491,207.983484816179 -1520,184.604679097906,184.375013773209,184.152629440212,183.937186183393,183.728364861502,183.525865549272,183.329400214551,183.138582470586,182.953290554625,182.773288399549,182.598353163999,213.966003256605,213.14211175705,212.349118364777,211.585598816878,210.849141275585,210.138681262444,209.45335130637,208.791083204939,208.150768297012,207.532039994596,206.933257285106 -1530,183.877495894135,183.650329978531,183.430362940107,183.217258818564,183.010702179555,182.81039657545,182.616063142102,182.427406510407,182.244115338577,182.066054889346,181.89300488281,212.809199935319,211.998370234703,211.218108015299,210.466518721103,209.74151798442,209.042214582274,208.36740436394,207.715259598492,207.084691272186,206.47541844594,205.885641139491 -1540,183.149046026592,182.924366004951,182.70680322994,182.496025671687,182.291721579578,182.093597961938,181.901379200021,181.714805782712,181.533583851926,181.357454880693,181.18628019858,211.656542060817,210.858583980624,210.090832783561,209.351004709125,208.637298643901,207.948966875152,207.284531512029,206.642370995059,206.021484170945,205.421449955513,204.840557950607 -1550,182.419258766231,182.197102823528,181.981931313705,181.773467778427,181.571404127697,181.375450804172,181.185335414259,181.000801478405,180.821607288696,180.647469709102,180.478160470573,210.507922706733,209.722648599457,208.967194031702,208.238960370229,207.53638908908,206.858848773653,206.204645348891,205.572331949098,204.960997383973,204.370054825511,203.797929710812 -1560,181.688108944063,181.468509159756,181.255727982809,181.049565961991,180.849730677698,180.655935985356,180.467912696331,180.285407343708,180.108181054013,179.936008514459,179.768626847967,209.363235504122,208.590460323228,207.847093608949,207.130289835371,206.43869573522,205.771771371472,205.127658965129,204.505057528572,203.903126200866,203.321153788939,202.757678854669 -1570,180.955628169077,180.738472544755,180.528173813103,180.324300830152,180.126681868049,179.935034173478,179.74909174263,179.568604102356,179.393335195917,179.223062363061,179.057575405229,208.222374707075,207.462059675268,206.730433905959,206.024897821388,205.344125613597,204.687646261092,204.05348597451,203.440463339993,202.847790065188,202.274668031764,201.719728277004 -1580,180.22179658515,180.007071706166,179.799140366333,179.597652772228,179.402238118863,179.21272581827,179.028853031382,178.850372259995,178.677050246459,178.508666966479,178.345014705981,207.085235250191,206.337172542058,205.617117902461,204.922689669457,204.252586402338,203.606385566605,202.982040540554,202.37846554979,201.794908883643,201.230519211861,200.684001348145 -1590,179.486594112504,179.274286599917,179.068693403688,178.869501718437,178.676379628813,178.488991148111,178.307176819539,178.130692101078,177.95930651656,177.792802661128,177.630975289664,205.951712798588,205.215697271953,204.507049208749,203.823571378254,203.164012523375,202.527901972056,201.913237399226,201.318980902259,200.744403046024,200.188629474996,199.650421926541 -1600,178.750000444539,178.540096955223,178.336829037335,178.139887670599,177.948982682127,177.763810166872,177.584043139625,177.409543685691,177.240084092842,177.075449559179,176.915437293062,204.821703791054,204.097535704836,203.400132101502,202.727449632235,202.078296054798,201.452108745659,200.846991878031,200.261926734371,199.696193442076,199.148921468077,198.618914368952 -1610,178.011995044604,177.804482271345,177.603526800991,177.40882337388,177.22008534197,177.037043275399,176.859431796507,176.686906846332,176.51936283439,176.35658754532,176.198380625524,203.695105476932,202.982590353678,202.296271554408,201.634231825444,200.995320314657,200.378919760209,199.783219911794,199.207220987676,198.650201475457,198.111318349857,197.589403538405 -1620,177.272557142707,177.067421814298,176.868765995202,176.676288161971,176.489705168601,176.308750871062,176.133174873194,175.962741381712,175.797122369465,175.636196273458,175.479784965657,202.571815947232,201.870764437848,201.195373263997,200.543826081198,199.914997682722,199.308249509991,198.721838055379,198.154782217537,197.606349075064,197.075743799305,196.561814810072 -1630,176.531665732158,176.328894613479,176.132525683979,175.942261132088,175.757821291114,175.578943281603,175.405379773462,175.236897855742,175.073278003344,174.914255163354,174.759629757961,201.45173416049,200.761961911305,200.097343671093,199.456141267988,198.837241173777,198.240013124452,197.662763493599,197.104529599897,196.56455870389,196.042122021805,195.536074075229 -1640,175.789184655799,175.588879458248,175.394784691356,175.206721141532,175.02441259874,174.847599426916,174.676037342204,174.509496297416,174.347759462132,174.190622289027,174.037891658054,200.33475996379,199.656087486079,199.002089978219,198.371087011912,197.761964452406,197.174126378905,196.605914048522,196.056382935768,195.524753365616,195.010377753348,194.512107743443 -1650,175.045155674047,174.847218090924,174.655521597892,174.46964680418,174.289457737329,174.114697983551,173.945126285461,173.780515441118,173.620651297417,173.46533182857,173.31436629141,199.22079410938,198.553046651459,197.909520163317,197.288573705913,196.68908184464,196.110505702498,195.551208184394,195.010262653633,194.486856609104,193.980436262884,193.489842743122 -1660,174.299600802513,174.10398614131,173.914542240169,173.73098225703,173.552935105764,173.380217381123,173.212625062368,173.04993377435,172.891932023971,172.738420290742,172.58921019311,198.109738267242,197.452745689208,196.819542990063,196.208512516105,195.618537478763,195.049068183654,194.498565010362,193.966089809923,193.450792530965,192.952223352957,192.46920652054 -1670,173.552497889242,173.359193030786,173.171983519477,172.99058612929,172.814734875246,172.644135798651,172.478511881485,172.317729534053,172.161579906026,172.009865966016,171.862401678882,197.001495033987,196.355091685169,195.732068015081,195.130815385403,194.550238660703,193.989731573206,193.447904281172,192.923786087712,192.416539256805,191.925665358762,191.450127037476 -1680,172.803824525527,172.612816387718,172.4278286517,172.248581683423,172.074812865057,171.906275323024,171.742736768178,171.583880702866,171.429572953512,171.279646890574,171.133918810165,195.895967938368,195.259992537541,194.647005592302,194.055395034706,193.484087048331,192.932414285391,192.399146396008,191.883273793789,191.383974787027,190.900689145748,190.43253276755 -1690,172.053558042083,171.864833579912,171.682055040167,171.504946356801,171.333248256744,171.16671700504,171.005123260592,170.848251031313,170.695888918235,170.547740842473,170.403739390268,194.793061443726,194.167356962129,193.564266874714,192.98216496183,192.419998390356,191.877035396897,191.352212395618,190.84447585422,190.353019865336,189.877222105878,189.416352691366 -1700,171.301660067193,171.115221710695,170.934639823738,170.75965732233,170.590018255852,170.425482007116,170.265822163558,170.11082548647,169.960290968505,169.814028970793,169.67184096046,193.692680947634,193.077094494796,192.483763813722,191.911039438376,191.357889182595,190.823514644104,190.307023957869,189.80731580854,189.323599814611,188.855192152639,188.401516290556 -1710,170.547927494606,170.363873794916,170.185559872796,170.012691484436,169.845099799441,169.682547297612,169.524810475472,169.371678829476,169.222953926266,169.078448551441,168.937985929196,192.594732778974,191.989115491386,191.40540915633,190.841933504718,190.297676661203,189.771772418676,189.263503391859,188.771717802666,188.295640538866,187.83454286189,187.387953540804 -1720,169.792523190845,169.610712203035,169.434623997549,169.263993074117,169.098469551984,168.937889572282,168.782064922106,168.630787814923,168.483862374349,168.341103794479,168.202337570109,191.4991241927,190.903401079827,190.329116440317,189.774762963262,189.239278794427,188.721734580409,188.221573630699,187.737606580656,187.269068514186,186.815244781261,186.375594903925 -1730,169.035423225373,168.855842028822,168.681911025317,168.513368187247,168.349967410423,168.191477325114,168.037561952417,167.888128920562,167.74299281816,167.601971231891,167.464891912206,190.405763362472,189.819812640339,189.254799987593,188.709444370141,188.182614272984,187.673398726556,187.181158223081,186.704907475387,186.243810778726,185.797167332851,185.364371319085 -1740,168.276603384031,168.099239095778,167.927452870702,167.760986130211,167.599596003625,167.443054155705,167.291145717438,167.143668309632,167.000321481945,166.861027114467,166.725625231797,189.314559371367,188.738244773919,188.182374895886,187.645895025456,187.127602499198,186.626604415775,186.142181323724,185.673546398254,185.219794921826,184.780239708235,184.354234153708 -1750,167.516039164638,167.340878939347,167.17122510514,167.006822508905,166.847431491481,166.69282673157,166.542796191425,166.397140154019,166.2556703426,166.118209114548,165.984513519575,188.225422200839,187.658609957303,187.111757028912,186.584032962221,186.074163574996,185.581273721842,185.104567682803,184.643449827976,184.196949072343,183.764391611203,183.345143395082 -1760,166.753561522889,166.580732838205,166.413203007471,166.250852636579,166.093449220201,165.940770430509,165.792607041862,165.648761981457,165.50904946118,165.373294182693,165.24133060865,187.138262718093,186.580821512747,186.042888627319,185.523776934101,185.02221828887,184.537329371373,184.068305893972,183.614544798559,183.175201886246,182.749553245083,182.33697716394 -1770,165.989171615585,165.818519170324,165.653228525461,165.493051332129,165.337624238691,165.186860332958,165.040553379423,164.898508931631,164.760543673348,164.626484634792,164.496168474061,186.052992662014,185.504793592924,184.975739546657,184.465046402058,183.971688101888,183.494694729382,183.033278028552,182.586758886513,182.154482533539,181.735655299483,181.329667599066 -1780,165.222951850475,165.05446289164,164.891265476823,164.733114611473,164.579780168031,164.431045777198,164.286610012653,164.146355842035,164.010127844385,163.877755362817,163.749077236152,184.969524627793,184.430441164713,183.910145485673,183.407761520012,182.922495132845,182.453293784095,181.999384966419,181.56004365238,181.134720684568,180.722628936472,180.323147284686 -1790,164.454876330139,164.288538142626,164.127421695112,163.971285324099,163.819902025263,163.673058360609,163.530553461777,163.392198119769,163.257776532502,163.1270809516,163.000031505339,183.887772050372,183.357679991978,182.846024418679,182.351875839773,181.874562142629,181.413051131073,180.966553047703,180.5343573352,180.115846495764,179.710405776261,179.31734923615 -1800,163.684918842591,163.520718749109,163.361671042301,163.207537366562,163.058093819173,162.91312987323,162.7724473953,162.635859748235,162.503190970662,162.374275025647,162.248955111817,182.807649186817,182.286426617439,181.783295056574,181.297344032644,180.827812517874,180.373891956716,179.934709169566,179.50956781235,179.097813745121,178.698917882424,178.312206885201 -1810,162.912814180597,162.75087626453,162.593987060559,162.441844315523,162.294329159438,162.151233956358,162.012363288941,161.877533074239,161.746569755039,161.619309559344,161.495597821398,181.729071097739,181.216598343724,180.721876827706,180.244014751,179.782177472862,179.335742021198,178.90378076916,178.485604114758,178.080570982627,177.688097746685,177.307654064856 -1820,162.13870245523,161.978874977012,161.824059854198,161.674025314923,161.528553636197,161.387343926032,161.250274488954,161.117191473011,160.987923708672,160.862309673415,160.740196822575,180.652028965533,180.148113213672,179.661689858104,179.191810095042,178.737656378309,178.298527640887,177.873695806126,177.462395763438,177.063999270436,176.677915609247,176.303624993937 -1830,161.362616879248,161.204887257531,161.052102040976,160.904032694973,160.760464532075,160.621195680687,160.486036144407,160.354806942872,160.227225903754,160.103248466653,159.982725239691,179.576401113278,179.08088998998,178.602654951136,178.140652801376,177.694082776782,177.262194700578,176.844382744687,176.439872751768,176.04803005503,175.668275740882,175.300065005879 -1840,160.584529715318,160.42888540658,160.278117997733,160.132002168574,159.990326245865,159.852891187316,159.719509654843,159.590005168099,159.464211330296,159.341971119237,159.223136237232,178.502058863747,178.014895694945,177.544693566658,177.090466222353,176.651381813363,176.226705534162,175.815770535358,175.417965527438,175.032595206591,174.659092255593,174.296922737886 -1850,159.804224796127,159.650787714881,159.502079716294,159.357905761991,159.218110836782,159.082498707829,158.950884676784,158.823094745915,158.698964855403,158.578340184874,158.461074512916,177.428919622079,176.950055372928,176.487727799693,176.041174305004,175.609479189088,175.191922737804,174.787830021734,174.396604974087,174.017627000933,173.650298752337,173.294096968491 -1860,159.021697468302,158.8703181786,158.723679377056,158.581562152273,158.443760846612,158.309989982087,158.180132980197,158.054047475142,157.931571727827,157.81255310445,157.696847445553,176.356901520238,175.886226308917,175.43173786289,174.992701569631,174.568301139893,174.157774172635,173.760459572397,173.375736805015,173.003058101193,172.641829188771,172.291522886189 -1870,158.237070960883,158.087737017492,157.943077449573,157.802876489964,157.666931429627,157.535051646095,157.407057717256,157.282780611857,157.162003416959,157.044581373808,156.930426556382,175.285923392247,174.823329362917,174.376612585589,173.944980001798,173.527774415273,173.124188177175,172.733566862505,172.35530262996,171.988824403558,171.633617863061,171.289135993047 -1880,157.450315891282,157.303014886623,157.160322583787,157.022026337342,156.887926365825,156.757834795013,156.631574785185,156.508979733922,156.389892546914,156.274164970147,156.161656977496,174.215904749089,173.761286025651,173.322240067812,172.897990464277,172.487826256697,172.091093546202,171.707082158687,171.335196718357,170.974877806833,170.6255993955,170.286872086693 -1890,156.661129989888,156.515980776598,156.375372211579,156.238982047148,156.106716040675,155.978401933257,155.853865449263,155.732942397953,155.615477955427,155.501326006968,155.390348543946,173.146765753313,172.70001839373,172.268544232198,171.851583195533,171.448423831118,171.058419509417,170.680936129014,170.315351101929,169.96111646054,169.617716858081,169.284667233333 -1900,155.869629368989,155.726485726024,155.587818003742,155.453419789141,155.323097150961,155.196667711675,155.073899776854,154.954638699924,154.838787298046,154.726201580776,154.616745542863,172.078503881066,171.639449144604,171.215449539484,170.805684340767,170.409457033325,170.026115004744,169.655059821986,169.295698161525,168.947474009423,168.609882549001,168.282448584646 -1910,155.075896432435,154.934746051999,154.798007299317,154.665476813532,154.536963525905,154.412287746267,154.291280329619,154.173781914819,154.059642228191,153.948719445701,153.8408177628,171.01096011648,170.579536814062,170.162880963906,169.760220518832,169.370838324673,168.99409544106,168.629392606706,168.27617060647,167.933884397489,167.602031547874,167.280146556403 -1920,154.279824592247,154.140730630841,154.005909010235,153.875234826549,153.748519852871,153.625587067041,153.50626983131,153.390411142916,153.277862948559,153.168485516496,153.062146860699,169.944044976808,169.520191539758,169.11077872142,168.715118798148,168.332496290912,167.962270930483,167.603855984116,167.256700615781,166.920281847736,166.594099222492,166.277697603841 -1930,153.48109745198,153.344024034515,153.211232158632,153.082524565669,152.957715914932,152.836534279914,152.718896941565,152.6046680305,152.493701697962,152.385860289639,152.281013778834,168.87768052489,168.461299914891,168.059078068412,167.670312732507,167.294359906771,166.93057184839,166.578368068625,166.237209226181,165.906588487436,165.586021172524,165.275038388731 -1940,152.680029072567,152.544909446541,152.414008441404,152.287131781479,152.164096923938,152.044732187463,151.928875957321,151.816375959143,151.7070885946,151.600812071097,151.497448693321,167.811789356031,167.402786275189,167.007664570977,166.625737026823,166.2563603295,165.898928901763,165.552860860993,165.21762634004,164.892729064725,164.577702229741,164.272105759864 -1950,151.876586795915,151.743408791355,151.61438691548,151.489329853697,151.368057840587,151.25040180256,151.136202575658,151.025310190937,150.917583220734,150.812888179855,150.711098976379,166.746304368376,166.344575417788,165.956464626187,165.581289738549,165.218421186389,164.867269004762,164.527266639263,164.197885431334,163.878643583196,163.569084002079,163.268776337055 -1960,151.070303665218,150.939180467777,150.812148509673,150.689019486236,150.569565715084,150.453607824422,150.341055397476,150.231760754039,150.125584621466,150.022395545467,149.922069349695,165.681162881383,165.286596983443,164.905405025635,164.536899131186,164.180458817639,163.835506701134,163.501501161912,163.177920199876,162.864266849032,162.560110336171,162.265029255242 -1970,150.261523166699,150.132314505385,150.007135525734,149.885800837384,149.7681362362,149.653977874189,149.543171502157,149.435571777781,149.331041632612,149.229367182411,149.130495050019,164.616246884279,164.228778029446,163.854412424128,163.492493799784,163.142403173575,162.803576022637,162.475482258953,162.157624127321,161.849533821383,161.550717239639,161.260802118671 -1980,149.450252744726,149.322946550562,149.199608904327,149.080057308333,148.964120271905,148.851636494929,148.742454122919,148.636430066404,148.533429378256,148.433324683299,148.335995655135,163.551480458529,163.17101968111,162.803401170387,162.447991678695,162.104184476774,161.77140844087,161.449155778101,161.136939317729,160.834301152337,160.540810509237,160.256032015044 -1990,148.636008246324,148.510715402611,148.389327569725,148.271665196428,148.157533990717,148.046714331655,147.939145836766,147.834687652942,147.733206938915,147.634578304223,147.538683294616,162.48678808272,162.113247964005,161.752293170245,161.403304264581,161.065701262214,160.738935643789,160.42245455952,160.11581317431,159.818563309041,159.530283299184,159.250576092328 -2000,147.819118588954,147.695701250472,147.57612871833,147.460224287466,147.347821905123,147.238765381045,147.132907666826,147.030110197467,146.930242288957,146.833177650239,146.738707782465,161.422087060489,161.055389232043,160.701016197511,160.358369624291,160.026882157612,159.706022008587,159.395290259195,159.094179764783,158.802255367714,158.519125704733,158.244402115189 -2010,146.999613700504,146.878063199251,146.76029441929,146.646136780277,146.535426879472,146.428011015125,146.323744477917,146.222490903545,146.124121680367,146.028515406758,145.93555739335,160.357288156355,159.997339916744,159.649496711274,159.313117100193,158.987671620955,158.672641630625,158.367539008407,158.071905335753,157.785309704763,157.507273823868,157.237476853153 -2020,146.176898651661,146.057316495364,145.941457188221,145.829149731976,145.720233431288,145.614552582355,145.511867179481,145.41214778175,145.315267834614,145.221107875349,145.129555043649,159.292317566592,158.939029493021,158.597600855308,158.267449420317,157.948000398147,157.63873134539,157.339191568619,157.048932564142,156.767532698753,156.494595254965,156.229737311796 -2030,145.351481051107,145.233735600367,145.119654137153,145.009068441825,144.901820425857,144.79776138132,144.69675129604,144.598658227807,144.503357731819,144.410732336125,144.320671060461,158.227100741934,157.880391125671,157.545299076156,157.221255270695,156.907726559802,156.604213185199,156.310180983239,156.025234121244,155.74897004895,155.481000587368,155.220960148626 -2040,144.523136292452,144.407335465615,144.295087436073,144.1862124429,144.080622026835,143.978169909592,143.87871836294,143.782137593655,143.688305180766,143.597105559962,143.508429550634,157.161521642719,156.821351881159,156.492519724972,156.174510274722,155.866802193472,155.568906738544,155.28036529107,155.000744081908,154.72955674512,154.466498568699,154.211211836283 -2050,143.69158455073,143.577593668164,143.467147529748,143.360083490107,143.256248693952,143.155499351165,143.057700075296,142.962723279083,142.870389825584,142.780606935242,142.69330742619,156.095501291954,155.761748293544,155.439157086498,155.127144116324,154.825187713048,154.532844178113,154.249664999454,153.975228874425,153.709139703569,153.451024756213,153.20043833857 -2060,142.857196967544,142.745004227248,142.636298701595,142.530920456886,142.428719182065,142.329553476511,142.233290200093,142.139803879241,142.048976163479,141.960695327496,141.87485581437,155.028989033301,154.701568642843,154.385078814589,154.078985391285,153.782788109786,153.495957392904,153.218078229173,152.948764474982,152.687628720814,152.434306375455,152.188454029107 -2070,142.019440527834,141.909150282054,141.802287334614,141.6986945275,141.598224157175,141.500677097818,141.405939909509,141.313934471391,141.224544408717,141.137659858623,141.053177021343,153.961903352497,153.64074656434,153.330285071982,153.030004262053,152.739415113109,152.458059131558,152.185506036375,151.921287646718,151.665048878149,151.416464936415,151.175199918523 -2080,141.178592334578,141.070073609942,140.964925568099,140.862993717045,140.764132854772,140.668206382018,140.575085675083,140.484649512665,140.396783551377,140.311379845196,140.228336404606,152.894050270009,152.579135253332,152.274704338085,151.980167415127,151.69512063744,151.419115817335,151.151732298001,150.892574896608,150.641272026143,150.397435734992,150.160706701103 -2090,140.334539202878,140.227895536465,140.124563526095,140.024282681146,139.927020785647,139.832644530352,139.741027483535,139.652050486624,139.565601139082,139.481573326435,139.399866787253,151.825458402957,151.516640258077,151.218092956287,150.929316086199,150.649835265872,150.379119580798,150.116846180356,149.862628729074,149.616103920542,149.376929804531,149.144784255848 -2100,139.486989688388,139.382091000754,139.28044826391,139.181912340383,139.086343055508,138.993608534722,138.903584598758,138.816154210904,138.73120697119,138.648638652928,138.568278399897,150.756053693392,150.45325955386,150.160518422464,149.877341365267,149.603270361731,149.337875928601,149.080754956128,148.83144631042,148.58964559343,148.355043551061,148.127325216419 -2110,138.636346779234,138.53319374312,138.433229046706,138.336318462548,138.242324255886,138.151116844003,138.06257420245,137.976581322392,137.893029713981,137.811816951314,137.732846254926,149.685595871083,149.388842561068,149.101916733104,148.824273912296,148.55554428107,148.29530816631,148.04317162179,147.798764507065,147.561738733603,147.331749736208,147.108409443612 -2120,137.78184496166,137.680512230854,137.582322523195,137.487131968231,137.394805336616,137.30521540154,137.218242355914,137.133773279707,137.051645340848,136.971779248677,136.894117117994,148.614126685268,148.323244195764,148.041999446239,147.769924350271,147.50658040473,147.251455651677,147.004246690791,146.76460412549,146.532187757618,146.306677341748,146.087771156237 -2130,136.924153067436,136.824527282644,136.727990123223,136.634400273769,136.543624902706,136.45553903562,136.370024983268,136.28697181881,136.206274899366,136.127835427606,136.051560049494,147.541595453479,147.256514290071,146.980862515369,146.714182959269,146.456047294096,146.206053819197,145.963825443832,145.728979914382,145.501121279011,145.280022846052,145.065389720168 -2140,136.062588216503,135.964767279906,135.869978246605,135.77808242538,135.688949449942,135.602456664069,135.518488560399,135.436862118917,135.357530784102,135.28041774589,135.205431307775,146.467688884578,146.188442111977,145.918428012654,145.65710852713,145.404121142112,145.159100667941,144.921678739181,144.691509197362,144.468266456967,144.251644012001,144.041329443723 -2150,135.197568765324,135.101428463786,135.008266567092,134.917946894257,134.830341434848,134.745329745792,134.662798400796,134.582640487111,134.504755144949,134.42904714542,134.355426503258,145.392529057423,145.118936249136,144.854373907778,144.598404870302,144.350619534697,144.110626955176,143.877957061608,143.652383326624,143.433587684056,143.221270676506,143.015150124683 -2160,134.328622208316,134.234258838367,134.142818062082,134.054166279494,133.96817790493,133.884734775433,133.803694532077,133.724921626614,133.648381052626,133.573979307424,133.501628034728,144.315982559369,144.04804953766,143.78887547649,143.538105779901,143.295340527598,143.06020459815,142.832345793021,142.611433126437,142.397155264505,142.189104149332,141.987108141998 -2170,133.455997275296,133.363288316422,133.273449347868,133.186349235336,133.10186470733,133.019879775015,132.940285202659,132.86297802358,132.787861097105,132.714842702554,132.643836166689,143.237795715786,142.975421236785,142.721688384227,142.476179505948,142.238426524351,142.008085388666,141.784861816297,141.568432596039,141.358493675689,141.154758773708,140.956958108762 -2180,132.579320841651,132.488360761891,132.400215777906,132.314757292864,132.231864419158,132.151423409674,132.073311397217,131.997367807133,131.923574894233,131.851842633863,131.782085953381,142.158113696212,141.901184998642,141.652704475015,141.412264516875,141.17948314493,140.954002042756,140.735484766857,140.52356852835,140.317920384914,140.118340411496,139.92456513453 -2190,131.698800184995,131.609468381298,131.522899960786,131.438968747997,131.35755612806,131.278550489183,131.201846713727,131.127345712981,131.054954001345,130.98458330607,130.916150209148,141.076593261933,140.825169907933,140.582009405594,140.3465959618,140.11865369802,139.897848671269,139.683852480884,139.476356451294,139.275070183476,139.079720231098,138.890048889133 -2200,130.81402750939,130.726416409177,130.641514719273,130.559198757804,130.479352252614,130.401865794963,130.326636340823,130.253549371693,130.182460982102,130.113356361075,130.04615366297,139.993292107112,139.747176097327,139.509135193808,139.278780460077,139.055747387459,138.839694021435,138.630234301939,138.427063168755,138.229963253091,138.038667617783,137.852924668289 -2210,129.925307868825,129.839299000325,129.755948715833,129.675135710814,129.59674594466,129.520672105386,129.44681312094,129.375073712461,129.305363985355,129.2375990545,129.171698700304,138.908084319289,138.667348077787,138.434384463679,138.208914780981,137.990600106487,137.779106810885,137.574121572289,137.375349864824,137.182514579095,136.995354761432,136.813560640814 -2220,129.032053305717,128.947736853708,128.866025938889,128.786801706153,128.709952416176,128.635372921114,128.562964185961,128.492632850974,128.424290831147,128.357837293705,128.293147940172,137.820741634154,137.58517759889,137.357325445825,137.136814404858,136.92329696293,136.716406711839,136.515781675172,136.321228821363,136.132477761573,135.949273846082,135.77137704224 -2230,128.134811635241,128.052077476934,127.971892896985,127.894147388126,127.818731401654,127.745541848156,127.67448162867,127.605459206071,127.538388212714,127.473187090809,127.409778762383,136.731395588017,136.501002994623,136.27808353543,136.062334757161,135.853417769593,135.651014588786,135.454826559999,135.264572920104,135.079989485464,134.900821940483,134.726716845914 -2240,127.232675102434,127.151598958957,127.073026291125,126.996842982443,126.922941743839,126.851221610937,126.781587485063,126.713949713641,126.648223706061,126.584329581607,126.522191846329,135.639577235658,135.41430782154,135.19639681788,134.985491113188,134.781259714034,134.583287313871,134.391351754472,134.205213259831,134.024614153356,133.849311736572,133.679077222278 -2250,126.32631874922,126.246892792561,126.169918635367,126.095266047648,126.022774757173,125.95242196532,125.884114473765,125.817764419045,125.753288896451,125.690609615272,125.629652582394,134.545616709917,134.325334890907,134.11223161717,133.905968201745,133.706221991887,133.512690210987,133.325088460469,133.143149354194,132.966621272016,132.795246345293,132.628711729838 -2260,125.415133477168,125.337243305578,125.261756358252,125.188563169236,125.11756081722,125.04865244393,124.981746814427,124.91675791508,124.853604585538,124.792210181373,124.732502264461,133.448875916761,133.233647303319,133.025433265404,132.823897843447,132.628726089445,132.439507071785,132.256052425004,132.078127012799,131.905485515037,131.737896850138,131.575143161977 -2270,124.499221362211,124.422952785204,124.349036693949,124.277365962236,124.20783986711,124.140363617773,124.074847925448,124.011208610113,123.949291160546,123.889091746353,123.830545272418,132.349798738067,132.139427772838,131.935899360992,131.73888897352,131.548089729819,131.363213624811,131.183990107716,131.010164786499,130.8414982453,130.677764963615,130.518649393884 -2280,123.57863048083,123.503871957958,123.431418216137,123.36116435202,123.293011729675,123.226867519696,123.162644278372,123.100259562909,123.039635579161,122.980698858706,122.923379962455,131.247675085222,131.042237093769,130.84347934639,130.651082532325,130.464747278701,130.284131891744,130.108952396335,129.939041495194,129.774165871803,129.614105730189,129.458653834048 -2290,122.65269758267,122.579531988965,122.508621377795,122.439863140538,122.373160797404,122.308423546832,122.245565854044,122.184507074845,122.125171111192,122.067486095458,122.011384100634,130.142952230543,129.942308439543,129.74811697058,129.560130555307,129.378057623683,129.201624510325,129.030574107981,128.864664639992,128.703668539737,128.54737142642,128.395571167727 -2300,121.721920323084,121.650333489463,121.580952293684,121.513676400656,121.448411466824,121.385028047147,121.32344109785,121.263615888323,121.205477926694,121.148956860373,121.09398619262,129.03497053342,128.839076684986,128.649538106676,128.466051638846,128.288333018954,128.116115439013,127.949079057142,127.786986831129,127.629687981348,127.476973670111,127.328646973589 -2310,120.785883040645,120.715766065365,120.647808376928,120.581911796422,120.517984004906,120.455938112874,120.395692267102,120.337169291161,120.280296356257,120.22500467949,120.171229246869,127.924044980966,127.732910166694,127.547871978968,127.368683792517,127.195119700759,127.02691995144,126.86384048177,126.705651756841,126.552137709199,126.403094769498,126.258330979292 -2320,119.844316228553,119.775749188757,119.709293036506,119.644851821091,119.582335317303,119.521658604872,119.462741684418,119.405509126277,119.349889748956,119.295816324355,119.243225307178,126.809714057394,126.623121590708,126.44256862313,126.267767655253,126.098449076723,125.934359802571,125.775262031753,125.620932115381,125.471040826099,125.325492184654,125.184116530431 -2330,118.897475858429,118.830444395107,118.765475881156,118.702476572449,118.641358317202,118.581997912041,118.524317785609,118.468285902462,118.413832639223,118.360892237626,118.309402540096,125.691999392677,125.510044496268,125.333974495846,125.163494296796,124.998224751301,124.838051786895,124.682743992193,124.532083706208,124.385866016139,124.243897841154,124.105997093721 -2340,117.944977410211,117.879375788618,117.815792109503,117.754134718839,117.694317427614,117.636259110694,117.579883340485,117.525118051924,117.471895235735,117.420150657186,117.369823597919,124.570810717925,124.393280576502,124.221483206153,124.055146284632,123.894014403126,123.73784777892,123.58642108329,123.439522372847,123.296952113896,123.158522290536,123.024009824273 -2350,116.98650798071,116.922412977425,116.860288927904,116.800046339154,116.741601052889,116.684873854049,116.629790113284,116.576279459997,116.524275482966,116.473715455858,116.424540085249,123.445689497707,123.272676600455,123.105246223172,122.94313332733,122.786089330948,122.633880855946,122.486191154343,122.342869777971,122.203765411118,122.068695144194,121.937486463 -2360,116.02229280724,115.959689893483,115.899011412171,115.840170009362,115.783083536859,115.727674670286,115.673870560295,115.621602513583,115.570789495033,115.521331683811,115.473227738795,122.31689965185,122.148348424026,121.985144257919,121.827053280409,121.673897956564,121.525451392807,121.38150034676,121.241844219593,121.106294135944,120.974672102728,120.846810239061 -2370,115.052158558353,114.991021519886,114.931689377461,114.874152665402,114.818331137029,114.764149255555,114.71153585369,114.66042382233,114.610749825477,114.56245403885,114.515479909914,121.183937616406,121.019632521618,120.860616410556,120.706638728221,120.557464446375,120.412872883671,120.27265663131,120.136620573424,120.004580992628,119.876349485376,119.751664300167 -2380,114.075472011066,114.015722129884,113.957807439367,113.901644703604,113.847155643174,113.794266571782,113.742908064388,113.693014653686,113.644524552154,113.597379397191,113.551524017139,120.04673420336,119.886771686804,119.731954088036,119.582037830389,119.436794425557,119.295989100821,119.15932115897,119.026721748688,118.898012321733,118.773024597557,118.651599837966 -2390,113.092443662849,113.034142122326,112.977630676223,112.922828159719,112.869658239742,112.818049060843,112.767932921757,112.719245979586,112.6719279789,112.625922003334,112.58117424753,118.905320422302,118.749644532451,118.598859092482,118.452802956398,118.311292495851,118.17411932257,118.041087556626,117.912012904851,117.786721819267,117.665050727551,117.546845328488 -2400,112.102957190822,112.04608923526,111.990966753381,111.937510629019,111.885646454397,111.83530418513,111.786417825131,111.738925138405,111.692767385126,111.647889079617,111.604174337575,117.759185573834,117.607582518555,117.46084378933,117.318739609458,117.181054406522,117.047585735114,116.918143295795,116.792548040422,116.670631355144,116.552234313349,116.437198320601 -2410,111.106813044226,111.051363845668,110.997615978171,110.945489614059,110.894841492575,110.84567887194,110.797937365605,110.751556253673,110.706478225649,110.662649144541,110.620017830267,116.608256265689,116.460822219111,116.318114614188,116.179910342509,116.046000080933,115.91618724637,115.790287043921,115.668012435878,115.549293854514,115.433997811822,115.321978726478 -2420,110.103630534699,110.04950291891,109.997035241547,109.946152325839,109.896783465375,109.848862096806,109.802325500885,109.757114529012,109.713173352785,109.670449234339,109.628892315473,115.452514056687,115.309192952649,115.170462336608,115.03607461358,114.905745972032,114.779399270626,114.656855191917,114.537944998762,114.422509767487,114.310399686587,114.20147341455 -2430,109.093155843555,109.040417712017,108.989296333721,108.939718512071,108.891615401723,108.844922190107,108.799577806504,108.755524655941,108.712708375473,108.671077610673,108.630583810421,114.29170537281,114.152288858724,114.017330861927,113.886621404212,113.759963453633,113.637171944826,113.518072886677,113.402502548419,113.290306716259,113.181340013523,113.075465278114 -2440,108.075406143659,108.024042547596,107.974253001532,107.925966266268,107.879115336161,107.833637129346,107.789472204761,107.746564503306,107.70486111076,107.664312040374,107.624870033231,113.125240697149,112.98982113791,112.858728353983,112.731758724407,112.608721175317,112.489436230826,112.373735148517,112.261459130903,112.152458605212,112.046592564692,111.943727965429 -2450,107.050151004866,107.000146932919,106.951674691802,106.90466497683,106.859052600584,106.814776191734,106.771777919914,106.730003244051,106.689400681849,106.649921598391,106.611520012021,111.953293674577,111.821815087313,111.694533473702,111.571251475082,111.451783886528,111.335956737881,111.223606456683,111.11456353849,111.008586805245,110.905653367766,110.805634234217 -2460,106.017150870727,105.968491251719,105.92132173045,105.875574913759,105.831187410878,105.788099540753,105.746255064667,105.705600941652,105.666087104458,105.627666254094,105.590293671155,110.77561942664,110.648025677758,110.524501053714,110.404854361883,110.288906175972,110.176366704425,110.067187094108,109.9612320232,109.858360986855,109.758441510047,109.661348583262 -2470,104.976156621035,104.928826326649,104.882944884865,104.838446790955,104.795270429144,104.75335778831,104.71265420226,104.673108112139,104.634617738407,104.597182338218,104.560767849223,109.591962368748,109.468197212617,109.348325853106,109.232121139537,109.119503166159,109.010308724291,108.904384338378,108.801585552745,108.701776280017,108.604828205079,108.510620239146 -2480,103.926909108263,103.88089295564,103.836284900183,103.793021302426,103.75104229984,103.710245318786,103.670604523598,103.632090460224,103.594655775595,103.558255732772,103.522848032784,108.401982014537,108.281842242877,108.165524306245,108.052849059954,107.943648359171,107.837764229378,107.7350481106,107.635360167876,107.538568661322,107.444549369867,107.353185063424 -2490,102.869138666116,102.824421420375,102.781072007697,102.738971698169,102.698108365991,102.658440032511,102.619915047418,102.582484693921,102.54610298346,102.510726467407,102.476314064144,107.205261208443,107.088836573731,106.976111994636,106.866914181739,106.761080478367,106.65845805919,106.558903200057,106.462280611801,106.368462831598,106.277329666157,106.188767681697 -2500,101.802564588253,101.759111067765,101.716934776357,101.676028526534,101.636335817931,101.597803451695,101.560381292876,101.524022053034,101.4886810911,101.454316230719,101.4208875925,106.0017525401,105.888987164382,105.779802016286,105.674029564285,105.571512548665,105.472103207796,105.37566257314,105.282059826012,105.19117170987,105.10288199264,105.017080974191 -2510,100.726888663684,100.684651662414,100.64370546146,100.603991794947,100.565455850874,100.528046018992,100.49171366045,100.456412897037,100.422100418112,100.388735303504,100.35627886087,104.791156690263,104.681994675511,104.576295015301,104.473895838111,104.374645189542,104.278400285782,104.185026833373,104.094398408512,104.006395889915,103.920906939946,103.837783440683 -2520,99.6418093217304,99.6008264016929,99.5610954718476,99.5225600390726,99.485166957852,99.4488661859954,99.4136105614396,99.3793555980311,99.3460592984405,99.3136819825533,99.2821861298604,103.573161263054,103.467546717348,103.365278609798,103.266200630628,103.170166038795,103.077036942172,102.986683641614,102.898984032408,102.81382305735,102.731026472149,102.650510629332 -2530,98.5470360172408,98.5073212993246,98.4687907782489,98.4314191878547,98.3951550271819,98.3599498015034,98.325757806183,98.2925359289079,98.2602434685067,98.2288419687516,98.1982950657125,102.347440175298,102.24531723677,102.146426776924,102.050617949235,101.95774913387,101.867687244086,101.780307094161,101.695490822584,101.613083032731,101.532953827532,101.455076044898 -2540,97.4421994347635,97.4037465471841,97.3664640926655,97.3302419135596,97.295092692461,97.2609694614657,97.2278279539616,97.1956264132207,97.1643254170378,97.1338877168662,97.1042780900682,101.113653000074,101.014965858854,100.91939919256,100.82680751931,100.737054248243,100.650011011643,100.565557056281,100.483578687931,100.403879444731,100.326424466755,100.251143730749 -2550,96.3269694725141,96.2897231227044,96.2536134165302,96.2185891165792,96.1846020187683,96.1515838178294,96.1194796218062,96.0882856339506,96.0579636937975,96.0284777442455,95.9997936886323,99.8714442618477,99.7761371802169,99.6838405230019,99.5944140743483,99.5077261801403,99.4236531053561,99.3420784483634,99.2628926063525,99.1859107436588,99.1110877092029,99.0383630427414 -2560,95.2009862796903,95.1649309336885,95.129975442952,95.0960702476185,95.0631687207474,95.0312269545634,95.0002035651274,94.9700595135987,94.9407579424745,94.9122558953821,94.8844856757059,98.6204426802172,98.5284600111651,98.4393796656341,98.3530665952662,98.2693939905613,98.1882426629611,98.1095004816429,98.0330618594532,97.9588107496148,97.8865774252541,97.8163678994726 -2570,94.0638742815566,94.0289943713029,93.9951780284614,93.9623773470654,93.9305472551238,93.8996453081515,93.8696315004921,93.8404680926618,93.8121194531555,93.7845519133211,93.7577336340534,97.3602603590081,97.2715465633599,97.1856289352657,97.1023774955069,97.021670187244,96.9433922823243,96.8674358401176,96.7936992135339,96.7220865975046,96.652507615738,96.5847759803268 -2580,92.9152413274595,92.8815212528097,92.8488289589517,92.8171181701362,92.786345347107,92.7564694878061,92.7274519452482,92.699256260853,92.671848011735,92.6451946706031,92.6192654770666,96.0904919170804,96.0049915793464,95.9221831924774,95.8419417482894,95.7641498508922,95.6886971467175,95.6154798049383,95.5444000431544,95.4753656938192,95.4082898073925,95.3430902886364 -2590,91.7546777823921,91.7221019130918,91.6905185398232,91.6598829933593,91.6301532449469,91.6012897140758,91.5732550928036,91.5460141849854,91.5195337589618,91.4937824124077,91.4687304481805,94.8107135568444,94.7283713999258,94.6486189099341,94.5713359519371,94.4964096995906,94.4237340883832,94.3532093171819,94.2847413931679,94.2182417158317,94.1536266961774,94.090817407705 -2600,90.5817555577231,90.5503082353423,90.5198186266372,90.4902436451953,90.4615427505224,90.4336777627645,90.4066126933821,90.3803135901854,90.3547483953367,90.3298868150709,90.3057002000151,93.5204820660607,93.4412429649323,93.3644931722131,93.2901173288259,93.2180070869349,93.1480605859038,93.0801819745103,93.0142809747182,92.9502724828618,92.8880762045569,92.8276163200554 -2610,89.3959172574409,89.3656423767343,89.3362815901529,89.3077524710422,89.2800661843162,89.2531859298779,89.227077018943,89.2017067247885,89.1770441459854,89.1530600809143,89.1297269124863,92.2193337480512,92.1431427425267,92.069342604248,91.9978226530396,91.9284789289543,91.8612136904414,91.7959349567763,91.7325560902537,91.6709954141848,91.6111758631722,91.5530246625231 -2620,88.1962260064197,88.1670465122057,88.1387550198593,88.111311606926,88.0846787083576,88.0588209450612,88.0337049671998,88.0092993107767,87.9855742662126,87.9625017577632,87.9400552327398,90.906558900071,90.8334820128885,90.7626822229958,90.6939671013301,90.6273405544142,90.5627088754302,90.4999838751458,90.4390824821181,90.3799263771274,90.3224416584748,90.2665585351419 -2630,86.9826689121938,86.9545690254829,86.927323920572,86.9008951844482,86.8752466714577,86.8503443384689,86.8261560942122,86.8026516613869,86.7798024502944,86.757581442891,86.7359630862643,89.5815471515527,89.5114048086175,89.4434594117729,89.3776094284317,89.3137594817308,89.2518198914346,89.191706255287,89.1333390667072,89.0765584528208,89.0213667980642,88.967711266094 -2640,85.7547262526516,85.7276901749079,85.7014761642979,85.6760472934556,85.6513688137938,85.62740799717,85.6041339911638,85.5815176866143,85.5595315962257,85.5381497431783,85.5173475587895,88.2439895184623,88.1767271021348,88.1115689894761,88.0484180367078,87.98718298352,87.9277780147139,87.8701223604304,87.8141399310516,87.7597589833277,87.7069118146593,87.6555344828004 -2650,84.5111663593859,84.4852325201293,84.4600869763934,84.4356943287056,84.4120212656201,84.389036412021,84.3667101904614,84.3450146942469,84.3239235711206,84.3034119165332,84.2834561755815,86.8933202926575,86.8288834064244,86.7664600699078,86.7059574327974,86.6472882622332,86.5903705246903,86.535127004634,86.4814849562181,86.4293757847435,86.3787347549553,86.3295007235721 -2660,83.2516780244732,83.2267743579176,83.2026273420581,83.1792030129785,83.1564694092796,83.1343964266538,83.1129556849514,83.0921204065026,83.0718653045988,83.0521664811605,83.0330013327136,85.5285174602062,85.4669632486473,85.4073309511156,85.3495320048963,85.2934828385209,85.2390051295348,85.1861280745308,85.1347821987719,85.0849019879202,85.0364256100127,84.9892946605109 -2670,81.9758200068717,81.9519827600747,81.9288695176187,81.9064331047398,81.8846245226391,81.863449412967,81.8428805731308,81.8228923359058,81.8034604626298,81.784562045192,81.7661754159762,84.1488336799283,84.089991685194,84.0329847316324,83.9777283566007,83.924143198835,83.872154619324,83.8216923554819,83.7726902052429,83.7250857381146,83.6788200305422,83.6338374232268 -2680,80.6818614768022,80.6590205068388,80.6368729730988,80.6153877727119,80.5945356352997,80.5742889899917,80.5546218438556,80.5355096706154,80.5169293086535,80.4988588674103,80.4812776413786,82.7540296901168,82.6978460647752,82.6434124674842,82.5906484420761,82.5394783863474,82.4898311917071,82.4416399144426,82.3948414754005,82.3493763852685,82.3051884929496,82.2622247547899 -2690,79.3701956387261,79.3483502239995,79.3271529577816,79.3065893260305,79.2866313387823,79.2672526305484,79.2484283441612,79.2301350244447,79.2123505207542,79.1950538975347,79.1782253521353,81.3424084719442,81.2889324130985,81.2371205998175,81.1868965790878,81.1381885072055,81.0909288077878,81.0450538597747,81.000503712388,80.9572218243751,80.915154825162,80.8742522957904 -2700,78.0384736128864,78.0176248119511,77.9974084587265,77.9777962079125,77.9587613829765,77.9402788551396,77.9223249327404,77.9048772599578,77.8879147239749,77.8714173697819,77.8553663218876,79.9138329244714,79.8629024473992,79.813555051112,79.7657180976161,79.7193233231817,79.6743065141545,79.6306072111668,79.5881684388773,79.5469364587134,79.5068605423663,79.467892764029 -2710,76.6870044101888,76.6671486885792,76.6478950720051,76.6292165844361,76.6110878374687,76.5934849152322,76.576385269164,76.5597676216805,76.5436118778772,76.52789904449,76.5126101196787,78.4667013167378,78.4183611673425,78.3715222148541,78.3261156355707,78.2820767472634,78.2393447024433,78.1978622084838,78.1575752718848,78.1184329642906,78.080387208134,78.0433925800099 -2720,75.313796682465,75.2948687894005,75.2765146021303,75.2587084285747,75.241426088048,75.2246448017382,75.2083430925741,75.1925006935551,75.1770984637166,75.1621183110052,75.1475431214038,77.0005688421618,76.9546619070109,76.9101788260078,76.8670544006634,76.8252273511709,76.7846400265076,76.7452381398899,76.706970527022,76.6697889248865,76.6336477690701,76.5985040078344 -2730,73.9179586265785,73.8999863885688,73.8825586879567,73.8656511476348,73.8492408240386,73.8333061033024,73.8178266063128,73.8027831017839,73.7881574265709,73.7739324125338,73.7600918193258,75.5133332580958,75.4698985243078,75.4278096892807,75.3870051781355,75.3474271139079,75.3090210441818,75.271735691614,75.2355227259411,75.2003365553459,75.166134135295,75.1328747931582 -2740,72.498458541106,72.481422641325,72.4649027134343,72.4488756675641,72.4333197712093,72.4182145509365,72.4035407025113,72.3892800086159,72.3754152634158,72.3619302033255,72.3488094433812,74.0046152737913,73.9635931671546,73.9238409600823,73.8853006075183,73.8479175473954,73.8116404433568,73.7764209499475,73.7422134980098,73.708975098289,73.6766508897283,73.6451588896346 -2750,71.0535971379861,71.0374360228069,71.0217641539029,71.0065596475245,70.9918019057982,70.9774715236517,70.9635502037089,70.9500206783705,70.936866638376,70.9240726672354,70.9116241809683,72.4727116153985,72.4339518712771,72.3963904557839,72.3599726639601,72.3246470693803,72.2903652822671,72.2570817287086,72.2247534488485,72.1933399121829,72.1628028482949,72.1331060915398 -2760,69.5813831188137,69.5661201836873,69.5513191245934,69.5369592898234,69.5230212407075,69.5094866638436,69.4963382908382,69.4835598248224,69.4711358730778,69.4590518851964,69.447294096245,70.9154687232885,70.8790024047011,70.8436623736579,70.8093972627515,70.7761587803429,70.7439014838244,70.7125825726492,70.6821616991322,70.6526007952762,70.6238639140621,70.5959170838098 -2770,68.0805657055671,68.066181149979,68.0522317174239,68.0386979598614,68.0255615711631,68.0128053045174,68.0004128969021,67.9883689999292,67.9766591164381,67.9652695422958,67.9541873129039,69.3317685289105,69.2975350882802,69.2643578821177,69.2321887850213,69.2009825505746,69.1706965992998,69.1412908250817,69.1127274182003,69.0849707033406,69.0579869911205,69.0317444418388 -2780,66.5491446173451,66.5356184590875,66.5225012934969,66.5097748475894,66.4974219208902,66.4854263078876,66.473772727119,66.4624467562393,66.4514347724836,66.4407238980177,66.4303019497071,67.7195951643886,67.6875336890212,67.6564603946408,67.6263303016963,67.597101118865,67.5687330452353,67.5411885897048,67.5144324058615,67.4884311408272,67.4631532967043,67.438569103418 -2790,64.9849340949581,64.9722461795552,64.9599417540962,64.9480036918245,64.9364158708265,64.9251631014057,64.9142310596656,64.9036062266938,64.8932758327952,64.8832278063048,64.8734507265347,66.0767409624351,66.0467902439531,66.017761660946,65.9896132831528,65.9623056838415,65.9358017557546,65.9100665430596,65.8850670876923,65.8607722886832,65.8371527732021,65.8141807782001 -2800,63.3855411324473,63.3736711423369,63.3621597717324,63.3509910110788,63.3401497897454,63.3296219081916,63.319393975927,63.3094533547043,63.2997881064251,63.2903869453221,63.2812391940032,64.4007840935965,64.3728826934133,64.3458393965629,64.3196152252988,64.2941735267744,64.2694798022857,64.2455015513493,64.2222081291228,64.19957061586,64.1775616972323,64.156155554476 -2810,61.7481983189323,61.7371597215652,61.7264545091759,61.7160678037396,61.7059855995106,61.6961768288408,61.6866354421381,61.6773619756402,61.6683453012361,61.6595748986581,61.6510408145374,62.689062922949,62.6631492341621,62.6380316325909,62.6136739961824,62.5900423552266,62.5671047344284,62.5448310086908,62.5231927712238,62.5021632127775,62.4817170109178,62.4618302283847 -2820,60.0691631889374,60.0588997398759,60.0489461321488,60.0392885442149,60.0299139645396,60.0208101331168,60.0119654879812,60.0033691162313,59.9950107091089,59.9868805207693,59.9789693303735,60.9386465166741,60.9146588227329,60.8914072160263,60.8688583334853,60.8469807978869,60.8257450722904,60.8051233271016,60.7850893184852,60.765618277024,60.7466868056274,60.7282727858065 -2830,58.3458115500033,58.3363024072007,58.3270802091167,58.3181321610532,58.3094462178276,58.3010110296837,58.2928158928174,58.2848507040719,58.2771059193846,58.2695725156469,58.2622419556345,59.1451324400574,59.12307504573,59.1016938739639,59.0809583020695,59.0608395285758,59.0413104398381,59.0223454882097,59.0039205806048,58.9860129764473,58.9686011940909,58.9516649249019 -2840,56.5738039418028,56.5650578113692,56.5565755018747,56.548345254003,56.5403559970553,56.532597299273,56.5250593223981,56.5177327800602,56.5106088996102,56.5036793870866,56.496936395001,57.3054404414781,57.2851809533087,57.2655418420478,57.2464950460029,57.2280141705368,57.2100743660983,57.1926522168156,57.1757256385836,57.1592737857242,57.1432769653878,57.1277165589575 -2850,54.748087293525,54.7400514336603,54.7322578607678,54.7246957801412,54.7173550289299,54.7102260305771,54.7032997531408,54.6965676711249,54.6900217304689,54.6836543164122,54.6774582239406,55.4145134906281,55.3960501737809,55.3781516698432,55.3607924548046,55.3439485195729,55.3275972592329,55.311717371887,55.296288766108,55.2812924761736,55.2667105843227,55.2525261493686 -2860,52.8632025199733,52.8558822483441,52.8487826007684,52.841893751495,52.8352064496962,52.8287119780239,52.8224021147004,52.8162690987993,52.810305598397,52.8045046813413,52.798859788365,53.4671811367993,53.4503866651175,53.4341053319193,53.418313975903,53.4029908088527,53.3881153153801,53.3736681613314,53.3596311099814,53.3459869452692,53.3327194013838,53.3198130981033 -2870,50.9129209264859,50.9062914302802,50.8998616574519,50.8936227166352,50.887566236513,50.8816843283416,50.8759695516724,50.8704148829568,50.8650136867448,50.8597596892509,50.8546469540395,51.4559610385949,51.4408262234757,51.4261533516951,51.4119215939042,51.3981113543817,51.3847041810439,51.3716826832251,51.359030456442,51.3467320134733,51.3347727211368,51.3231387422274 -2880,48.8891102257483,48.8831462636669,48.8773618992746,48.8717491404594,48.8663004623727,48.8610087737714,48.8558673862298,48.8508699859402,48.8460106078427,48.8412836118794,48.8366836611537,49.3739318112634,49.3603863266709,49.3472538272069,49.3345157107122,49.3221544756229,49.3101536407622,49.2984976720549,49.2871719154595,49.2761625355246,49.2654564590206,49.2550413231674 -2890,46.7822549171977,46.7769308484616,46.7717670383928,46.7667563584943,46.7618920968674,46.7571679282153,46.7525778864041,46.7481163393286,46.7437779658543,46.7395577346527,46.7354508847321,47.2116027637514,47.1995755713366,47.1879146624377,47.1766035564978,47.1656267469931,47.1549696305226,47.14461844201,47.1345601953996,47.1247826293189,47.1152741572259,47.1060238216182 -2900,44.5811508213258,44.5764406356606,44.5718721669123,44.5674391141105,44.563135544363,44.5589558663633,44.5548948061576,44.5509473849455,44.5471088987132,44.54337489954,44.5397411783995,44.9566771950347,44.946141678102,44.9359266927512,44.9260178310518,44.9164015358072,44.9070650386782,44.897996303633,44.8891839751889,44.8806173309859,44.8722862382696,44.8641811139176 -2910,42.2695903578655,42.2654870828993,42.2615072134917,42.2576452650466,42.2538960732309,42.2502547709303,42.2467167671732,42.2432777278211,42.2399335578521,42.236680385101,42.2335145452969,42.5948623472796,42.5856971121238,42.5768103851436,42.5681896620802,42.5598231761526,42.551699844479,42.5438092191064,42.5361414421834,42.5286872048817,42.5214377097005,42.5143846358359 -2920,39.8299321197139,39.8264056207662,39.8229851346072,39.8196659516575,39.8164436372291,39.813314011755,39.8102731327044,39.807317278015,39.8044429308913,39.8016467658512,39.7989256358864,40.1069069781787,40.0990771183521,40.0914849237537,40.0841197354335,40.0769715224202,40.0700308361467,40.0632887687884,40.0567369151247,40.050367337585,40.044172534174,40.0381454089979 -2930,37.2363911158711,37.2334104792486,37.2305194044432,37.2277139145104,37.22499026453,37.2223449249268,37.2197745662125,37.2172760450055,37.2148463912044,37.2124827962141,37.2101826021105,37.4681882686138,37.4616123832426,37.4552358658864,37.4490497854626,37.4430457364756,37.4372158009158,37.4315525134245,37.4260488294034,37.4206980957838,37.4154940242012,37.4104306663416 -2940,34.4547448181611,34.4522933512119,34.4499155121755,34.4476080331033,34.4453678366227,34.4431920222433,34.4410778538299,34.4390227481236,34.4370242642091,34.4350800938475,34.4331880525787,34.6434231624328,34.6380501259349,34.6328398036827,34.6277849147022,34.6228786060308,34.6181144217237,34.6134862745136,34.6089884198623,34.6046154321751,34.6003621829726,34.5962238208241 -2950,31.4341236712243,31.4321653931892,31.4302659012052,31.4284225873535,31.4266329957276,31.4248948115148,31.423205851009,31.421564052459,31.4199674676675,31.4184142542855,31.4169026687149,31.5831621867139,31.5789003705417,31.5747674560487,31.5707576823359,31.5668656267519,31.5630861804267,31.5594145259004,31.5558461166348,31.5523766582343,31.5490020912079,31.5457185751224 -2960,28.0990596776223,28.0975575177045,28.0961004263933,28.0946864054111,28.0933135728968,28.0919801550439,28.0906844784588,28.0894249631557,28.0882001161232,28.0870085254266,28.0858488547745,28.2116048349711,28.2083850407466,28.2052625047907,28.2022328859753,28.1992920977377,28.1964362896921,28.1936618308107,28.1909652940184,28.1883434420751,28.1857932146099,28.1833117162052 -2970,24.3182684751628,24.3172033704836,24.3161702029151,24.3151675572275,24.3141941005942,24.3132485766751,24.3123298002107,24.3114366520667,24.3105680746798,24.3097230678877,24.3089006850823,24.3973140586133,24.3950323029105,24.3928193668559,24.3906721832409,24.3885878644567,24.3865636895407,24.3845970923226,24.3826856505702,24.3808270760408,24.3790192053404,24.3772599915256 -2980,19.8421138268028,19.8414458982659,19.8407979830919,19.8401691950568,19.8395586995045,19.8389657096419,19.8383894831599,19.837829319138,19.8372845551898,19.8367545648573,19.8362387552069,19.8909785698865,19.8895604680665,19.8881850635616,19.886850456636,19.8855548586085,19.8842965838534,19.8830740424836,19.8818857336445,19.8807302393729,19.8796062189506,19.8785124037175 -2990,14.0186817099014,14.0183730095292,14.0180735496328,14.0177829214291,14.0175007399003,14.0172266420861,14.0169602855274,14.0167013468423,14.0164495204105,14.0162045171747,14.0159660635317,14.0409085854145,14.0402598564366,14.0396306144381,14.0390199943689,14.0384271816341,14.0378514084684,14.0372919506175,14.0367481242975,14.0362192834055,14.0357048169674,14.0352041467747 -3000,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 diff --git a/data/Gemini_Portugal_October_2023/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_trajectories_Gemini_Portugal_October_2023.csv b/data/Gemini_Portugal_October_2023/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_trajectories_Gemini_Portugal_October_2023.csv deleted file mode 100644 index df0fab45871e665463e8b14d836cacc499919fad..0000000000000000000000000000000000000000 --- a/data/Gemini_Portugal_October_2023/data/Gemini_Portugal_October_2023/HIL_CPP_files_ABK/ABK_trajectories_Gemini_Portugal_October_2023.csv +++ /dev/null @@ -1,1003 +0,0 @@ -Z,Vz -944.143829309707,267.033308834361 -949.739213950982,267.815224529649 -954.607896989672,267.396873770192 -959.323990588156,266.972340820669 -964.642892081877,266.613744707637 -969.797057026061,266.243594944017 -975.299894915225,265.913400772374 -980.123667557248,266.184752285399 -984.808896520356,266.361775416692 -989.951055558181,266.513844620896 -994.942827819506,266.57069440951 -1000.44221101802,266.608509904703 -1005.12190666132,266.465193672545 -1009.65815824927,266.222155565964 -1015.15290326505,266.030692236553 -1020.47950605878,265.740096372786 -1025.83163024033,265.391014030997 -1030.82486054959,264.998279815468 -1035.65963140687,264.580692581593 -1041.24228174324,264.279844296988 -1046.65095285706,263.953883125381 -1052.16439055319,263.646546649336 -1057.23002708901,263.236038216129 -1062.1333691433,262.770989803552 -1067.55581192326,262.371454476991 -1072.80540979144,261.94359565964 -1078.20149387979,261.571628265961 -1083.10933215749,261.081340805707 -1087.85616363881,260.532765034522 -1093.0977898689,260.060274916503 -1098.16855324496,259.536302734556 -1103.65781586109,259.093901715883 -1108.38165494711,258.469849838494 -1112.9453358111,257.798423730224 -1117.8926215078,257.207426685951 -1122.67325628761,256.575257650797 -1128.35405783404,256.157490374138 -1132.78361246479,255.444012744005 -1137.05785284533,254.692639067854 -1142.24517950329,254.189139404306 -1147.25863089274,253.646120027906 -1152.48860323558,253.162935579395 -1157.15533059422,252.533574854625 -1161.65958421575,251.862830147904 -1167.09408823761,251.449519536525 -1172.34704519516,250.990811712715 -1177.88345254087,250.617236894418 -1182.77275136245,250.064295023064 -1187.49243931429,249.466283142032 -1192.22283184271,248.876603879289 -1196.78675666557,248.240356545835 -1201.99198528293,247.802828186906 -1206.21217714944,247.064629647325 -1210.27706071521,246.280659320608 -1215.83418613291,245.972593854658 -1221.20326140184,245.609087474955 -1226.34004874519,245.17539332278 -1231.34656671159,244.705373672168 -1236.17713676616,244.18374907403 -1241.73131305608,243.909529135341 -1247.09559744054,243.576827668277 -1252.42938624273,243.239021505141 -1257.42219117613,242.784614955213 -1262.23749104377,242.269958016059 -1267.36226266203,241.867636477608 -1272.30551644788,241.407310941609 -1277.47960605945,241.034617595647 -1282.06093366928,240.448530902061 -1286.47301299161,239.804182684672 -1291.21411935294,239.287719462976 -1295.78147372922,238.711290056901 -1300.83538298187,238.323600718505 -1305.04919773887,237.634577676099 -1309.10173968436,236.887902981818 -1314.48266152585,236.659515389021 -1319.67267986692,236.362146477609 -1323.68852845656,235.607443567255 -1328.53710472076,235.189631315828 -1333.20722394371,234.706267841498 -1337.7904255408,234.19349425808 -1342.20134345863,233.615548425974 -1346.8092192636,233.123629444358 -1350.87776190346,232.418092463044 -1354.78647439406,231.653364242069 -1359.74216563879,231.327223522598 -1364.51499598708,230.929821314154 -1368.85523142087,230.357581315623 -1373.28263511498,229.828312353437 -1377.54010682869,229.234163521493 -1382.51424018002,228.951262569058 -1387.30393633565,228.593826983489 -1391.84343871318,228.133887433565 -1396.27975796838,227.632590206588 -1400.54494209576,227.06149143963 -1405.48889242188,226.789676848334 -1410.24798938308,226.443125795776 -1415.53971097777,226.333567106833 -1419.92289124323,225.826399066035 -1424.1353362055,225.248012291721 -1428.97787609485,224.95333056185 -1433.6371407896,224.582548304334 -1438.72197253322,224.405160937422 -1443.01157821713,223.874653404891 -1447.13210877467,223.273684698035 -1451.83611869268,222.941385077336 -1456.35969289966,222.532246628903 -1460.9213706138,222.145207643586 -1465.09202787331,221.582411659551 -1469.09620258351,220.948820210406 -1473.6419999265,220.568916806516 -1478.01096195051,220.123457645666 -1482.30867729312,219.649404137601 -1486.33548777407,219.057075636006 -1490.19955906075,218.39395872211 -1495.02846677872,218.187503330727 -1499.67257236505,217.896984165635 -1504.21457260062,217.56309362537 -1508.50148817173,217.115321998822 -1512.61815773991,216.593842323907 -1517.64032785631,216.501865189043 -1522.47178255634,216.321382624302 -1527.16461494608,216.079986060154 -1531.62854306148,215.734537962416 -1535.91687303425,215.309398932643 -1540.15758626686,214.864918517472 -1544.22875137909,214.344406155529 -1548.46438743605,213.908884242613 -1552.20094959705,213.240455042159 -1555.78200933823,212.50654693512 -1560.30934502399,212.230564756246 -1564.65904593375,211.87419151496 -1568.89765564217,211.468154305086 -1572.90501250139,210.958978128472 -1576.74931815644,210.376550148024 -1581.47350647816,210.223613826059 -1586.01438778807,209.984589149042 -1590.62339810325,209.781528199143 -1594.80570545014,209.374227024692 -1598.81983869801,208.888055733549 -1603.02336310755,208.499241307648 -1607.05807574216,208.031802093021 -1611.28506949744,207.662676767725 -1614.9860262336,207.043020955053 -1618.5324910057,206.354801625798 -1622.87609960609,206.059790617637 -1627.04694277532,205.686170726223 -1631.22562987641,205.320706759414 -1635.06055171435,204.791782885343 -1638.73730650761,204.19244054269 -1643.54610054176,204.152010901685 -1648.16887632651,204.022361516244 -1652.27335664478,203.642022123643 -1656.54969849626,203.356857074211 -1660.65538423391,202.990719612448 -1664.65739964756,202.579913932089 -1668.49670092251,202.094096913033 -1672.31861398155,201.606030128636 -1675.84246182372,200.977045562334 -1679.21756497797,200.282253497524 -1683.75229532478,200.163466010098 -1688.10920096601,199.959024152954 -1691.80157991143,199.43064105184 -1695.83249653704,199.076140875721 -1699.70024431888,198.645560248171 -1703.69344348554,198.281426380366 -1707.52464594239,197.842846524037 -1711.9313020834,197.692453413818 -1715.43114354752,197.098281806127 -1718.78346028952,196.437027535869 -1722.95152920994,196.184757036388 -1726.95279043094,195.853792281894 -1731.14580495487,195.622261527307 -1734.81759738275,195.13602690913 -1738.3371430095,194.578650639967 -1742.17619754658,194.186394112847 -1745.85828156877,193.721672132857 -1750.07282045129,193.525433373909 -1753.4346311068,192.909337102392 -1756.65356096004,192.232002304888 -1760.30760326503,191.776500625895 -1763.81048251258,191.250601430781 -1767.89815691421,191.020377465559 -1771.09051654988,190.354192276545 -1774.14550431604,189.629165504391 -1777.65985545936,189.140169335493 -1781.02770699345,188.584271656931 -1785.20029508384,188.434330615089 -1788.26028336552,187.738137520418 -1791.18738707238,186.98327635474 -1794.83795317402,186.598410096692 -1798.33863144713,186.142822934124 -1802.4928641205,186.01796807944 -1805.68347320127,185.41898853972 -1808.73792023282,184.760092202831 -1812.71099345795,184.565459732 -1816.52519142478,184.294690157018 -1820.45498594665,184.083920495968 -1823.95744059887,183.665842285722 -1827.31500036236,183.181208465462 -1831.30715106502,183.016940476177 -1835.1401747387,182.779040016406 -1839.10344588831,182.608455998233 -1842.62392659573,182.221619846668 -1845.99934344327,181.767438487291 -1850.14829953233,181.703070976868 -1854.13385215203,181.55860530632 -1858.52254260047,181.616779074259 -1862.17902769664,181.310193472825 -1865.68662509685,180.933048750109 -1869.43296158546,180.678817158537 -1873.02788695127,180.350652239602 -1877.16915257011,180.299737682986 -1880.45414756857,179.822381702044 -1883.6014260243,179.279841736999 -1887.31898529374,179.027884846926 -1890.88624856737,178.702918546746 -1895.11796233072,178.713840688692 -1898.37398550216,178.237554488366 -1901.49340757936,177.697403251661 -1905.64637254318,177.677892085675 -1909.63644701647,177.578089682591 -1914.32464382828,177.827618306628 -1917.97793155139,177.556723681513 -1921.48300232425,177.212837571321 -1925.06150472724,176.907986342902 -1928.49404767761,176.534851798302 -1932.12156225442,176.262253739755 -1935.26524984588,175.750774949245 -1938.2759945722,175.176804562208 -1941.76135022004,174.846337730108 -1945.10386762328,174.447365180128 -1948.93506640962,174.296637217485 -1951.98606150627,173.759945432635 -1954.90723475428,173.165843017927 -1958.15970773362,172.743266766361 -1961.27666075764,172.257549762789 -1965.12206752336,172.141483190131 -1967.95471473144,171.5233316007 -1970.66450364268,170.850258753013 -1974.06780253251,170.530952673045 -1977.33164381562,170.145568359696 -1980.73721602332,169.835117937566 -1983.72639350411,169.321781132438 -1986.58858657318,168.752699692512 -1990.08446849244,168.505566445847 -1993.43863733254,168.191999861208 -1996.49473063537,167.733430236028 -1999.58289706048,167.298077888122 -2002.54168928341,166.80321447779 -2005.64851930737,166.3892174312 -2008.62564995704,165.915127769454 -2012.24369565572,165.765988630267 -2014.95039739678,165.166035369151 -2017.53949133423,164.514988327438 -2021.09687786845,164.354362782562 -2024.51177527005,164.12540413496 -2028.3636460091,164.117344606781 -2031.48921166585,163.748066378269 -2034.48518675567,163.319746701278 -2037.95726311301,163.134147318708 -2041.28970021153,162.881385642869 -2044.5292414956,162.583659215724 -2047.5935286183,162.204346589623 -2050.5304245527,161.765035012751 -2053.83649596053,161.514990210126 -2057.00818398834,161.199803195265 -2060.83081713214,161.214454771396 -2063.72258330024,160.764443387056 -2066.49235259799,160.258300363424 -2069.69976222057,159.976588053405 -2072.77603827423,159.630214633178 -2076.49198145959,159.608734276167 -2079.29494703877,159.130948129591 -2081.97885658343,158.599306662166 -2085.17194923981,158.329356447245 -2088.23468919964,157.996049293901 -2091.73919494492,157.88847360617 -2094.53602778174,157.428089653323 -2097.21437509734,156.91357857112 -2100.53862495588,156.726540124533 -2103.72896972994,156.474968289322 -2107.39551745988,156.464818808623 -2110.31203557281,156.081301607122 -2113.10685062932,155.64112034584 -2116.10374375226,155.306636917374 -2118.97672434728,154.91344934683 -2122.60088122988,154.900954110097 -2125.21135878653,154.383013758616 -2127.7095425319,153.814074874892 -2131.39299848153,153.843802846064 -2134.93262574659,153.802535221079 -2138.20594464968,153.627466748974 -2141.47432725058,153.453697665323 -2144.61123836234,153.216864308528 -2147.93114804238,153.07237946852 -2151.11812780605,152.863895910292 -2154.186320675,152.599099575797 -2157.11897505321,152.269781712771 -2159.93032644653,151.882149635003 -2163.39327881014,151.823891765794 -2166.71934775666,151.69829730589 -2170.19484255898,151.648627446191 -2173.2508871849,151.388433998567 -2176.18211780718,151.067714215796 -2179.57827695607,150.98378130444 -2182.83967497154,150.834312642221 -2186.10753730857,150.688865829908 -2189.10728236522,150.410014706315 -2191.98406000735,150.07244446459 -2195.55647660168,150.086541641337 -2198.98910358979,150.029932218252 -2202.09436819441,149.811582356003 -2205.26538428336,149.626656132028 -2208.30852161592,149.37914997906 -2211.65721820495,149.286791527458 -2214.87284827053,149.129845650495 -2218.02645178112,148.942845013342 -2220.98575333493,148.66001486825 -2223.82359356238,148.319722964736 -2227.3012639115,148.302356396825 -2230.64225070362,148.216339140363 -2233.37270046887,147.826747687461 -2236.46650244185,147.621875263694 -2239.43506676399,147.355164281845 -2242.39766156374,147.088253548204 -2245.23897027721,146.763810947068 -2247.75960951805,146.281689493438 -2250.37518750503,145.851020336209 -2252.87993741581,145.371451103028 -2255.44338817012,144.924625856335 -2257.89774388039,144.428895382419 -2260.77484021369,144.149933507046 -2263.00527081458,143.549503665681 -2265.13671112831,142.907617002104 -2268.22443792357,142.749664892002 -2271.18806465688,142.532039707027 -2274.06687945172,142.273887367243 -2276.79228999576,141.943731549217 -2279.40449651178,141.560485716496 -2282.63837077277,141.492907499013 -2285.74415076746,141.363963158607 -2288.69165994107,141.157031781066 -2291.55364406077,140.910539688571 -2294.29867654935,140.609687518824 -2296.81013346603,140.194438462658 -2299.21513922935,139.730157452153 -2302.37527663199,139.648719912792 -2304.5515916182,139.077109413383 -2306.63159094876,138.462739772537 -2309.49696750477,138.249381393392 -2312.24589548106,137.980216214312 -2315.2947805734,137.862830533743 -2317.80895335565,137.480336050203 -2320.21719740114,137.049244721517 -2322.98353042008,136.801807558117 -2325.63664298725,136.50146038979 -2329.40991954736,136.764244918473 -2331.81033620494,136.338657311657 -2334.10845602418,135.867128574949 -2336.90967888284,135.653368722616 -2339.59696013686,135.384329546689 -2342.74866803788,135.349379945405 -2345.20116477081,134.966150029556 -2347.55013640141,134.534566988902 -2350.5313908945,134.423956623185 -2353.39362676763,134.2566223729 -2356.65796966283,134.291911229876 -2359.27744847207,134.005056720463 -2361.78870671794,133.666601599157 -2365.0638200771,133.713435820597 -2368.21141803989,133.69631062719 -2370.84739283106,133.423773486574 -2373.76265383622,133.292547941683 -2376.56108725167,133.105109679702 -2378.87023649277,132.674348354333 -2381.08056743637,132.198185527601 -2384.10921219889,132.136625158811 -2386.10379195983,131.558649099542 -2388.00905856629,130.941036285621 -2391.36364443088,131.054686510665 -2394.588882301,131.102880478757 -2397.25348704506,130.870345346303 -2400.2442442887,130.804155482853 -2403.11646315725,130.67880860382 -2406.03532372041,130.579303180605 -2408.83782469417,130.42249956193 -2411.39543808543,130.145285733316 -2413.97943070155,129.882916476652 -2416.45706409725,129.569617836603 -2419.53058175933,129.55744935706 -2422.48335392772,129.483842520908 -2424.6497790842,129.019103306 -2427.39148427981,128.846703675183 -2430.02237516441,128.620257330417 -2432.30308457622,128.221079752682 -2434.48669737815,127.776571175881 -2437.37573217083,127.690496349235 -2439.35025196947,127.14730887821 -2441.23691344042,126.566465990412 -2444.81653449022,126.836580656072 -2448.26099000346,127.03707160117 -2450.82282653094,126.794482765549 -2454.03096789223,126.876345676298 -2457.11489183917,126.895208333499 -2459.53936673699,126.583733004634 -2461.86279319541,126.224858912335 -2464.75777606728,126.154725343837 -2466.86834592136,125.692090466531 -2468.88727078416,125.187863312631 -2471.75909875128,125.115086532445 -2474.51692442939,124.985254900507 -2476.93551550362,124.68724638156 -2479.4821535276,124.456630742531 -2481.92450684585,124.17524781504 -2484.17658107181,123.800239680139 -2486.3331457346,123.384210830809 -2488.97930088623,123.215953668642 -2490.93632408961,122.705665235821 -2492.80680707869,122.157751616203 -2495.36220932396,121.958948038531 -2497.81359446638,121.708991715467 -2500.93504193766,121.798398422042 -2503.16483203176,121.440489288971 -2505.30031485059,121.037598129743 -2507.268244977,120.555244244022 -2509.14974399325,120.033728668351 -2512.1920525675,120.098842449066 -2513.87171956694,119.482371076751 -2515.47368101782,118.83473985253 -2518.01409582996,118.662572679694 -2520.45159298092,118.442129778392 -2523.55197676034,118.555078071623 -2525.77026870354,118.225861843835 -2527.89525553347,117.854968955703 -2530.06480504035,117.510289744363 -2532.14266347778,117.124198872167 -2533.87978737288,116.571703985685 -2535.79002510392,116.112625304485 -2537.61654105617,115.618296373871 -2540.07957015613,115.447383995158 -2542.4427399517,115.228895496824 -2545.07700180797,115.150112283999 -2547.23851055421,114.836958156077 -2549.30924926911,114.481972874201 -2551.69768582075,114.289924491497 -2553.9887816725,114.049397039179 -2556.15676386869,113.751127937503 -2558.26266633604,113.427240905442 -2560.27977283615,113.06295242009 -2563.08056213951,113.09507870226 -2565.77215012843,113.071752146553 -2568.34585773927,112.990463150808 -2570.82898377029,112.864816867418 -2573.21233229091,112.691101932829 -2575.85470732455,112.648622989122 -2578.39265883645,112.555667648018 -2580.66548479071,112.331137616977 -2583.00870546446,112.1425219724 -2585.25642428484,111.90903868188 -2588.15804331397,112.004512984944 -2590.94772476593,112.043528199075 -2592.81818539333,111.622542230197 -2595.41780325947,111.569228676996 -2597.91446589736,111.465843879928 -2600.24190263499,111.277376231275 -2602.47445924009,111.04391897993 -2605.37017547018,111.145000630537 -2607.39910926893,110.810593796941 -2609.34206286258,110.435292141604 -2611.33579875558,110.089043425222 -2613.24470699705,109.704384911271 -2615.45955053131,109.47718878888 -2617.19500955507,109.011000190767 -2618.85346319463,108.511041148157 -2621.34183552506,108.431767021408 -2623.73111568564,108.303846174921 -2626.58392348163,108.408122373563 -2628.76720749102,108.176962486155 -2630.86044320478,107.902786662145 -2633.7069660416,108.007896291144 -2636.44389673868,108.057150440827 -2638.44040614768,107.735782828579 -2640.98651020067,107.692025337218 -2643.43194090233,107.598361626926 -2645.22299904789,107.177977103055 -2646.93575193033,106.723165060154 -2648.74344864949,106.320246393509 -2650.30168301706,105.795304627515 -2651.78873196847,105.240905663734 -2653.91444410408,105.012682111235 -2655.95242174968,104.743014515615 -2658.09401425859,104.526164681001 -2659.95876249005,104.174930993343 -2661.74364486331,103.786879556497 -2664.02443457509,103.652830844381 -2666.21321886206,103.473425368737 -2667.70816144161,102.94731505403 -2669.73895005703,102.696591567848 -2671.68529376822,102.408033763118 -2674.48747520692,102.550613635269 -2677.18252313487,102.638259618487 -2679.77637557963,102.674026741529 -2682.26641765067,102.658693841716 -2684.65853074664,102.593028230576 -2686.75676032699,102.382046344506 -2688.76866431352,102.130841869461 -2691.26062722164,102.121808190401 -2693.09093427462,101.78162530305 -2694.84293825169,101.404011843844 -2697.38608479136,101.426338554967 -2699.82994379163,101.397821030862 -2702.39160881478,101.428563526257 -2704.63924438602,101.301620193684 -2706.79631103361,101.129297615357 -2708.49302590211,100.727835898928 -2710.11549831019,100.293981988557 -2711.68726206363,99.8382821650389 -2713.16739524326,99.3420506673558 -2714.57995703479,98.8145906203273 -2716.07101484638,98.3320456314219 -2717.4943359131,97.8205821994596 -2719.71161199592,97.7108371459526 -2720.98024852388,97.1289420447118 -2722.18796033484,96.5227465629538 -2724.07183901113,96.2623630780749 -2725.87684748007,95.9657628608704 -2727.82034723966,95.7407609618942 -2729.46835400186,95.3719331246629 -2731.04465522958,94.9730865069384 -2732.48109743758,94.5084145044813 -2733.85228781729,94.0166532433765 -2735.4551042761,93.6463863063684 -2736.6931195241,93.0981667049985 -2737.87205781448,92.5278974295593 -2739.9529368763,92.4148748074108 -2741.95005301807,92.2625119436008 -2744.11018408769,92.1933262454494 -2745.9400376687,91.9592508481425 -2747.69364489193,91.6904060968251 -2750.07175294491,91.7387286433363 -2752.35754412965,91.7394655471083 -2753.76337279997,91.3001991894269 -2755.89598917308,91.2302951928891 -2757.94364256871,91.1184871269839 -2760.18582289941,91.1059802686771 -2762.33984719061,91.0503318848659 -2764.41487772833,90.9552878681391 -2766.40018544468,90.8162504603158 -2768.30497768981,90.638559798254 -2770.22920680013,90.472455673717 -2772.07479521768,90.2692868773155 -2773.54334467439,89.8801294077557 -2775.24760398782,89.6134215151923 -2776.87991442427,89.3122945832277 -2779.10226514891,89.310624016228 -2781.23744557874,89.2650486864763 -2783.85749974454,89.462362331706 -2785.80914358063,89.3231548412169 -2787.68158863483,89.1455635743562 -2790.00738191683,89.1963466135209 -2792.24295686753,89.201517834707 -2793.89879224499,88.9167225400744 -2795.97641210789,88.8455112553288 -2797.97120028044,88.7330608496155 -2800.02238640994,88.6494626704847 -2801.99153928948,88.5259596986907 -2803.79301266915,88.3192421636796 -2805.60797414306,88.1224011700429 -2807.34798866526,87.8883473628781 -2808.64527997186,87.435882088951 -2809.88301010698,86.9572847582246 -2811.62890145324,86.7378094908919 -2812.73623000374,86.2024863049801 -2813.78985362597,85.6438786473632 -2815.86528901743,85.6016579270878 -2817.85853544813,85.5186567369541 -2819.35855953988,85.1894830924094 -2821.20691484273,85.0373793721477 -2822.97987348691,84.8510085189354 -2824.64224696829,84.6109607083826 -2826.23482620711,84.3392713553108 -2827.93039649478,84.1208130505371 -2829.38462907302,83.7842829190004 -2830.77537461169,83.4201047419516 -2832.17514191648,83.0636015177641 -2833.51317396173,82.6809007654269 -2835.43343811638,82.5921754799521 -2836.63465379837,82.1464842254144 -2837.78020559453,81.6760905570005 -2839.79633574578,81.6469771692138 -2841.73285415765,81.5782557545582 -2843.60070439542,81.4767154271954 -2845.38478210029,81.3337639396327 -2847.09615933327,81.1552557265803 -2849.09451096484,81.1229062246115 -2851.01388576676,81.0521286247307 -2853.14692826334,81.0884790715456 -2854.90674656094,80.9374016177806 -2856.59465944909,80.7513488592918 -2858.3886288612,80.6205503319271 -2860.1097434772,80.4531496827872 -2862.04227222844,80.3941664130176 -2863.61577763091,80.157114289509 -2865.12303086544,79.8888483655979 -2866.37979612864,79.4978807052224 -2867.57977096905,79.0806464117614 -2869.5938980539,79.075592834431 -2870.65973361407,78.5964487632341 -2871.67457070946,78.0970474412689 -2873.56893045145,78.0436938397021 -2875.38798726678,77.9524022434874 -2876.17446645087,77.345252431179 -2877.87793929586,77.2039593549456 -2879.51190404668,77.0291184272415 -2880.95803275196,76.7625692482642 -2882.34233690983,76.468746848158 -2883.73364606969,76.1808221263364 -2884.99793991332,75.8317926615229 -2886.20595401513,75.4563238861741 -2887.75564717007,75.2576909190257 -2889.24076008822,75.027807869741 -2890.77031377153,74.8228634241137 -2892.12886629362,74.5346809963731 -2893.42861242322,74.2206933288141 -2895.58090701824,74.3361830867699 -2897.651029542,74.4104783646592 -2899.38633716289,74.3165692255204 -2901.3068721779,74.3146765168827 -2903.15206679811,74.2760420798578 -2904.33989602155,73.9083192695124 -2905.47408446721,73.5181444336818 -2907.09893015639,73.3780189343825 -2908.11474694742,72.9344056957289 -2909.08220925903,72.4712875515104 -2910.76369112001,72.36962192997 -2912.3772886248,72.2355197579425 -2913.9569075224,72.0869076671556 -2915.4398666853,71.8908161898207 -2916.86091108265,71.6651243625711 -2918.4109726903,71.5055754361111 -2919.89719064529,71.3167442423525 -2921.59029233151,71.2323197066705 -2922.9465985888,70.9819930957157 -2924.2449139593,70.7042425744425 -2926.18164606988,70.7482130298081 -2928.04328399625,70.7531922436871 -2929.57980180459,70.596341083841 -2931.30527997416,70.5365155697608 -2932.96195268697,70.4415239206733 -2935.01548743079,70.5471135296256 -2936.99053222988,70.612815936708 -2938.82218591315,70.6060950167346 -2940.64910374459,70.5975462067424 -2942.40422400116,70.551702993398 -2943.36755008984,70.1093139972563 -2944.28460338014,69.6490217976654 -2945.72561091679,69.4556868528517 -2946.53764486038,68.9495385660439 -2947.30811297267,68.429062426115 -2948.43874877747,68.0927828456863 -2949.51859056073,67.7358826924673 -2950.48906283023,67.3270974375147 -2951.47379870392,66.9300275746338 -2952.41229314674,66.5129251885563 -2953.8695316648,66.3598436028985 -2955.26669039128,66.1789808096652 -2956.79242514157,66.0639681545949 -2958.06929196375,65.8257519584175 -2959.29151542438,65.5628286578777 -2960.76654922029,65.4271178358321 -2962.18113926632,65.2646248967132 -2963.54657581516,65.078812564015 -2964.84546827487,64.8608626861192 -2966.08924318308,64.6178687572657 -2967.11810773078,64.2701010253441 -2968.09994794578,63.9025781610506 -2969.98250900629,63.9899766259745 -2970.84665346056,63.5666900702386 -2971.66878108914,63.1262094006889 -2972.68909098534,62.7903774264238 -2973.66294133119,62.43344192974 -2974.91424617078,62.21936992926 -2975.78987599228,61.8190753265878 -2976.62348045656,61.4008430452256 -2978.19166686841,61.355929452983 -2979.69750176528,61.2806280463446 -2980.9218205457,61.0660469801945 -2982.31503601027,60.9376095830624 -2983.65115557992,60.7820523862826 -2984.01654648235,60.1428903493912 -2984.35532842571,59.4978376899278 -2985.47805464797,59.2496283236917 -2985.74236622671,58.5757371699337 -2985.98336481079,57.8974607377404 -2987.59429868464,57.9105857892954 -2989.142320178,57.8924658721343 -2991.32482074132,58.1930361162737 -2992.73199627142,58.1021166879954 -2994.08224947138,57.9847787665158 -2995.42712970684,57.8654573515872 -2996.71698443875,57.7210993009262 -2997.45400666374,57.3020139876167 -2998.65356069573,57.1180105452135 -2999.80254453603,56.9107227691015 -3001.15285298098,56.8070248241636 -3002.44822330022,56.6768696906591 -3004.06755228586,56.709810275069 -3005.24676942204,56.523778746009 -3006.37617480327,56.3133485939251 -3006.65031607252,55.679212674478 -3006.90152285441,55.03913393889 -3008.30372447463,54.9806497473983 -3008.47667779816,54.3086605941792 -3008.62993682542,53.6341503897126 -3010.17487450323,53.662748925891 -3011.65978484156,53.6592367981468 -3012.99176349836,53.5809491231529 -3014.36465199477,53.5240903722866 -3015.68261705612,53.4410912686529 -3017.23350387931,53.4737176453887 -3018.72420749568,53.4775829516529 -3019.80155066397,53.2732454909009 -3021.18770913732,53.2258419725056 -3022.51860555072,53.1534833479493 -3023.35477336903,52.8336044584904 -3024.15200838452,52.4977872449172 -3025.20946449446,52.2951706107756 -3025.92363078065,51.9229630845376 -3026.60264239767,51.5370820232247 -3027.33626084819,51.1821186488467 -3028.03429327193,50.812531516767 -3028.59842035632,50.3805339003648 -3029.23156051279,49.9879283909354 -3029.83233106458,49.5837090669305 -3031.47061540881,49.7019947330268 -3033.04693570829,49.7882132587205 -3034.14499924484,49.6349141481249 -3035.61516815991,49.6704873636396 -3037.02837543677,49.6756944982237 -3038.3389364122,49.6295536100358 -3039.59722376201,49.5585985385504 -3041.1475340866,49.6319035927252 -3042.2957417021,49.5051473333563 -3043.39649246533,49.3551852306391 -3044.16433760701,49.0421849549295 -3044.89606105065,48.7137123203357 -3045.89540539338,48.5221035598557 -3046.5492600261,48.1590732543085 -3047.17050115242,47.7839322375599 -3048.20818670591,47.6209328082351 -3049.20205252681,47.4370935226655 -3050.06939611623,47.1911387035356 -3050.98202522615,46.97245863136 -3051.85466810849,46.7350590795204 -3053.18041242591,46.7277281931745 -3054.45403354538,46.6937051340838 -3055.26825974926,46.4303607714149 -3056.4543023881,46.3560409729779 -3057.59241227504,46.2578468959329 -3058.79094037596,46.191188326883 -3059.94119338767,46.1014305405909 -3060.92758653733,45.9297785407541 -3061.98903862465,45.7978904155306 -3063.00633692413,45.6452487405964 -3063.91964562592,45.4412091289247 -3064.79322278156,45.2203273984248 -3065.70950671725,45.0240439092133 -3066.50488739798,44.7671980283893 -3067.26414576608,44.4960362355498 -3069.43192889381,44.9304861807026 -3071.52306172173,45.3245926957602 -3072.64735706393,45.2315091746425 -3074.61819760753,45.5622866247446 -3076.51811780425,45.8537106680713 -3076.615530346,45.2411022719966 -3076.69735158835,44.6275423950616 -3077.53059182705,44.3951489477617 -3077.56027791038,43.7625054719485 -3077.57664325324,43.1307719433091 -3077.85571535997,42.6361561778177 -3078.1143406332,42.1367282767858 -3079.0034515909,41.9575716450465 -3079.20403467219,41.4366115273567 -3079.38674224058,40.9110503776261 -3080.57294207632,40.891080936083 -3081.71224738216,40.8491163525692 -3082.86906246984,40.8164815375393 -3083.91690359069,40.7304366418598 -3084.92200552301,40.6251400138186 -3085.54556313079,40.3296229415368 -3086.138992497,40.0213984650214 -3087.42246656353,40.0608238937617 -3087.93713750647,39.7158893972749 -3088.42500004989,39.3622296039178 -3088.82874831719,38.9684828421398 -3089.20909948744,38.5676624245811 -3089.0663017328,37.907756051532 -3089.41695573699,37.5027929135483 -3089.74607893429,37.0910588747593 -3090.11276536497,36.7007381833568 -3090.45757372494,36.3045581183097 -3091.66452392224,36.3433724524389 -3091.9416208838,35.9167486591793 -3092.1996549774,35.4852654553901 -3093.31685985646,35.4891745857313 -3094.39033433827,35.4700916529278 -3095.46473491399,35.4505060444396 -3096.45324833886,35.3888720476281 -3097.40181788441,35.3086018086629 -3097.77489007801,34.9420327148066 -3098.12629022163,34.568450832518 -3098.98447022753,34.450891197715 -3099.27900515188,34.0533696260997 -3099.55435268967,33.6496818264192 -3100.37428056073,33.5227248592685 -3101.15961954538,33.3802864921441 -3101.8272348124,33.1800437154664 -3102.5490186837,33.0091390217467 -3103.23921739621,32.8236167485267 -3104.12439421405,32.7383714279633 -3104.9732252622,32.6351350312571 -3105.56159662785,32.4036235721481 -3106.34764263544,32.2719870876702 -3107.10033834112,32.1258057896743 -3107.92520108796,32.017502870259 -3108.71563990479,31.8936817098126 -3109.11812194699,31.5776893193199 -3109.85333506202,31.4297021746393 -3110.55687683776,31.2670157455457 -3111.54559929759,31.249662919606 -3112.49522058006,31.2126441065523 -3113.18740506114,31.047853509604 -3114.06877334081,30.9779961256124 -3114.91424087481,30.8907466814871 -3115.75635437021,30.8037010103255 -3116.56377601018,30.700342671425 -3117.57169910039,30.6979515217859 -3118.30590915689,30.5598736444862 -3119.00867761846,30.4059236775093 -3120.01440711066,30.4065076073024 -3120.98071325025,30.3866019525395 -3121.08495891143,29.9371763647591 -3122.00027022415,29.8961023751392 -3122.87890298356,29.8379602197066 -3123.51711355539,29.661177870866 -3124.12690292699,29.4709655738345 -3124.7235689061,29.275485575415 -3125.27864187287,29.0627994389992 -3125.80786353822,28.8393319472114 -3126.83106835811,28.8648114985031 -3127.81464300851,28.8697023221584 -3128.10457634953,28.526891109013 -3129.03172344187,28.506122595573 -3129.92211808692,28.4677977348254 -3130.30099134604,28.1739831033263 -3130.65936313117,27.8729730423942 -3131.28608856128,27.7095316735164 -3131.59690995654,27.3889272870566 -3131.88938339938,27.0647949933395 -3132.51869964008,26.9114409962812 -3133.12039362112,26.746324603103 -3133.86998076438,26.6554891095912 -3134.4137727995,26.4636408880194 -3134.93255627487,26.2605416565177 -3135.77841721645,26.2237530542114 -3136.59040509541,26.1701712578022 -3137.25562693743,26.0444330458365 -3138.00624776318,25.9621275917599 -3138.72585524086,25.865863966523 -3138.72308786953,25.4077202172492 -3138.71162540723,24.9511911043108 -3139.36251214425,24.830014871111 -3139.31487683575,24.3603737096634 -3139.26008477253,23.8925212658137 -3139.89655459525,23.7744811955489 -3140.50580025235,23.6434557820142 -3141.69800109556,23.8063781003897 -3142.23722510346,23.6400724705958 -3142.75211048498,23.4642825522436 -3142.73287715173,23.0220192267068 -3142.70589951164,22.5814720854505 -3143.31241488019,22.4627841339051 -3143.25196746133,22.0111571129826 -3143.18521180573,21.561902324989 -3144.1864159408,21.6504254700787 -3145.15006398468,21.7188769006225 -3145.8923652871,21.6767701357888 -3146.78962942686,21.7111668990749 -3147.65237287254,21.7283671503166 -3148.24277680186,21.6099947698465 -3148.80775641997,21.4803494168959 -3149.21542249603,21.2735483371822 -3149.73579966604,21.1248676357698 -3150.2329158698,20.9663362665579 -3150.71369042896,20.8013198499661 -3151.17244293323,20.6257746362874 -3151.19384891827,20.2328259312201 -3151.62285038006,20.0483941648373 -3152.03148672448,19.8546925469171 -3151.97890882939,19.4316488470411 -3151.92026338557,19.0112032798313 -3152.20674191967,18.7677005290928 -3152.12640485938,18.3416042586465 -3152.04103002744,17.9191360694253 -3152.40561647683,17.7247926680848 -3152.75217305634,17.5242777488994 -3153.2970386921,17.4238467534392 -3153.60285976056,17.2056260266906 -3153.8924963231,16.9801292499258 -3153.9532050667,16.6433184907202 -3154.00506133657,16.3060961898612 -3153.67875512745,15.7824811279977 -3153.72483087761,15.4501460537029 -3153.76271391643,15.1174481653802 -3154.6753762016,15.226225381262 -3155.55434331265,15.3167832383053 -3155.21976319371,14.7996179511388 -3156.06918733043,14.8795041624357 -3156.886840692,14.9428742442801 -3157.29800140859,14.8018720400688 -3157.69033107585,14.6537940793506 -3158.01119872399,14.4722306030136 -3158.36922965687,14.3097117140523 -3158.71009929466,14.1399322185729 -3158.75719741568,13.8250287137432 -3158.79639769985,13.5099276372384 -3158.95879914057,13.2597946231346 -3158.97923321103,12.9404249917531 -3158.99272911975,12.6209318772412 -3159.07461697212,12.3395563105949 -3159.14788715127,12.0565669152814 -3159.35649268005,11.8427947781387 -3159.40916486409,11.554308280736 -3159.4542282767,11.2642835509693 -3159.46091261789,10.960288570912 -3159.46149335938,10.6544949790118 -3159.24888550498,10.245577250221 -3159.24404606175,9.94560597352354 -3159.23363218416,9.64556170213407 -3159.41114060098,9.44198721445264 -3159.57777707996,9.23434992105488 -3160.09836512431,9.20714556596675 -3160.23354291394,8.98667823092854 -3160.35918393664,8.76559071348452 -3160.59419754619,8.59988764014727 -3160.81681217346,8.43009475193201 -3161.14146021808,8.31338391680135 -3161.33711132086,8.13224859153338 -3161.52161029902,7.94724332198578 -3162.48312936396,8.1527772325979 -3163.41089684181,8.33877081267066 -3163.10465562676,7.9073704612276 -3164.00333742151,8.08311449492657 -3164.87015903716,8.24123911947762 -3165.11824784165,8.08782407632386 -3165.35366111085,7.93005809769972 -3165.06677046822,7.51206570755634 -3165.29313850255,7.3554907885344 -3165.50762195171,7.19468259800607 -3165.08802417591,6.71911411303896 -3164.67574036583,6.2505578713822 -3163.86302879819,5.58823314655995 -3163.47704617502,5.14519659215911 -3163.09768459724,4.70947152740094 -3163.42643784927,4.63226360427115 -3163.74081710034,4.54838456598338 -3164.05454245194,4.46430869764967 -3164.34106638341,4.369158802779 -3164.61452735284,4.26859062824501 -3164.73837889127,4.09293575431895 -3164.85399887153,3.9152460017283 -3165.19709797926,3.85371966169839 -3165.29013489164,3.6674195968786 -3165.37594392902,3.4794390804158 -3165.26424228837,3.19403955073531 -3165.15143627941,2.91020366188911 -3165.08864239691,2.65625599908135 -3164.97238770368,2.37649456720122 -3164.85531550755,2.10023192217155 -3164.56554826466,1.73970920255295 -3164.28021503923,1.38625259946576 -3164.36762839647,1.22314647378918 -3164.08012942641,0.873633375148846 -3163.7971870937,0.530554883709359 -3164.33215352924,0.59937112490103 -3164.84746633268,0.658088288807566 -3165.06385317401,0.566152860793108 -3165.54983777709,0.609929371164183 -3166.01760816333,0.644812689452527 -3165.79330947863,0.332433651050102 -3165.57180291386,0.0242326105871949 -3165.05021987026,-0.430690739717163 -3164.84318574297,-0.72422575274478 -3164.63862889675,-1.0132892297766 -3164.89549357142,-1.06890589143142 -3165.14121788393,-1.12902754850388 -3165.11635310722,-1.32417305340018 -3165.34851237178,-1.38824353711591 -3165.57033752437,-1.4567072755393 -3165.87853894575,-1.48268128503558 -3166.17415670253,-1.51341444675278 -3166.31432481413,-1.62227446407532 diff --git a/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_ABK/ABK_configABK_Gemini_Roccaraso_September_2023.csv b/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_ABK/ABK_configABK_Gemini_Roccaraso_September_2023.csv deleted file mode 100644 index 2d967ad4e49ac06509527e974e51d4e4d9fb1a77..0000000000000000000000000000000000000000 --- a/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_ABK/ABK_configABK_Gemini_Roccaraso_September_2023.csv +++ /dev/null @@ -1,2 +0,0 @@ -ABK_FREQUENCY,REFERENCE_DZ,STARTING_FILTER_VALUE,CHANGE_FILTER_MINIMUM_ALTITUDE,CHANGE_FILTER_MAXIMUM_ALTITUDE,ABK_CRITICAL_ALTITUDE,ABK_REFERENCE_LOWEST_MASS,DELTA_MASS,ESTIMATED_MASS,N_FORWARD,ABK_DELAY_FROM_SHUTDOWN -10,10,0.75,400,1000,970,26,0.1,26.6127654803445,0,0.5 diff --git a/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_ABK/ABK_outputABK_Gemini_Roccaraso_September_2023.csv b/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_ABK/ABK_outputABK_Gemini_Roccaraso_September_2023.csv deleted file mode 100644 index 70a327b1e8d9b08432369414f89f470e177c5181..0000000000000000000000000000000000000000 --- a/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_ABK/ABK_outputABK_Gemini_Roccaraso_September_2023.csv +++ /dev/null @@ -1,799 +0,0 @@ -ABK -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0.143936900247599 -0.261316468788693 -0.369124020088354 -0.467767848855985 -0.400614797889469 -0.338732485163282 -0.285776394294311 -0.239947583403007 -0.201751708044714 -0.170111976986925 -0.143673691308664 -0.12173523150355 -0.103501145823177 -0.0881755497223627 -0.0752619240523143 -0.0643471236053354 -0.0551523689873061 -0.0473955326555801 -0.0407860261478003 -0.0351552351296127 -0.0303214135256291 -0.0261837590426142 -0.0226553838175047 -0.0196358524246332 -0.01706553214272 -0.0148509449554794 -0.0129409992470146 -0.0112929259454447 -0.00986458874786797 -0.00862499517391007 -0.00755174520415121 -0.00661648488958464 -0.00579610122756527 -0.00508119348314224 -0.0044533801502411 -0.00391354608965466 -0.00344815361569836 -0.00304711289839569 -0.00269333103241539 -0.00238243448377047 -0.00210857926358739 -0.00186668896403859 -0.00165478042314901 -0.00146984869968034 -0.00130836289660631 -0.00116619892188303 -0.00104243100219448 -0.000935134244875468 -0.00083877250290333 -0.00075110689803653 -0.000673073630535971 -0.000603867881240658 -0.000542333821941486 -0.000487937046753873 -0.000439574365126022 -0.00039705333061514 -0.000359463240837006 -0.000326265093718725 -0.000297093641998676 -0.000271247940715219 -0.000247557561632297 -0.000225652670520882 -0.000205122701694285 -0.000186910514588513 -0.000170556155772047 -0.000155598833662346 -0.000142064120506843 -0.000129811833434877 -0.00011891347418991 -0.000109252988605828 -0.000100558321323492 -9.26796797390267e-05 -8.54386388328177e-05 -7.88082350904175e-05 -7.26889721799242e-05 -6.70697077631962e-05 -6.18904970114683e-05 -5.70851211480867e-05 -5.26634703128841e-05 -4.86042825773923e-05 -4.49687318044401e-05 -4.17260210138527e-05 -3.88744211637007e-05 -3.61863952297243e-05 -3.35931825400145e-05 -3.11970660314643e-05 -2.89456520652285e-05 -2.67883197225317e-05 -2.48207408058324e-05 -2.30643639095823e-05 -2.14963578047316e-05 -2.00823752947825e-05 -1.88194480632987e-05 -1.76593018684082e-05 -1.65684002909519e-05 -1.556308522711e-05 -1.46429185620492e-05 -1.38113193065689e-05 -1.30538041055872e-05 -1.23410581112854e-05 -1.16760687299847e-05 -1.10622333716031e-05 -1.04879474325693e-05 -9.94475890742632e-06 -9.42407613854184e-06 -8.93559040186204e-06 -8.47696116729529e-06 -8.0485211544412e-06 -7.64241212417218e-06 -7.25715121682867e-06 -6.89865701275408e-06 -6.55594344070821e-06 -6.22460734153213e-06 -5.91518816125161e-06 -5.62420705570762e-06 -5.3529861321579e-06 -5.10146299438026e-06 -4.86600784523503e-06 -4.64378566963009e-06 -4.43106066522579e-06 -4.23660211734693e-06 -4.05969233100354e-06 -3.89961581234186e-06 -3.74955284364551e-06 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 diff --git a/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_ABK/ABK_references_Gemini_Roccaraso_September_2023.csv b/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_ABK/ABK_references_Gemini_Roccaraso_September_2023.csv deleted file mode 100644 index 0597c98901447a432abcb00fa74e7587811b806a..0000000000000000000000000000000000000000 --- a/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_ABK/ABK_references_Gemini_Roccaraso_September_2023.csv +++ /dev/null @@ -1,107 +0,0 @@ -Heights,Vz_closed_m26,Vz_closed_m26_1,Vz_closed_m26_2,Vz_closed_m26_3,Vz_closed_m26_4,Vz_closed_m26_5,Vz_closed_m26_6,Vz_closed_m26_7,Vz_closed_m26_8,Vz_closed_m26_9,Vz_closed_m27,Vz_open_m26,Vz_open_m26_1,Vz_open_m26_2,Vz_open_m26_3,Vz_open_m26_4,Vz_open_m26_5,Vz_open_m26_6,Vz_open_m26_7,Vz_open_m26_8,Vz_open_m26_9,Vz_open_m27 -0,152.281183589541,152.245755350089,152.210609519524,152.175742743635,152.141151720961,152.106833201762,152.072783987011,152.039000927416,152.005480922458,151.972220919451,151.939217912631,169.360315331402,169.245401138596,169.131483352568,169.018549440047,168.906587066945,168.795584094774,168.685570230743,168.576758674548,168.46886387969,168.361874651667,168.255779968402 -10,151.46876639657,151.433869072696,151.399251019435,151.364908902743,151.330839441355,151.297039405745,151.263505617113,151.23023494639,151.197224313278,151.1644706853,151.131971076877,168.246480367201,168.13373829021,168.021987670571,167.911215676248,167.801409690573,167.692557307917,167.584646329466,167.477664759087,167.371600799283,167.266442847243,167.162192733818 -20,150.654145389855,150.619758851732,150.585647363659,150.551807643526,150.518236461159,150.48493063729,150.451887042568,150.419102596577,150.38657426689,150.354299068137,150.322274061098,167.134073503613,167.0234127897,166.913723128917,166.804991979826,166.697207011095,166.590356097278,166.484427314696,166.379408937412,166.275289433288,166.172057460137,166.069701861961 -30,149.836780149099,149.802933721734,149.769357969649,149.736049663359,149.703005624475,149.670222724698,149.637697884841,149.605428073866,149.573410307954,149.541641649582,149.510091542429,166.022426559672,165.913819215268,165.806162864455,165.69944525064,165.593654322181,165.488778228285,165.384805314988,165.281724121234,165.179523375033,165.078191989716,164.977719060261 -40,149.016705742141,148.983362845367,148.950286467789,148.917473431018,148.884920606928,148.852624916669,148.820583329703,148.78879286286,148.757250579419,148.725953588209,148.694899042729,164.911499807547,164.804894908062,164.699223769936,164.594489580683,164.490666223961,164.387738801583,164.28569592402,164.184526389915,164.084219182355,163.984763465206,163.886148579548 -50,148.194090806251,148.161248211031,148.128668008159,148.096347069949,148.064282318157,148.032470723006,148.000909302239,147.969595120189,147.938525286881,147.907696957141,147.877107329736,163.801180771595,163.696573631899,163.592880806674,163.4900905106,163.388191156171,163.287171349686,163.187019887333,163.087732411267,162.989293988637,162.891689478684,162.794908463837 -60,147.368545299231,147.336231679034,147.304176169823,147.272375695397,147.240827228178,147.209527788255,147.178474442449,147.147664303406,147.117094528702,147.086762319979,147.056664922089,162.691340150731,162.588704265396,162.48696357211,162.386106556436,162.286121896822,162.186998460698,162.088725300665,161.991291650769,161.894686922867,161.798900703067,161.703922748259 -70,146.540184456041,146.508363917621,146.476797427427,146.445481959129,146.414414534208,146.38359222102,146.353012133874,146.322671432139,146.292567319369,146.26269704245,146.23305789076,161.581892032395,161.481201390453,161.381387135012,161.282438017206,161.184342976228,161.08709113554,160.990671799155,160.895074448018,160.800288736459,160.706304488736,160.613111695649 -80,145.709156237422,145.677825579755,145.646744936456,145.615911330684,145.585321832603,145.554973558463,145.524863669696,145.49498937204,145.465347914672,145.435936589378,145.406752729722,160.472755991675,160.373980152089,160.276067113742,160.179000977387,160.082770937899,159.987366369802,159.892776823657,159.798992022537,159.706001858579,159.613796389609,159.522365835857 -90,144.874895029495,144.844082149046,144.813515095859,144.783190943419,144.753106811422,144.723259864863,144.693647313153,144.664266409254,144.635114448831,144.606188769432,144.577486749675,159.363858989209,159.266973787375,159.170930177318,159.075717361825,158.981324724607,158.88774182662,158.794958276955,158.702962703546,158.611745038509,158.521295568787,158.431604739666 -100,144.037811823631,144.007481641361,143.977393316162,143.947543970178,143.917930770972,143.888550930633,143.859401704909,143.830480392353,143.801784333495,143.773310910031,143.745057544031,158.255076329991,158.160059173274,158.065865683118,157.972485314413,157.879907698388,157.788122639031,157.697120109588,157.606890249155,157.517423359333,157.428709900975,157.340740491 -110,143.197745207749,143.167925542373,143.138343607042,143.108996573506,143.079881658144,143.050996121095,143.022336542448,142.993871814025,142.965628675919,142.937604553633,142.909796912352,157.146323850155,157.053150545625,156.960783273119,156.869211734768,156.778425804556,156.688415524839,156.599171102938,156.510682907825,156.422941466866,156.335937462659,156.249661729934 -120,142.354379620129,142.325035490906,142.295925184969,142.267045921899,142.238394965134,142.209969621106,142.1817672384,142.153785206939,142.126020957175,142.098471959315,142.071135722547,156.037509424379,155.946160005792,155.85560006476,155.765814158809,155.676796991135,155.588538837923,155.501030136122,155.414261480221,155.328223619085,155.242907452877,155.158304030038 -130,141.508113667175,141.479241919132,141.450600115973,141.422185524735,141.393995455544,141.366027260764,141.338278334178,141.310746110176,141.283428062975,141.256321705844,141.229424590358,154.928523292648,154.838968124123,154.75018605909,154.662167229108,154.574901930628,154.488380621634,154.402593918367,154.317532592117,154.233187566099,154.149540072807,154.066587958333 -140,140.65835031699,140.629977782493,140.601831161473,140.573907769392,140.546204964029,140.51872014465,140.491450751199,140.464394263504,140.437548200509,140.410910119514,140.384477615441,153.819291188769,153.731507331512,153.644479765301,153.558198856204,153.472655130933,153.387839273574,153.303742122402,153.220354666761,153.13766804403,153.055673536648,152.974362569214 -150,139.805461647332,139.777554371874,139.74986919445,139.722403477161,139.695154623667,139.668120078376,139.641297325649,139.614683889021,139.588277330443,139.562075249543,139.536075282899,152.709730100639,152.623695012999,152.538399670524,152.453834669369,152.36999076217,152.286858854869,152.204430003618,152.122695411745,152.041646426804,151.961274537679,151.881571371771 -160,138.949190516325,138.921775088473,138.894577788639,138.867596026598,138.840827252932,138.814268958225,138.787918672288,138.761773963392,138.735832437525,138.710091737666,138.68454954307,151.599668963086,151.515370665724,151.431797030004,151.34893883593,151.266787017324,151.185332658691,151.104566992153,151.02447466393,150.945042898062,150.866273440767,150.788158118517 -170,138.089427939597,138.062470671407,138.035727778478,138.00919671641,137.982874980864,137.95676010678,137.93084966761,137.90514127457,137.879632575911,137.854321256199,137.829205035625,150.489079565894,150.406483238506,150.32459554215,150.243407479148,150.162910201622,150.083095008443,150.003953342255,149.925476786568,149.847657062916,149.770486028088,149.693955671423 -180,137.226341439041,137.199868605701,137.173606239555,137.147551843121,137.121702958234,137.096057165278,137.070606615013,137.045331590065,137.020252796546,136.995367960286,136.970674842081,149.377885385811,149.296969622668,149.216746710064,149.137207868512,149.058344464392,148.980148006983,148.902610145574,148.825722666637,148.749477491067,148.673866671489,148.598882389628 -190,136.359442928428,136.333421179004,136.307606206417,136.281995558196,136.256586820462,136.23137761717,136.206365609372,136.181548494497,136.156924005649,136.132489910916,136.108244012702,148.265870235037,148.186630337033,148.108068726142,148.030176802289,147.952946108577,147.876368328361,147.800435282399,147.725138906152,147.650448858313,147.576379051883,147.502921857494 -200,135.489217534117,135.463672764336,135.438330589448,135.413160653025,135.388189052897,135.363413456239,135.338831566631,135.314441123351,135.290239900686,135.266225707255,135.242396385354,147.153034470015,147.075430248138,146.998489024823,146.92220241072,146.846562155861,146.771560146817,146.697188403928,146.623439078599,146.550304450661,146.477776925786,146.405849032977 -210,134.614909634047,134.589808896816,134.56490746254,134.540202969109,134.515693091553,134.491375541323,134.467248065573,134.443308446477,134.419554500541,134.395984077953,134.372595061928,146.039310268352,145.963327820648,145.887986867122,145.813285675937,145.739216200288,145.665770526275,145.592940870211,145.520719575995,145.449099112549,145.378072071307,145.307631163775 -220,133.737204982698,133.712554201462,133.688090125555,133.66381943345,133.639739843317,133.61584910905,133.592145019571,133.56862539815,133.545288101743,133.52213102034,133.499152076336,144.924403754144,144.850030479483,144.776291119778,144.703177666616,144.630682244579,144.558797108522,144.48751464093,144.416827349337,144.346727863797,144.277208934424,144.208258302506 -230,132.855202173581,132.831007928586,132.807005637333,132.783193026494,132.759567858465,132.736127930665,132.712871074855,132.689795156474,132.666898073987,132.644177758248,132.621632171883,143.808418560157,143.735617545146,143.663435860165,143.591865696552,143.520899375052,143.450529343185,143.380748172669,143.311548556918,143.242923308588,143.174865357185,143.107367746732 -240,131.969660088597,131.945927801359,131.922356150717,131.898970455045,131.875768748267,131.852748869473,131.829908691435,131.807246119943,131.784759093177,131.762445581076,131.740303584736,142.691154752502,142.619932618686,142.549316088821,142.479297525719,142.409869418917,142.341005103139,142.272706918421,142.204976870697,142.137807951998,142.071193268059,142.005126036057 -250,131.079664105217,131.056361823404,131.033244270852,131.010309261439,130.987554643371,130.964978298512,130.942578141729,130.920352120252,130.898298213049,130.876414430218,130.854698812387,141.572461306612,141.502769476635,141.433669120944,141.365152795154,141.297213178154,141.229843069594,141.163035387437,141.096783165562,141.031079551436,140.965917803829,140.90129129059 -260,130.185907545998,130.163059662486,130.140392852358,130.117904973303,130.095593916644,130.073443228631,130.05145306502,130.029633763249,130.007983341272,129.986499847555,129.965181360491,140.452406425859,140.384226138456,140.316623407473,140.249590977913,140.183121714668,140.11720860009,140.051844731605,139.987023319395,139.922737684132,139.858981254763,139.79574756635 -270,129.287606645828,129.265181792979,129.242934569645,129.22086287533,129.198964642501,129.177237835939,129.155680452117,129.134290518578,129.113066093345,129.092005264325,129.071106148747,139.330559078558,139.26389865617,139.197802610314,139.132263851042,139.067275405684,139.00283041646,138.938922138147,138.875543935805,138.812689282553,138.750351757402,138.688525043137 -280,128.385238574269,128.363260532298,128.341456527848,128.319824503446,128.298362433894,128.277068325644,128.255940216178,128.234976173414,128.21417429511,128.193532708298,128.173049568719,138.207142240544,138.141953075543,138.077314802393,138.013220513944,137.949663417069,137.886636830349,137.824134181808,137.762149006706,137.700674945383,137.639705741156,137.579235238258 -290,127.478306751639,127.45674479197,127.435353486752,127.414130819542,127.393074805514,127.372183490842,127.351454952101,127.330887295676,127.310478657188,127.29022720093,127.270131119324,137.081788005055,137.018082242506,136.954914511937,136.892278067816,136.830166276048,136.76857261171,136.707490656827,136.646914098217,136.586836725379,136.527252428432,136.468125989427 -300,126.566908908799,126.5457861476,126.524830512989,126.504040030746,126.483412757601,126.462946780625,126.44264021665,126.422491211683,126.402497940352,126.382658605351,126.362971436904,135.954543762304,135.892269994398,135.830521193842,135.769290791518,135.708572326618,135.648359444435,135.588645894221,135.529425527086,135.470692293954,135.412440243561,135.354663520507 -310,125.651005050447,125.630291449902,125.609741653331,125.589353726765,125.569125766536,125.549055898689,125.529142278402,125.509383089424,125.489776543526,125.47032087996,125.451014364936,134.825185415819,134.764358670881,134.704044358959,134.644236068848,134.584927495098,134.526112435869,134.467784790821,134.409938559071,134.352557901333,134.295622180286,134.239150218386 -320,124.730136635695,124.709854598997,124.689732902745,124.669769654394,124.649962991044,124.630311078864,124.610812112527,124.591464314658,124.572265935296,124.553215251368,124.534310566176,133.693635972874,133.634202948614,133.575269699904,133.516829985779,133.45887766802,133.401406709066,133.34441116998,133.287885208454,133.231823076879,133.176219120437,133.121067775264 -330,123.804728493886,123.784874274836,123.765176963417,123.745634708138,123.726245686504,123.707008104449,123.687920195787,123.668980000697,123.650161857034,123.631488409761,123.612957997475,132.559748527893,132.501726313433,132.444191668923,132.387138507394,132.330560842128,132.274452784611,132.218808542547,132.163622417914,132.108880822872,132.054558471532,132.000677517929 -340,122.874099856926,122.854643995785,122.835341813559,122.816191497802,122.797191264436,122.778339357199,122.759634047109,122.741073631931,122.722656435667,122.704380808049,122.686245124051,131.423402685643,131.36673687076,131.310546362978,131.254825239606,131.199567675304,131.144767940103,131.090420397478,131.036519502466,130.983059799829,130.930035922262,130.877442588637 -350,121.938494092651,121.919458367271,121.900572952773,121.88183607696,121.863245995363,121.844800990708,121.826499372384,121.808339475929,121.79031966253,121.772438318524,121.754693854927,130.284432664314,130.229141677191,130.174314121649,130.119944224944,130.066026309233,130.012554789651,129.959524172423,129.906929053034,129.854764114432,129.803024125281,129.751688190099 -360,120.997934171153,120.97928994655,120.960792863729,120.942441188767,120.924233214861,120.906167261799,120.888241675445,120.870454827233,120.852805113679,120.8352909559,120.817910799138,129.142784634321,129.088813641437,129.035294199772,128.982220695094,128.929587605292,128.877389498505,128.825621031295,128.774276946874,128.723352073366,128.672841322107,128.622739685996 -370,120.051624825784,120.033393039748,120.015305092351,119.997359289112,119.979553962042,119.961887469133,119.944358193853,119.926964544654,119.909704954489,119.892577880348,119.875581802795,127.998149031994,127.945517165827,127.893325305339,127.841567982095,127.790239817395,127.739335520449,127.6888498866,127.638777795595,127.589114209884,127.539854172974,127.490992807816 -380,119.100084871254,119.0822616981,119.064579091961,119.047035397413,119.029628984907,119.012358250267,118.995221614201,118.978217521817,118.961344442155,118.944600867729,118.92798531408,126.850677124078,126.799329725144,126.748410822322,126.697915100134,126.647837330158,126.59817236926,126.548915157874,126.500060718327,126.451604153197,126.40354064371,126.355865448186 -390,118.14315807336,118.125739662359,118.108435543303,118.091266519636,118.074231775202,118.057329741742,118.040558875306,118.023917655791,118.007404586476,117.991018193578,117.974757025813,125.699762077224,125.649718422777,125.600092047644,125.550877777939,125.502070524505,125.453665281202,125.405657123228,125.358041205484,125.310812760981,125.263967099277,125.21749960496 -400,117.180100240481,117.163058733959,117.146151511612,117.12937699335,117.112733623761,117.096219871632,117.079834229482,117.0635752131,117.047441361105,117.031431234504,117.015543416263,124.545732350525,124.496976446168,124.448626738249,124.400678193037,124.353125859225,124.305964866261,124.259156659437,124.212725786401,124.166672084618,124.120990996584,124.075678037563 -410,116.211315398257,116.194670899962,116.178157511366,116.161773690232,116.145517918404,116.12938870134,116.113384567652,116.097504068662,116.081745777964,116.066108291001,116.050590224644,123.388086429243,123.34056126544,123.293431340795,123.246691766367,123.200337733118,123.154364510289,123.10876744383,123.063541954857,123.018683538149,122.974187760683,122.9300502602 -420,115.236655226956,115.22040384241,115.204280425278,115.188283470785,115.172411497645,115.156663047603,115.141036684993,115.125530996297,115.110144589725,115.094876094798,115.079724161938,122.22678244767,122.180509976902,122.134621991213,122.089113737498,122.043980540315,121.999217800315,121.954820992701,121.910785665741,121.867107439301,121.823782003417,121.780805116912 -430,114.255726725382,114.239841598892,114.224081488583,114.208444925174,114.192930462305,114.177536676095,114.162262164702,114.147105547905,114.132065466685,114.117140582819,114.102329578488,121.061838910406,121.016802951695,120.972106862744,120.927774770742,120.883807398833,120.840200282556,120.796949029684,120.754049318777,120.711496897768,120.669287582584,120.627417255802 -440,113.268259505295,113.252759712339,113.237381858813,113.222124512079,113.206986261844,113.191965719725,113.177061518822,113.162272313311,113.147596778033,113.133033608106,113.11858151853,119.892601854044,119.848744663861,119.80525091659,119.762116130352,119.719335896335,119.67690587732,119.63482180624,119.593079484775,119.55167478198,119.510603632944,119.469862037486 -450,112.274378373159,112.259259980483,112.244260483028,112.229378484405,112.214612609992,112.199961506518,112.185423841649,112.170998303582,112.156683600653,112.142478460955,112.128381631957,118.719294972083,118.676639666519,118.634337515645,118.592384167447,118.550775340835,118.509506824211,118.468574474068,118.42797421363,118.387702031519,118.347753980452,118.308126175976 -460,111.273884006837,111.259143061607,111.244518000119,111.230007461829,111.215610107394,111.201324618268,111.187149696296,111.173084063324,111.159126460812,111.145275649464,111.131530408858,117.541762424381,117.500292741596,117.459166068322,117.418355128934,117.377862804209,117.337701080435,117.297865939559,117.258353428119,117.219159655951,117.180280794938,117.141713077783 -470,110.266569375787,110.252201906462,110.237947342303,110.223790888272,110.209736972506,110.195792194847,110.18195528947,110.168225010042,110.154600129346,110.141079438919,110.127661748693,116.359420720709,116.319079500839,116.279071370591,116.239392235664,116.20003806833,116.161004906083,116.122288850337,116.083886065141,116.045792775939,116.008005268345,115.97051988696 -480,109.251883070934,109.237863577153,109.223954194018,109.210153629929,109.196460613393,109.182873892645,109.16939223526,109.156014427786,109.142739275375,109.129565601433,109.116492247272,115.172332529927,115.133142803974,115.094276344341,115.055729180526,115.01749740655,114.979577179653,114.941964719029,114.904656304586,114.86764827574,114.830937030228,114.794519022964 -490,108.229915553916,108.216261706941,108.202715057859,108.189274349688,108.175938345013,108.162705825608,108.149575592063,108.136546463427,108.12361727685,108.110786887239,108.098054166921,113.980366023733,113.942311527574,113.904570619208,113.867139450122,113.830014234307,113.793191246996,113.756666823441,113.720437357707,113.684499301507,113.648849163055,113.613483505953 -500,107.200487643897,107.18719544172,107.174007557828,107.160922769454,107.147939872857,107.135057682957,107.122275032974,107.109590774075,107.097003775031,107.084512921882,107.072117117609,112.78328457612,112.746322118768,112.709651512399,112.673281335156,112.637207921443,112.601427664848,112.565937016961,112.530732486217,112.495810636763,112.46116808736,112.426801510304 -510,106.163359979054,106.150425403584,106.137592300079,106.124859479576,106.112225771609,106.099690023847,106.087251101748,106.074907888216,106.062659283267,106.050504203703,106.038441582792,111.58046804476,111.544594927024,111.509016602242,111.473729462122,111.438729956832,111.404014593817,111.369579936659,111.335422603955,111.301539268224,111.267926654841,111.234581540997 -520,105.118283626543,105.105702644359,105.093220321237,105.080835501611,105.06854704788,105.056353840069,105.044254775484,105.032248768379,105.020334749637,105.008511666449,104.996778482003,110.372034891077,110.33724720946,110.302745103897,110.268525081955,110.234583707746,110.200917600784,110.16752343488,110.134397937061,110.101537886512,110.068940113543,110.036601498587 -530,104.064999619219,104.052768182294,104.040632625069,104.02859182496,104.016644676831,104.004790092659,103.993027001206,103.981354347692,103.969771093486,103.958276215791,103.946868707353,109.157731235397,109.124012748825,109.090570767566,109.05740191317,109.024502861849,108.99187034337,108.959501139991,108.927392085409,108.895540063746,108.863942008548,108.832594901812 -540,103.003238464434,102.991352510841,102.97955969124,102.967858915615,102.956249110886,102.944729220586,102.933298204535,102.921955038534,102.910698714053,102.899528237938,102.888442632115,107.937279056964,107.904613502543,107.872215529525,107.840081871549,107.808209315058,107.77659469824,107.745234909991,107.714126888904,107.683267622292,107.652654145213,107.622283539544 -550,101.932719622999,101.921175077596,101.909720954233,101.89835619505,101.887079758615,101.875890619612,101.864787768529,101.853770211353,101.842836969278,101.831987078412,101.821219589495,106.710388018682,106.678759122208,106.647389030539,106.616274587488,106.585412687852,106.554800276382,106.524434346794,106.494282983142,106.464364616841,106.434684140738,106.405238735423 -560,100.853150956205,100.841943731293,100.830824250328,100.819791487184,100.808844431669,100.797982089216,100.787203480583,100.776507641556,100.765893622667,100.755360488908,100.744907319461,105.476754945406,105.446119252229,105.415723322119,105.38557467042,105.355670298971,105.326007257754,105.296582643942,105.267393600956,105.238437317554,105.209711026935,105.181212005869 -570,99.7642281386292,99.7533541346046,99.7425652303751,99.7318604311362,99.7212387575233,99.7106992453148,99.7002409451403,99.6898629221948,99.6795642559619,99.6693440399418,99.6591936540695,104.23588820423,104.20624602044,104.17684569139,104.147684275799,104.11875887977,104.090066655839,104.061604802052,104.03337056106,104.005361219239,103.977574105828,103.95000659209 -580,98.665634034297,98.6550891402744,98.6446267359209,98.6342458573339,98.6239455555655,98.6137248963344,98.6035829597442,98.5935188400059,98.5835316451706,98.5736204968654,98.5637845300357,102.987660747081,102.959006518586,102.930585819697,102.902395813242,102.874433707719,102.846696756374,102.819182256317,102.791887547647,102.764810012608,102.737947074756,102.71129619815 -590,97.5570380335149,97.5468181279407,97.5366781360087,97.5266171242993,97.5166341738686,97.5067283799706,97.4968988517833,97.4871447121413,97.4774650972766,97.4678591565632,97.4583260522675,101.731742270957,101.70405989436,101.676602868099,101.649368457204,101.622353970683,101.595556760649,101.568974221457,101.54260378887,101.516442939243,101.49048918872,101.46474009246 -600,96.4380953475082,96.4281962987566,96.4183746217864,96.4086294132409,96.3989597837677,96.3893648577493,96.3798437730387,96.3703956807007,96.361019744761,96.3517151419596,96.3424810615093,100.467776711107,100.441050103474,100.414540812681,100.388246204042,100.362163685198,100.336290705274,100.310624754052,100.28516336117,100.259904095332,100.234844563544,100.209982410363 -610,95.3084462577238,95.298863924679,95.2893564557807,95.279922977315,95.2705626291071,95.2612745642613,95.2520579489053,95.24291196194,95.2338357947974,95.224828651202,95.2158897469375,99.1953920596245,99.1696051650051,99.1440276993012,99.1186571261929,99.0934909500701,99.0685267152186,99.043762005029,99.0191944412223,98.9948216830954,98.9706414267826,98.9466514045362 -620,94.1677153163993,94.1584455490239,94.1492481724396,94.1401223421543,94.1310672267567,94.1220820076657,94.1131658788825,94.1043180467503,94.0955377297188,94.0868241581155,94.078176573919,97.9141995654263,97.8893363608352,97.8646748425003,97.8402125705544,97.8159471442535,97.7918762011947,97.7679974165565,97.7443085023561,97.7208072067237,97.6974913131941,97.6743586400159 -630,93.0155104946976,93.006549134589,92.9976577262422,92.9888354539658,92.9800815146977,92.9713951177634,92.9627754846369,92.9542218487082,92.9457334550571,92.9373095602312,92.928949432028,96.6237928747764,96.5998373756894,96.5760759650707,96.5525062975941,96.5291260655025,96.5059329978569,96.4829248598084,96.4600994518848,96.4374546092949,96.4149882012485,96.3926981302938 -640,91.8514222743819,91.842765155316,91.8341755833496,91.8256527711702,91.8171959436505,91.8088043376144,91.8004772016072,91.7922137956711,91.7840133911267,91.7758752703596,91.7677987266097,95.3237471084763,95.3006833738967,95.2778062743917,95.2551135572692,95.2326030058845,95.2102724389206,95.1881197096899,95.1661427054507,95.1443393467403,95.1227075867228,95.101245410554 -650,90.6750226786436,90.6666656271074,90.65837375241,90.6501462951963,90.6419825078582,90.6338816543104,90.6258430097677,90.6178658605292,90.6099495037675,90.6020932473235,90.5942964095027,94.0134755817458,93.9913215174958,93.9693465967026,93.9475486582521,93.9259255756011,93.9044503648583,93.8831378521849,93.8619941940291,93.8410173945125,93.8202054890391,93.7995565436867 -660,89.4856019474907,89.4775565308792,89.4695738404114,89.4616531455046,89.4537937268754,89.4459948763227,89.4382558965152,89.4305761007826,89.4229548129136,89.4153913669583,89.4078851070323,92.6924549638871,92.6711599958102,92.6500370079844,92.6290839281749,92.6082987172587,92.5876793685652,92.5672239072352,92.546930389593,92.5267969025352,92.5068215629322,92.4870025170449 -670,88.282533767652,88.2747795855256,88.2670858315855,88.2594518023261,88.2518768051171,88.2443601579958,88.2369011894616,88.2294992382759,88.2221536532672,88.2148637931413,88.2076290262928,91.3603118747879,91.3398601407874,91.3195733673837,91.2994495693191,91.2794867930224,91.2596831159777,91.2400366461118,91.2205455211946,91.201207908254,91.1820220030042,91.162986029288 -680,87.0656475005727,87.0581803478825,87.0507713600094,87.043419860101,87.0361251817641,87.0288866688643,87.0217036753287,87.0145755649535,87.0075017112168,87.0004814970956,86.9935143148854,90.0165297318923,89.9969054349139,89.9774392216188,89.9581291918365,89.9389734756901,89.9199702329934,89.9011176526654,89.8824139521582,89.8638573768977,89.845446199738,89.8271787204284 -690,85.8344235136038,85.8272391803842,85.8201107832082,85.813037671454,85.806019204549,85.7990547517776,85.7921436920914,85.7852854139251,85.7784793150158,85.7717248022281,85.7650212913802,88.660567268661,88.6417546799249,88.623093439841,88.6045817314495,88.5862177667234,88.5679997859932,88.5499260573886,88.5319948762927,88.5142045648081,88.4965534712364,88.4790399695698 -700,84.5874947465647,84.5806033657714,84.5737656215671,84.5669808902813,84.5602485578731,84.5535680197478,84.5469386805745,84.5403599541099,84.5338312630252,84.5273520387386,84.5209217212486,87.2916139739664,87.2736284235172,87.2557874432964,87.2380892989704,87.220532283807,87.2031147181269,87.1858349487717,87.1686913485823,87.1516823158908,87.1347770292141,87.1180030520955 -710,83.324827217275,83.3182096973134,83.3116436583328,83.3051285020036,83.2986636392305,83.2922484899762,83.2858824830871,83.2795650561241,83.2732956551972,83.267073734804,83.2608987576706,85.908740671119,85.8915342286298,85.8744659108293,85.8575340628243,85.8407370560265,85.8240732876301,85.8075411801055,85.7911391807029,85.7748657609686,85.7587194162718,85.7426986653437 -720,82.0457096278374,82.0393755312979,82.0330906930786,82.0268545408799,82.0206665112317,82.0145260493254,82.0084326088468,82.0023856518145,81.9963846484215,81.9904290768815,81.9845184232764,84.5117719408656,84.495329045546,84.4790179690958,84.4628371342171,84.4467849886527,84.4308600046887,84.4150606786734,84.3993855305449,84.3838331033719,84.3684019629031,84.3530906971291 -730,80.7486749628618,80.7426057000813,80.7365836136397,80.730608155684,80.7246787868096,80.7187949758998,80.7129561999655,80.7071619439913,80.7014117007834,80.6957049708232,80.6900412621207,83.0996650103509,83.0839992592729,83.0684589788966,83.0530426691203,83.0377488536409,83.0225760794811,83.007522916533,82.9925879571092,82.977769815506,82.9630671275761,82.9484785503123 -740,79.4338607615884,79.4280652371814,79.4223147445155,79.4166087608309,79.4109467714264,79.4053282695061,79.3997527560275,79.3942197395534,79.3887287361081,79.3832792690369,79.3778708688667,81.6712708674768,81.6563362139503,81.6415210126344,81.6268238372804,81.6122432842374,81.5977779720038,81.5834265407946,81.5691876521153,81.555059988348,81.5410422523463,81.5271331670396 -750,78.0991665033548,78.0936267256959,78.0881299717913,78.0826757424302,78.0772635460938,78.071892898809,78.0665633240034,78.0612743523641,78.0560255217003,78.0508163768098,78.0456464693453,80.2264197090199,80.2122288237985,80.1981513291283,80.1841858723471,80.1703215296299,80.1565488685423,80.1428844882167,80.1293271176714,80.1158755057223,80.1025284205998,80.0892846495736 -760,76.7446619169102,76.7393860502793,76.7341511419843,76.7289567169571,76.723802307447,76.7186874528815,76.7136116997284,76.7085746013617,76.7035757179309,76.6986146162335,76.6936908695887,78.7630162208311,78.7495241096846,78.736139656041,78.7228615773764,78.7096886114444,78.6966195158749,78.6836530677857,78.6707880634015,78.658023317683,78.6453576639641,78.6327899535974 -770,75.3685866225035,75.3635573637401,75.3585671296012,75.3536154676685,75.3487019324884,75.3438260854402,75.3389874946048,75.3341857346371,75.3294203866412,75.3246910380499,75.319997282504,77.2811121656465,77.2683301540632,77.2556500277865,77.2430705742164,77.2305905999085,77.2182089301946,77.205924408817,77.1937358975682,77.181642275941,77.1696424407859,77.1577353059767 -780,73.9698278034401,73.9650524991158,73.9603142341499,73.955612579305,73.9509471119494,73.9463174159319,73.941723081457,73.9371637049641,73.9326388890096,73.9281482421519,73.9236913788376,75.7786303881267,75.7665150159221,75.7544960787138,75.7425724303685,75.7307429428338,75.7190065057806,75.7073620262579,75.6958084283538,75.6843446528651,75.6729696569747,75.6616824139358 -790,72.5474663089349,72.5429398221279,72.5384484305309,72.5339917275971,72.5295693130338,72.5251807926841,72.5208257784082,72.51650388797,72.5122147449245,72.5079579785098,72.5037332235386,74.2547147333932,74.2432756148519,74.2319274499954,74.2206691589271,74.2094996787707,74.1984179633334,74.1874229827818,74.1765137233225,74.1656891868915,74.154948390851,74.1442903676924 -800,71.0998994747218,71.095605476199,71.091344753525,71.087116921422,71.0829216005362,71.0787584173257,71.0746270039484,71.0705269981542,71.0664580431786,71.0624197876405,71.0584118854396,72.7081441558916,72.697364219074,72.6866698993925,72.6760601813762,72.6655340655436,72.6550905680859,72.6447287205635,72.6344475696059,72.6242461766202,72.6141236175065,72.6040789823789 -810,69.6249411642998,69.6208858323125,69.6168619135995,69.6128690445966,69.608906867327,69.6049750292964,69.601073183387,69.5972009877557,69.5933581057342,69.5895442057322,69.5857589611408,71.1368655836554,71.1267035461265,71.1166221010087,71.1066202938045,71.0966971850236,71.0868518498875,71.0770833780436,71.067390873285,71.0577734532764,71.048230249288,71.0387604059336 -820,68.1214404232699,68.1176184924483,68.1138261544216,68.1100630668372,68.1063288926016,68.1026232997819,68.098945961506,68.0952965558671,68.0916747658291,68.088080279136,68.0845127882209,69.5391547447803,69.5296178585841,69.5201565200394,69.510769835374,69.5014569248545,69.4922169225084,69.4830489758586,69.4739522456603,69.4649259056458,69.4559691422748,69.4470811544908 -830,66.5873975730555,66.583803729791,66.580237701304,66.5766991659472,66.5731878070125,66.5697033126382,66.5662453757153,66.562813693798,66.5594079690151,66.5560279079846,66.5526732217284,67.9133719216858,67.904442903485,67.8955845346031,67.886795980158,67.8780764183671,67.869425040289,67.8608410495752,67.8523236622251,67.843872106348,67.8354856219309,67.8271634606104 -840,65.0206274307197,65.0172563157423,65.0139112803265,65.0105920230206,65.0072982469998,65.0040296599796,65.0007859741282,64.9975669059823,64.9943721763642,64.9912015103021,64.9880546369497,66.257311088182,66.2489725744482,66.2406999587355,66.232492463208,66.2243493222208,66.2162697820797,66.2082531008103,66.2002985479306,66.1924054042294,66.1845729615503,66.1768005225803 -850,63.4187375411119,63.4155837519961,63.4124543503412,63.4093490543778,63.4062675866591,63.4032096739809,63.4001750472988,63.3971634416501,63.3941745960764,63.3912082535489,63.3882641608939,64.5685515855946,64.5607861529751,64.5530820144768,64.5454384474621,64.5378547406061,64.530330193674,64.5228641173075,64.5154558328133,64.5081046719584,64.5008099767691,64.4935710993356 -860,61.7788913095777,61.7759584045937,61.7730481705832,61.7701603457035,61.7672946721279,61.7644508959707,61.7616287672105,61.7588280396179,61.7560484706829,61.7532898215466,61.7505518569308,62.8444325050821,62.8372226895241,62.8300697117241,62.8229729023937,62.8159316027102,62.8089451641102,62.8020129480924,62.7951343260225,62.7883086789434,62.7815353973901,62.7748138812089 -870,60.0974916035063,60.0947646527577,60.0920587713138,60.0893737159412,60.0867092471352,60.0840651290504,60.0814411294299,60.0788370195371,60.0762525740897,60.0736875711954,60.0711417922867,61.0818038286117,61.0751513796656,61.0685513214076,61.0620030375042,61.0555059212506,61.0490593753814,61.0426628118896,61.0363156518462,61.0300173252268,61.0237672707407,61.0175649356654 -880,58.3718398588616,58.3693133212936,58.3668062954703,58.3643185562435,58.3618498819148,58.3594000541716,58.3569688580214,58.354556081729,58.3521615167551,58.3497849576973,58.3474262022295,59.2765618187081,59.2704288396001,59.2643440977881,59.2583070265182,59.2523170678806,59.2463736726344,59.2404763000421,59.2346244177048,59.2288175014017,59.2230550349347,59.2173365099757 -890,56.597541226983,56.595217401955,56.5929115159511,56.5906233620528,56.5883527365107,56.5860994386859,56.5838632709901,56.5816440388267,56.5794415505358,56.577255617339,56.5750860532844,57.4257151566554,57.4200840825586,57.4144972399486,57.4089541098089,57.4034541812121,57.3979969511595,57.39258192443,57.3872086134296,57.381876538045,57.3765852255011,57.3713342102218 -900,54.7696610514191,54.7675259349765,54.7654072928502,54.7633049351075,54.7612186747232,54.7591483275259,54.757093712143,54.7550546499471,54.7530309650049,54.751022484027,54.7490290363177,55.523715252443,55.5185850593929,55.5134951186859,55.508444958503,55.503434114371,55.4984621290173,55.4935285522326,55.4886329407341,55.4837748580334,55.4789538743064,55.4741695662676 -910,52.8826329147933,52.8806879096757,52.8787579056344,52.8768427297941,52.8749422119245,52.873056184392,52.8711844821095,52.8693269424873,52.8674834053872,52.8656537130767,52.8638377101825,53.5660024963227,53.5613537488966,53.5567414342047,53.5521651256781,53.5476244033823,53.5431082425134,53.5386220306471,53.5341702952857,53.5297526405762,53.5253686767019,53.5210180197682 -920,50.9302854325946,50.9285239468375,50.926776040805,50.9250415580696,50.9233203445957,50.9216122486964,50.9199171209883,50.9182348143468,50.9165651838645,50.9149080868102,50.9132633825867,51.5446655475009,51.5404632028398,51.5362937467672,51.5321567947398,51.5280519681874,51.5239788943938,51.5199372063863,51.5159265428244,51.5119465478925,51.5079968711945,51.5040771676524 -930,48.9044877152189,48.9029030431781,48.9013305822642,48.8997701918773,48.8982217335666,48.8966850709917,48.8951600698814,48.893646597994,48.89214452508,48.8906537228448,48.8891740649115,49.4529070771036,49.4491473518355,49.4454170152926,49.4417157242628,49.4380431408588,49.4343989324123,49.4307827713754,49.4271943352214,49.4236333063493,49.4200993719904,49.4165922241171 -940,46.7957255802411,46.794310910424,46.7929071366803,46.7915141336095,46.7901317777266,46.7887599474286,46.7873985229568,46.7860473863621,46.7847064214711,46.7833755138536,46.782054550789,47.2813085630852,47.2779714775322,47.2746604442557,47.2713751593836,47.2681153237535,47.2648806428178,47.2616708265571,47.2584855893927,47.255324650102,47.252187731736,47.249074561539 -950,44.592796083963,44.5915445070942,44.5903025655055,44.5890701483595,44.5878471465108,44.5866334524767,44.5854289604041,44.5842335660382,44.5830471666934,44.5818696612242,44.5807009499952,45.0173461901611,45.0144239949148,45.0115245871944,45.0086477015002,45.0057930764432,45.0029604546617,45.000149582747,44.9973602111657,44.9945920941872,44.9918449898108,44.9891186596966 -960,42.2794707199437,42.2783803832867,42.2772984368827,42.2762247842582,42.2751593304123,42.2741019817903,42.2730526462557,42.2720112330624,42.2709776528296,42.2699518175164,42.2689336403958,42.6472163924613,42.6446752670154,42.6421539307963,42.6396521535451,42.6371697085639,42.6347063726429,42.6322619259962,42.6298361521946,42.6274288381029,42.6250397738168,42.6226687526033 -970,39.8381425902815,39.8372054912072,39.8362755998336,39.8353528333233,39.8344371101021,39.8335283498377,39.8326264734145,39.8317314029105,39.8308430615754,39.8299613738092,39.8290862651394,40.1512282774346,40.1490582186216,40.1469050382637,40.1447685402118,40.1426485313466,40.1405448215165,40.1384572234834,40.1363855528654,40.1343296280831,40.132289270307,40.1302643034058 -980,37.2430292543444,37.2422371834903,37.2414512018354,37.2406712394317,37.239897227397,37.2391290978975,37.2383667841264,37.237610220284,37.2368593415597,37.2361140841138,37.2353743850582,37.5049975932762,37.5031758068286,37.5013681713287,37.4995745225391,37.4977946987562,37.4960285407582,37.4942758917594,37.4925365973632,37.4908105055163,37.4890974664655,37.4873973327142 -990,34.4599032639387,34.4592517906086,34.4586053231666,34.457963804137,34.4573271769189,34.4566953857729,34.4560683758031,34.4554460929404,34.4548284839283,34.4542154963078,34.4536070784014,34.6731004141643,34.6716124620735,34.6701360530485,34.6686710532882,34.667217331054,34.6657747566259,34.6643432022668,34.6629225421831,34.6615126524883,34.6601134111677,34.658724698043 -1000,31.4379167461659,31.4373963163521,31.4368798833573,31.436367401316,31.4358588250603,31.4353541101093,31.4348532126553,31.4343560895499,31.4338626982924,31.4333729970188,31.432886944488,31.6062887300925,31.6051090189613,31.6039384468464,31.6027769079599,31.6016242981433,31.6004805148312,31.599345457024,31.598219025257,31.5971011215711,31.5959916494853,31.5948905139691 -1010,28.1016053399742,28.1012061102367,28.100809944689,28.1004168081889,28.1000266661281,28.0996394844248,28.0992552295128,28.0988738683303,28.0984953683119,28.0981196973795,28.0977468239322,28.2286684462889,28.2277775815275,28.2268936080629,28.2260164462406,28.2251460176322,28.2242822450064,28.2234250523099,28.222574364643,28.2217301082383,28.22089221044,28.2200605996832 -1020,24.3197095473458,24.3194264604742,24.3191455450002,24.3188667760365,24.3185901290729,24.3183155799728,24.3180431049642,24.317772680632,24.3175042839124,24.3172378920867,24.316973482774,24.4089685562411,24.4083375534924,24.4077114236162,24.4070901103829,24.4064735584277,24.405861713229,24.4052545210955,24.404651929149,24.4040538853095,24.40346033828,24.4028712375333 -1030,19.8426201220378,19.842442589616,19.8422664178905,19.8420915912781,19.8419180944302,19.8417459122337,19.8415750298029,19.8414054324756,19.841237105809,19.8410700355767,19.8409042077629,19.8977836278758,19.8973916846481,19.8970027623163,19.8966168260871,19.8962338417036,19.8958537754282,19.8954765940369,19.8951022648077,19.8947307555111,19.8943620344018,19.8939960702102 -1040,14.0185018340729,14.0184197802997,14.0183383547549,14.0182575502518,14.0181773597103,14.0180977761605,14.0180187927368,14.017940402677,14.0178625993186,14.0177853760999,14.0177087265563,14.0435849933506,14.0434058201059,14.0432280242359,14.043051589917,14.04287650157,14.0427027438515,14.0425303016496,14.042359160082,14.0421893044884,14.0420207204283,14.0418533936787 -1050,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 diff --git a/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_ABK/ABK_trajectories_Gemini_Roccaraso_September_2023.csv b/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_ABK/ABK_trajectories_Gemini_Roccaraso_September_2023.csv deleted file mode 100644 index 76de407a2ec89e16842f67f0640ffb348d8ad618..0000000000000000000000000000000000000000 --- a/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_ABK/ABK_trajectories_Gemini_Roccaraso_September_2023.csv +++ /dev/null @@ -1,799 +0,0 @@ -Z,Vz -0,-0 -0.00556526091077103,-0.0722042777183493 --0.00187732916424466,-0.028629272114192 -0.012203639159452,0.13110293117061 -0.0643131928814,0.407969892695492 -0.0302154802491259,0.799190241465337 -0.00323151163024704,1.30535418813599 -0.0241862281377507,1.93198634047356 --0.0307197611973606,2.67090226126514 --0.0630906815081289,3.52535817574377 -0.0402831253629756,4.487540600598 -0.0987417241819912,5.45286234527328 -0.132144176269321,6.40505874922452 -0.30791073706223,7.34014049977148 -0.466870433305075,8.26300134374896 -0.690070578217956,9.17681834678557 -0.879374489946485,10.0729410527287 -1.21075672616303,10.9797816930491 -1.32988719054651,11.8698594819378 -1.4679799184994,12.7618656707588 -1.57460934480446,13.6510987651105 -1.59233669019068,14.5288720340536 -1.52346461690263,15.3917247688078 -1.95380945314059,16.3156385124639 -2.1256451041254,17.2186409082627 -2.58985999668789,18.1544193820745 -3.07287955182983,19.0903547988515 -3.83824950375561,20.0557244908703 -4.04358087468972,20.9417108164658 -4.45619145021396,21.8555233184212 -4.9920606890762,22.7924293561083 -5.59865034918403,23.7500036697645 -6.18193920859062,24.7126537004107 -6.40294222832085,25.6179613435797 -6.50002856103856,26.5191671648743 -7.07213995120605,27.5316880576419 -7.49518803898536,28.5180080010793 -7.7869727659297,29.4717406365124 -8.03997611589625,30.4129256817787 -8.33975178139281,31.372306588356 -8.95377816831137,32.3907992728926 -9.29670052994834,33.3509868197924 -9.73647920351209,34.3369526002231 -10.6345944704833,35.4298594469778 -11.4246457650042,36.495827294971 -12.3515902901686,37.58759210693 -13.216188741254,38.6493384629655 -13.8663292913775,39.6486504337499 -14.9291604319806,40.7411176380544 -16.0513921302042,41.8695019235321 -17.0023900527631,43.0113404435915 -17.8967313103203,44.1399095863968 -19.2708365159174,45.3868919638164 -20.2374257856204,46.5269163158587 -21.3636187826794,47.7079157138574 -22.381919733549,48.8507525780454 -23.3485074192813,49.970632743358 -24.3930301674002,51.103862361505 -25.0435903791365,52.1211149719241 -25.5554592029689,53.0914907463751 -26.597952303963,54.2061376240555 -27.5900435636804,55.2877881585334 -28.4153905846647,56.3095743139021 -29.7192310372154,57.4639057932722 -30.5034197550788,58.4456865386168 -31.941263057749,59.6132958670948 -33.6258197866027,60.8439943497989 -35.8249581735818,62.2255756887781 -37.3816621845647,63.396217971771 -38.599971039481,64.4499701373287 -40.4746961933156,65.7005044759778 -42.2991177260401,66.9263304415812 -43.8951231318526,68.0566133409931 -45.1826059859554,69.0698280757966 -46.7171499798628,70.1481989299112 -47.9175946540511,71.1112057832671 -49.3614156438261,72.1780527525544 -50.9540767268741,73.2849404147887 -52.475299578186,74.3411331092113 -53.8589238481538,75.3118095775261 -55.0464951804743,76.1911161143757 -56.4219618690458,77.1272845845673 -58.1381535040807,78.1752337184173 -59.6933435282588,79.1558869080037 -61.26494213099,80.1215108142191 -62.8639792783829,81.0869244508067 -64.0582737659072,81.8911462567747 -65.5626829884959,82.804887506602 -66.9619523200311,83.6703144196649 -68.2726968121594,84.489031396226 -69.884898379061,85.4107850634446 -71.1328446674984,86.1791020133324 -72.2282849563392,86.87742169087 -73.6559019927738,87.6883817314811 -74.9336683703882,88.4285849317674 -77.0106988030923,89.4755751784239 -78.8399704452931,90.4095864779039 -80.3113630238208,91.1885943414436 -83.054776096657,92.4798397227504 -85.9284682688794,93.8164215846667 -87.8536960999261,94.737110061651 -90.367479970934,95.8860541094286 -92.8061609192671,96.9946557904826 -94.3716058486193,97.7266829116578 -95.7541475267499,98.3759206418546 -97.5858874342587,99.2079843859188 -99.054454116949,99.8710250149935 -100.13920625696,100.363324850166 -102.22579955652,101.268833861536 -103.919088730192,101.99756675458 -106.426602192385,103.053551560961 -108.780356539248,104.041827921814 -110.736439568993,104.844164802743 -113.076590287556,105.801456838434 -114.610447194539,106.394941110693 -116.703362982692,107.216402677104 -118.704957474601,107.990543203681 -120.191385615854,108.525061022349 -122.015995645702,109.204041474793 -123.518574443027,109.725424034661 -126.186822280923,110.761091313926 -128.726738940759,111.720569260965 -131.588213597835,112.817606910085 -134.014313351209,113.707006779215 -136.705054299096,114.706557512021 -138.962952131858,115.493285629337 -140.931564283972,116.147347668488 -142.885229942809,116.802578464836 -145.674544785976,117.888976476436 -148.307693974702,118.940051891259 -150.61224779939,119.856227652354 -153.339518120808,120.964775724465 -156.743649416639,122.377017951364 -158.939151287748,123.215950345946 -161.450915209701,124.194490364268 -163.775902138443,125.075374254196 -165.994025111324,125.878306502238 -168.714002980873,126.88071357215 -171.633298323292,127.964199632871 -174.449378367303,128.977912766086 -176.918576024609,128.690864334452 -178.930423118778,129.229605045785 -180.405868966427,129.413496590835 -183.209195795954,130.151663524131 -186.042325129471,130.822449292569 -188.954840621136,131.421388457982 -191.114926241858,131.544651092837 -193.777227962438,131.802916910506 -196.569671405771,132.027058798033 -199.824277229204,132.384914960294 -202.560361426385,132.415520544638 -205.087392183844,132.280121024243 -208.052382324387,132.299265511516 -210.758940133011,132.146995764618 -213.077567029506,131.772665798632 -215.757588281366,131.554536595359 -218.797857019263,131.513532083462 -221.697335591336,131.405383496894 -224.382421618171,131.195184655681 -227.298236056384,131.098171993608 -230.074222201122,130.935583385857 -232.885157187284,130.791594092114 -235.892743576099,130.744051198338 -239.014151181176,130.750950904428 -241.855751622056,130.623523752325 -244.604251489364,130.452472798046 -247.497180208358,130.355106518195 -249.886945462593,130.012909366625 -252.16911554902,129.621403446328 -254.781817691525,129.395329439657 -257.527484462403,129.236963646544 -259.755332058918,128.825959232148 -262.723479804946,128.781588067243 -265.560722113429,128.674823848235 -268.32280434859,128.532158918873 -270.320573137714,128.017427342389 -272.986122894227,127.83482022912 -276.428035988602,128.034291912379 -278.818714892137,127.715775202922 -280.771084107799,127.187026454948 -283.201873046169,126.896338629348 -285.375802587843,126.482816681867 -287.568307210928,126.084113052693 -289.806966715176,125.71152723057 -292.284239419902,125.460054302017 -294.761212932921,125.211009932546 -296.693183504501,124.69554781729 -298.460716652105,124.104018358673 -300.73562338948,123.768970773985 -302.365671540242,123.118750942942 -304.744048541595,122.844841937734 -307.13257314944,122.577760810518 -309.714067066639,122.410314041172 -312.231241386162,122.212736314004 -314.885298629724,122.084193298441 -317.699216047284,122.03593505784 -320.68787674928,122.073459533685 -323.718321387715,122.132716074759 -326.106889033312,121.875087545715 -328.25836380262,121.502187772188 -331.003333939309,121.426461966893 -333.623943913615,121.291716189829 -336.65471614833,121.359536576046 -339.461253370921,121.316336571731 -342.03981062438,121.160494579577 -344.215554592965,120.806586747212 -346.264135400271,120.392596001688 -348.449772828415,120.051606214431 -351.138925119297,119.962133971301 -353.855301878077,119.8885645352 -356.437029162081,119.748818427198 -359.396252422752,119.797450354198 -362.322925010284,119.830470025014 -364.407766300889,119.445764713569 -365.749351358683,118.694679204191 -367.866908111327,118.33783491229 -370.220273426916,118.101956577273 -372.448029664142,117.805645230211 -374.413086782587,117.381394058231 -375.547534503172,116.547767295832 -377.764118259261,116.262022571146 -379.965120926929,115.971197492335 -381.806891901208,115.50489078994 -383.772520606855,115.104394867571 -385.665289563768,114.672413013856 -387.647515624108,114.289674641531 -390.192641093477,114.190495273999 -392.373133345021,113.910306264294 -394.282134213205,113.497458021728 -396.278774357786,113.13331629478 -398.388096121932,112.829108495738 -401.291014999784,112.923947547108 -403.7412507378,112.792632660366 -405.825072377249,112.479751381502 -407.837487515713,112.134258012388 -410.095756564496,111.914509492629 -412.547974049124,111.793844714152 -415.212532808222,111.780952435659 -417.520126823176,111.589629497579 -419.787198803754,111.380062416709 -422.056862346134,111.174560028418 -424.032640833232,110.825323005017 -425.660676063967,110.306295997321 -428.124226456911,110.209511668235 -430.778459807502,110.208389445408 -432.712260962849,109.848026093971 -435.258795733332,109.796981669814 -437.727759505216,109.707706426816 -439.922917504715,109.483242082566 -442.219563126669,109.310923234618 -444.833070610728,109.299079592259 -447.06551294739,109.096865993451 -449.470419188913,108.982739040462 -451.718399458726,108.791212109997 -453.828183643702,108.53413519545 -455.53441495666,108.076860675802 -457.638767065108,107.823048143088 -459.790684177377,107.596069885577 -461.773243236555,107.287818615073 -464.003467007441,107.105441248058 -466.603274967309,107.108606572997 -468.754386918612,106.889978935473 -470.712403589089,106.576792287149 -472.849001397738,106.3548270631 -475.564468404273,106.42492549583 -478.233831434667,106.47209137728 -480.297722969313,106.215051866158 -482.168902710012,105.865603838969 -484.4437824545,105.720669706493 -486.18000784291,105.307771903737 -487.816640748413,104.85029534002 -489.793835596075,104.567444983931 -491.122599005914,103.961837043637 -493.380334950174,103.828651107933 -495.341293412578,103.548239425307 -496.314334915436,102.77816910209 -498.410187154951,102.575136608173 -500.606577588536,102.424956045489 -502.872372495768,102.310819350855 -505.440296593783,102.34949136894 -508.401642869245,102.584592174704 -510.854934286643,102.563555843799 -512.758219150431,102.268117957143 -514.749402381361,102.019892893953 -516.660785146383,101.733417351846 -518.489121912099,101.408313554753 -520.53008578693,101.192728267618 -522.52187640947,100.95524420581 -524.564162505329,100.745512815539 -526.41374128326,100.441881323818 -528.516274874108,100.267174809363 -530.131100138553,99.849938382687 -531.730021195164,99.4305945717226 -534.038150338216,99.3699100644493 -536.088600422559,99.1804023051793 -537.707778455868,98.7768038572014 -539.848489275571,98.6395475000993 -541.980266014142,98.498753594724 -544.062872730823,98.3338925160606 -546.108614701504,98.153884205384 -548.390268607964,98.0930026870277 -550.609094579748,98.0014259052242 -552.842421818994,97.9175553043711 -555.294476332894,97.9442367505901 -557.370588143377,97.7833882192316 -558.942619163525,97.3719973592761 -560.90158961971,97.1582746294795 -562.936246364262,96.9840426681232 -565.259095746681,96.9562949714385 -567.422137438137,96.8493941810292 -569.315005945937,96.6073611687178 -571.536801968698,96.5321839617175 -573.61711998281,96.3883432477753 -575.830187885289,96.3127609903173 -578.308438270883,96.3707619258242 -580.686050617598,96.3769569614407 -582.183181025369,95.9442452714764 -583.722050671627,95.5364856847342 -585.336474920832,95.1713547413629 -586.343131231561,94.5040420682957 -587.328099603067,93.8336373262104 -588.864909632157,93.4466220024134 -590.79303485242,93.2578788904091 -593.581983573471,93.5016588331758 -597.034361364601,94.0750933251759 -600.570882444234,94.6850878574453 -602.580919529673,94.5266495398306 -604.537835581393,94.3436692480765 -606.060478289341,93.9439022259969 -607.876514435443,93.6956932573286 -610.045348791874,93.6255916665864 -611.601706662164,93.2496152402149 -613.596729385886,93.0976545719587 -615.252543138615,92.7781611545975 -616.313725840541,92.1647282882352 -617.442957502281,91.59072812315 -619.472455008091,91.4740000974655 -620.975366354252,91.0937582463536 -622.857746537669,90.9077205645874 -624.183027931365,90.4467192224072 -625.185643911723,89.827517641893 -627.061770459052,89.6502963362053 -629.220403674505,89.6174065866825 -630.747487171826,89.2686939405238 -631.578962579255,88.575167829298 -632.561562553939,87.9657114019736 -634.382210661526,87.781268298689 -636.639712959218,87.8152599958505 -638.531868627053,87.6679272291154 -640.375912595714,87.4972044853263 -641.402761616198,86.9207657123595 -643.866541824126,87.067983136055 -645.678700144314,86.8876411613222 -647.488725031181,86.7088287744941 -649.181386024496,86.472869651485 -650.362811235702,85.9844872574992 -651.588473105985,85.5225023195903 -652.790052763979,85.0547722260736 -655.271772966146,85.2298552936505 -658.180272427751,85.6183793777718 -660.695232713873,85.8044827765084 -662.775501722881,85.7713640460066 -665.384340272557,86.0039740811144 -666.721634053668,85.5989027589495 -667.942719071026,85.1398715255941 -668.88102967826,84.5436029516483 -670.308296801787,84.1973042536955 -672.484536928851,84.2284081110228 -674.755343983574,84.3082386136289 -676.489868985638,84.1184592372 -678.651907660911,84.1436200370274 -680.816049523639,84.1707946151038 -683.542261232211,84.4793571670156 -685.112403813338,84.2053049709341 -686.784384405904,83.9867572507124 -688.454810685885,83.7682566893848 -690.012647984536,83.4961374562198 -691.154169209133,83.0182947887571 -692.805729567738,82.8013007697141 -694.605093878878,82.6590803906175 -695.731576081027,82.1840145169287 -697.656362170273,82.1126815015492 -699.234530246351,81.867732103111 -700.902176471131,81.6705329821646 -702.31476424025,81.3472034624357 -703.906507656532,81.1161374871352 -705.785768933323,81.0325846464027 -708.235424978426,81.2347849174152 -709.552975805293,80.8696436895905 -710.658762731188,80.4018191225668 -711.251581041072,79.682789021992 -713.507381175561,79.8006641368032 -715.811309826214,79.9419581765641 -717.971604919404,80.0110744480862 -719.826545913344,79.9272895062659 -721.342575442434,79.6745895347677 -723.589792827497,79.7907417860136 -725.336240448589,79.6552734720121 -726.95552470102,79.4564537467464 -728.649492849914,79.2980932091247 -730.666600464561,79.3033102140494 -732.333830413293,79.1324293100097 -734.563840827444,79.2450614059412 -736.04015526309,78.9799978715747 -737.276319217417,78.5971870672553 -738.515513464008,78.2208612303344 -739.634651220974,77.787449883485 -740.525763778352,77.2440996333957 -742.449108570429,77.2226959027242 -744.259552359217,77.1458323417955 -746.277809181321,77.1732486359775 -748.06958747738,77.0875862789071 -749.742338180126,76.9429204891975 -751.020724716004,76.6033772711159 -752.008506767601,76.1217822778397 -753.363202802919,75.8274422784206 -755.092131174598,75.7234384875128 -756.241053897186,75.3295618495797 -757.825960592913,75.1600385642935 -759.675312467861,75.1228268358725 -761.295795615504,74.9712632153262 -762.720033733318,74.7245421969237 -763.987231210967,74.4005905109316 -765.511199520975,74.208771698319 -767.021932392402,74.0131338288901 -768.91067755249,74.0090060657062 -769.869715740134,73.5397034028777 -770.714855565589,73.0180423247864 -772.586399960216,73.0145700624664 -774.983368766886,73.2731246485675 -776.885517490104,73.283240355616 -778.17100699867,72.9847213063943 -779.638618860707,72.7808235872634 -781.031150314678,72.5416857425845 -782.678317875081,72.4313670129948 -784.241165491092,72.2813293941179 -785.623259735841,72.0416812985714 -787.328230582376,71.9654477101194 -789.103625433902,71.9251535933758 -791.152929565466,72.0227312007197 -793.392644432665,72.2136114114687 -794.502061664688,71.8378508453677 -795.828044771366,71.574987233368 -797.119906054642,71.2974002122142 -797.982129604784,70.8069713747512 -798.455825410734,70.1289403943517 -799.688900443339,69.8362053874323 -801.19352562228,69.6819940995478 -802.257902795347,69.308946056714 -802.845444912314,68.7026793577176 -803.769012889704,68.2697975974299 -805.125400725952,68.0581126510642 -806.409564053218,67.8109210429131 -807.975238230453,67.7100841550346 -809.832835117914,67.7542226712993 -811.454969977075,67.6810911058367 -812.74948818094,67.4443055011998 -813.648288904328,67.0108656177869 -815.092215895305,66.8566268534581 -816.483281340771,66.6772992468869 -818.171344141781,66.6481530874714 -819.278481393072,66.3295359359851 -820.568884588997,66.1046059856546 -821.870889474373,65.8889380360855 -822.748890873257,65.4627907726804 -823.33685115181,64.8956977310169 -824.778127522071,64.7600373908084 -826.234933080962,64.635302489544 -827.564656691109,64.4484080727515 -828.69237018914,64.1614346427809 -829.584936536567,63.7599236044803 -831.014485466453,63.6313623997442 -832.230715342077,63.3958254051179 -833.754315333622,63.3167642892774 -835.518422795297,63.3594956395825 -836.283195583059,62.902714479079 -837.617366141771,62.7339626747767 -838.615161186181,62.4002439436465 -839.822108528733,62.1741395280754 -840.390900207839,61.6310909312335 -841.500689351463,61.3644738250242 -843.597506861739,61.5942292688491 -845.704133305039,61.8249220046306 -847.138659607982,61.7185956237494 -848.39810582996,61.5265775007868 -849.28853821902,61.1515876602896 -850.774292783312,61.076339133417 -851.992103899018,60.8692990167528 -853.12611276306,60.6232896948447 -854.04559000367,60.2717446988813 -854.891565382185,59.8871345882508 -857.587460342798,60.4326161615375 -859.786894174885,60.7224866652088 -860.849679734587,60.4425645735903 -862.415360774399,60.4164889226049 -864.515321001939,60.6588474862807 -865.636701086375,60.408210596087 -868.039006513646,60.8007271984222 -869.758015215271,60.8480466904981 -871.549057023325,60.931276270703 -873.158069433801,60.9224944639351 -874.91192321959,60.9862058857097 -876.87280942898,61.1519894931418 -876.425308196906,60.1116727235437 -874.931178582547,58.558819282114 -871.707217793206,56.1559979461839 -872.652602483965,55.8612697149792 -874.539922900574,56.0413659970684 -875.666435031589,55.8387350629035 -877.842855680613,56.1630235464416 -880.172170668002,56.5610260699665 -881.542597590204,56.4760251405041 -882.837129243112,56.3536471366935 -883.980638715618,56.1566891519244 -885.685586514492,56.243063256201 -887.4849951267,56.3757205213961 -888.436632949175,56.0829814166353 -889.554505795044,55.8771415788565 -890.000528543486,55.3371107936002 -890.832147926941,54.9946708139382 -892.196526270592,54.9242611514489 -893.375228874701,54.7615983851158 -895.280521514261,54.9621367195422 -896.184324345945,54.6601833748046 -897.113848892954,54.3752191436978 -898.11770976186,54.129325648478 -898.815438657657,53.7334944036375 -899.471241578049,53.3214493008614 -900.452121016335,53.0765620488845 -900.922471372317,52.5774149883176 -900.807310744619,51.7913477407505 -901.325706180141,51.3290695393991 -901.15498101239,50.5278516294338 -903.024840929925,50.7534933185135 -904.865313800893,50.9628550364073 -906.95525501489,51.2942193829505 -907.116834124112,50.6599559394552 -907.654411610561,50.2188184262344 -908.041888396553,49.7072946348122 -908.226243622539,49.0992818019078 -909.183138713749,48.8835840470848 -910.595160115928,48.8987958705506 -912.107523388415,48.9634805456603 -913.073673922099,48.7543900928096 -915.096529508908,49.0764582340013 -917.656510911026,49.6636388466411 -917.563286768548,48.917429867183 -916.386763215671,47.6393238472053 -916.887177892206,47.2112692664156 -917.743621315005,46.9651436379891 -918.480103067911,46.6615500647951 -919.758977977248,46.6330781534632 -920.706686324236,46.4388049752596 -922.614168824532,46.726147157079 -924.2618824632,46.8798798353633 -926.11617913202,47.1360367501688 -928.471780079061,47.6408225906812 -930.403892565099,47.9295842082243 -930.129227096196,47.1127213911957 -929.212774703441,45.9830339788118 -927.215684957924,44.3234901705895 -928.970564621694,44.5563072963281 -930.001332017217,44.4247582449388 -929.842123647808,43.6999813583963 -930.412264221086,43.3467714627826 -931.004185838039,43.007914654144 -932.835958284592,43.2932576065594 -935.008303138773,43.7460122173815 -936.333697460998,43.7697243330704 -937.32081855965,43.6236048950765 -937.496193973921,43.0743140351079 -937.916578887693,42.6529245581916 -937.88199516487,42.0096775391868 -938.155522102375,41.5253580541945 -938.222951320866,40.943346551957 -937.885444836661,40.1638653208127 -938.034279388043,39.6367196834638 -938.337709818584,39.1915172220917 -940.160815793738,39.5107109193404 -942.311723538226,39.9907226122758 -945.327164568023,40.8972807422864 -944.682887029349,39.9664645379712 -942.669886331651,38.359904307836 -942.938029031432,37.9112045382406 -942.266007605584,36.9961439231525 -940.375643627988,35.4807718753814 -941.240691851403,35.3582195256243 -943.390024979836,35.8794625457112 -945.612855884598,36.4315553521558 -947.377782867463,36.7499410849984 -949.690125278679,37.3390355473102 -950.683093744794,37.2622726792266 -950.580081337967,36.6394975632705 -951.458678149351,36.5128116654923 -952.700038500957,36.5684588396563 -954.566475148708,36.9361974188082 -956.122065724954,37.1450812282557 -956.31949194048,36.6736466652051 -956.892553276773,36.3945553516398 -957.942326474644,36.3559884998454 -958.468716416128,36.0566431533055 -958.566647772762,35.5459350960892 -958.113995624718,34.7646772907503 -958.532954997507,34.4278102244845 -958.93909958351,34.0877877537632 -959.566641450991,33.8626602855531 -959.633923054804,33.3598092708621 -959.671276441638,32.845174902091 -960.480999404474,32.7240214654055 -960.257357753861,32.0870928257579 -959.568156476923,31.2237500939382 -960.232777644816,31.0449916593643 -960.646241828775,30.743446996558 -961.420919128576,30.6241610968289 -962.410044551901,30.6143552523663 -963.076450907575,30.4423239637086 -963.46538145062,30.1340075544899 -963.353174407597,29.5771137382319 -964.891738105969,29.8519220240746 -966.59402390061,30.2063166703574 -968.455438371191,30.6364799012925 -969.214819937612,30.5117093992775 -969.892296579372,30.3474807438264 -970.548177739324,30.1738333034791 -970.788117878537,29.7947972713675 -971.623039195114,29.7167033446008 -972.700919771359,29.7600072971585 -972.637071909282,29.232015176617 -973.853171348568,29.3488539318272 -975.24149334603,29.5496952211484 -976.985827376203,29.9272503655768 -977.878950706574,29.875182555777 -978.858298889444,29.8651540909913 -980.060562799766,29.9669361693786 -980.855780318448,29.8631540670206 -981.426361905906,29.6490695977048 -982.306834530886,29.5916732269433 -983.225577769148,29.552726755446 -983.355724401949,29.1211468775699 -983.096495602468,28.4981608413994 -982.80147031968,27.8648103209117 -983.751711898068,27.8600783575826 -984.750531791805,27.8793832317969 -985.328571088504,27.6878371528798 -985.902601948214,27.4975347546903 -985.826377292729,26.9835307247049 -986.228299300228,26.7139094483759 -986.923060124308,26.5935271165506 -988.242162529255,26.7856139179947 -988.812400188803,26.6021394252419 -989.010434853295,26.2336385385929 -989.817926306187,26.1733945666125 -991.357266495759,26.4802598079585 -991.827586369607,26.2493457861934 -992.101250185518,25.9232507581558 -992.700097553855,25.7639616480924 -993.295081307662,25.603666775128 -994.116387125933,25.5578274444467 -995.078985752793,25.5835844865061 -996.025014434024,25.6012397661804 -996.755235012956,25.5118640200454 -997.29865299355,25.3289980643199 -998.801428629938,25.6272973409973 -999.401156157665,25.4718235297911 -1001.04162822388,25.8384766386078 -1002.06207854714,25.8913001364917 -1001.57214867368,25.189418472201 -1000.53516097538,24.220397414992 -1002.73505370666,24.8788337222367 -1004.41147680996,25.2695886902649 -1006.84171574739,26.0331433234242 -1006.44453882651,25.3756594637418 -1005.76294310827,24.5822374382129 -1006.31189168385,24.4122386470883 -1006.25734802451,23.9413831101738 -1006.57869043918,23.6647609558942 -1007.55802379777,23.7198620821821 -1008.09044272541,23.5510413035356 -1009.40081978199,23.7719745321853 -1010.08536397799,23.679185163083 -1010.5575983567,23.4804009391794 -1011.00401172917,23.2698420600528 -1012.50942062588,23.5923249585396 -1013.0396890715,23.4238935643631 -1013.06529319993,23.0052189798007 -1013.40254277167,22.7456551639431 -1013.85115211439,22.5457827473916 -1013.67952942389,22.0372821511554 -1014.37458862582,21.9666987189884 -1014.78272493004,21.7533015266155 -1015.21071977717,21.5524304464489 -1015.35124854927,21.2109003689269 -1016.28874531418,21.2704501256289 -1017.11506110283,21.2744072842751 -1018.04273994761,21.3282602510308 -1019.19654504132,21.4945872903006 -1019.42478170066,21.1970026240411 -1019.16294390613,20.6575848418893 -1019.46810857126,20.4068671108794 -1019.22033339876,19.8822836696728 -1019.46000238503,19.6068721513482 -1019.73177103154,19.3509665173242 -1019.38592509767,18.788216337032 -1019.8367387273,18.6296131424134 -1020.26909901548,18.4620416776948 -1020.27970199405,18.0862882935918 -1021.27472599785,18.2073168708396 -1022.05734754902,18.2201363596766 -1022.23621764407,17.9321917923052 -1022.44726258254,17.6636303256851 -1021.92434535952,17.029532872146 -1021.81056002304,16.6068391732189 -1021.88172012839,16.2813823475195 -1023.10804418616,16.536120584629 -1024.14514171422,16.6925981232276 -1025.31430666357,16.9146359862276 -1025.73018995637,16.7564701775741 -1026.1738709509,16.6164033521576 -1025.94499531505,16.1410822573805 -1025.50500743643,15.5659327999608 -1024.91048740072,14.9181180461801 -1025.14489586114,14.6913126315719 -1025.42270580172,14.4884136000014 -1025.77031188384,14.3232423261754 -1026.11364207865,14.1577017009167 -1026.50406307242,14.0168455546629 -1026.46765651071,13.6654921539999 -1026.60374747408,13.4027300506723 -1027.30521957368,13.4247829712474 -1027.83212004941,13.3603935762071 -1028.65165012233,13.4425124134026 -1028.49852996111,13.036692976959 -1027.79019086286,12.3569868913755 -1027.8736360596,12.0801870515575 -1029.19312499026,12.4251343801654 -1029.93874464871,12.4801316955839 -1030.68435892151,12.534235016911 -1032.7461290088,13.2450502061908 -1033.62823784376,13.3595041399923 -1034.34569828965,13.3907875487149 -1034.37190104951,13.0750114324684 -1035.46165406619,13.2953241792307 -1036.93367204535,13.7047501548005 -1036.94912522784,13.3816334767813 -1037.89210986139,13.524863549337 -1038.77049603111,13.6361152176283 -1038.92677313399,13.3840987195611 -1040.1838785482,13.6862424058022 -1039.32895295586,12.9303797172072 -1037.2660730996,11.5760252088979 -1036.91793950756,11.0931449339208 -1036.77914068768,10.7193648854186 -1036.10440536513,10.0819699694484 -1035.58728991847,9.52946797264148 -1034.50350327982,8.69957597013464 -1033.1769810753,7.75625466479393 -1033.23432983136,7.51509741140123 -1033.82152148914,7.54025544977628 -1033.5794337025,7.15266848528694 -1033.3075389439,6.75276058153862 -1032.06294475204,5.87104360573129 -1032.89373234438,6.03431319590441 -1034.09224561095,6.38080430864683 -1033.80763549575,5.98192096727312 -1033.95736800812,5.80480190590665 -1033.29616900625,5.2235739971944 -1033.9440098001,5.30217788096646 -1034.33282356854,5.25145871804845 -1033.90250834745,4.79106286599185 -1033.13740257059,4.16848326489001 -1032.40088860982,3.56537819063669 -1032.50682948459,3.39011597799512 -1032.54873634909,3.18558416594726 -1032.40788845075,2.89173565174537 -1032.12864502317,2.53141211990158 -1031.42777347568,1.96275056339689 -1031.90123715356,1.98691291121505 -1033.0554765817,2.35279553553068 -1033.28512520973,2.25297239823049 -1034.31845502547,2.55526643420276 -1035.40664856995,2.88220041041296 -1035.43075068509,2.67275127223016 -1035.20789337209,2.34203135975784 -1034.76664010188,1.90665675689358 -1034.37433978533,1.49934835138511 -1033.91520559226,1.06322699928562 -1033.37037198139,0.588175752825401 -1032.95119976096,0.180661932999299 -1033.09990933516,0.0616221224217922 -1033.03460336618,-0.162359752387517 -1033.0646186006,-0.336908442316262 -1032.56636178095,-0.774067337077759 -1032.22023152905,-1.13188439094091 -1032.44823651864,-1.1978058606169 -1032.95368594782,-1.1244481683257 -1033.11432542255,-1.22410042749699 -1033.28160945255,-1.32149410726466 -1033.40975074035,-1.43670815564825 diff --git a/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_ADA/ADA_configADA_Gemini_Roccaraso_September_2023.csv b/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_ADA/ADA_configADA_Gemini_Roccaraso_September_2023.csv deleted file mode 100644 index 3af7bb320805d1da0a0a8a28692492a8bbc35e2d..0000000000000000000000000000000000000000 --- a/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_ADA/ADA_configADA_Gemini_Roccaraso_September_2023.csv +++ /dev/null @@ -1,2 +0,0 @@ -ADA_FREQUENCY,ADA_SHADOWMODE,ADA_VELOCITY_THRESHOLD,ADA_COUNTER_THRESHOLD,ADA_Q_11,ADA_Q_22,ADA_Q_33,ADA_R -50,10,2.5,5,30,10,2.5,4000 diff --git a/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_MTR/MTR_CDcoeffShutDown_Gemini_Roccaraso_September_2023.csv b/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_MTR/MTR_CDcoeffShutDown_Gemini_Roccaraso_September_2023.csv deleted file mode 100644 index 63daa990fa28ef7b3c6d95f64aa490482dcdda62..0000000000000000000000000000000000000000 --- a/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_MTR/MTR_CDcoeffShutDown_Gemini_Roccaraso_September_2023.csv +++ /dev/null @@ -1,2 +0,0 @@ -n000,n100,n200,n300,n400,n500,n600 -0.554395329698886,-1.71019994711676,8.05103009321528,-22.2129400612042,34.6990670331566,-28.6219169089691,9.73349655723146 diff --git a/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_MTR/MTR_configMTR_Gemini_Roccaraso_September_2023.csv b/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_MTR/MTR_configMTR_Gemini_Roccaraso_September_2023.csv deleted file mode 100644 index a216a469ef43be76287ef7a67d05743fd9ec78a1..0000000000000000000000000000000000000000 --- a/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_MTR/MTR_configMTR_Gemini_Roccaraso_September_2023.csv +++ /dev/null @@ -1,2 +0,0 @@ -MEA_FREQUENCY,MEA_SHADOWMODE,SHUTDOWN_MAX_TIME,MEA_PREDICTION_THRESHOLD,MEA_Q_11,MEA_Q_22,MEA_Q_33,MEA_R,MEA_INIT_MASS,MEA_SHUTDOWN_TARGET_APOGEE -50,2.4,2.5,5,0.1,0.1,0.1,0.36,29.3444284809405,1000 diff --git a/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_MTR/MTR_mea_model_Gemini_Roccaraso_September_2023.csv b/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_MTR/MTR_mea_model_Gemini_Roccaraso_September_2023.csv deleted file mode 100644 index 7f0f31d80d9ebad41d08eb4d85af5a5005ab4c43..0000000000000000000000000000000000000000 --- a/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_MTR/MTR_mea_model_Gemini_Roccaraso_September_2023.csv +++ /dev/null @@ -1,2 +0,0 @@ -F_11,F_12,F_13,F_21,F_22,F_23,F_31,F_32,F_33 -1.43587119122887,-0.46900127650878,0,1,0,0,-0.002045309260755,0.001867496708935,1 diff --git a/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_NAS/NAS_configNAS_Gemini_Roccaraso_September_2023.csv b/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_NAS/NAS_configNAS_Gemini_Roccaraso_September_2023.csv deleted file mode 100644 index 2634c69936ab122bca4b089725f9cd39189984eb..0000000000000000000000000000000000000000 --- a/data/Gemini_Roccaraso_September_2023/HIL_CPP_files_NAS/NAS_configNAS_Gemini_Roccaraso_September_2023.csv +++ /dev/null @@ -1,2 +0,0 @@ -NAS_FREQUENCY,ACCELERATION_THRESHOLD,SIGMA_BARO,SIGMA_GPS,SIGMA_MAG,SIGMA_BETA,SIGMA_PITOT,SIGMA_W -50,NaN,5,5,1,0.0001,400,1 diff --git a/data/Lynx_Portugal_October_2021/CAinterpCoeffs.mat b/data/Lynx_Portugal_October_2021/CAinterpCoeffs.mat deleted file mode 100644 index f7fa8ef9357f2db30fb565ca31e4a54e63ef254b..0000000000000000000000000000000000000000 Binary files a/data/Lynx_Portugal_October_2021/CAinterpCoeffs.mat and /dev/null differ diff --git a/data/Lynx_Portugal_October_2021/Trajectories.mat b/data/Lynx_Portugal_October_2021/Trajectories.mat deleted file mode 100644 index 2108bf2592e26a3be5b53420033b31c2d488557a..0000000000000000000000000000000000000000 Binary files a/data/Lynx_Portugal_October_2021/Trajectories.mat and /dev/null differ diff --git a/data/Lynx_Roccaraso_September_2021/CAinterpCoeffs.mat b/data/Lynx_Roccaraso_September_2021/CAinterpCoeffs.mat deleted file mode 100644 index 4e68df5e4d4c0a7753498823feb67f09ec1428b7..0000000000000000000000000000000000000000 Binary files a/data/Lynx_Roccaraso_September_2021/CAinterpCoeffs.mat and /dev/null differ diff --git a/data/Lynx_Roccaraso_September_2021/Trajectories.mat b/data/Lynx_Roccaraso_September_2021/Trajectories.mat deleted file mode 100644 index 5921b9a1ad1bc9ef592d3729ec52e7576fb5b483..0000000000000000000000000000000000000000 Binary files a/data/Lynx_Roccaraso_September_2021/Trajectories.mat and /dev/null differ diff --git a/data/Pyxis_Portugal_October_2022/Trajectories.mat b/data/Pyxis_Portugal_October_2022/Trajectories.mat deleted file mode 100644 index 2eb1b452e7fea0cd8a68b6535f14242b042e3c4d..0000000000000000000000000000000000000000 Binary files a/data/Pyxis_Portugal_October_2022/Trajectories.mat and /dev/null differ diff --git a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp1.csv b/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp1.csv deleted file mode 100644 index 0f756f9d83fa3b9043a29d4b8a122b8050277698..0000000000000000000000000000000000000000 --- a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp1.csv +++ /dev/null @@ -1,301 +0,0 @@ -0,330.33 -10,329.18 -20,328.04 -30,326.91 -40,325.79 -50,324.68 -60,323.58 -70,322.5 -80,321.42 -90,320.34 -100,319.28 -110,318.23 -120,317.18 -130,316.14 -140,315.11 -150,314.08 -160,313.07 -170,312.05 -180,311.05 -190,310.05 -200,309.05 -210,308.06 -220,307.08 -230,306.1 -240,305.12 -250,304.15 -260,303.19 -270,302.23 -280,301.27 -290,300.32 -300,299.37 -310,298.43 -320,297.49 -330,296.55 -340,295.62 -350,294.69 -360,293.76 -370,292.84 -380,291.92 -390,291 -400,290.09 -410,289.18 -420,288.27 -430,287.36 -440,286.46 -450,285.55 -460,284.66 -470,283.76 -480,282.86 -490,281.97 -500,281.08 -510,280.19 -520,279.31 -530,278.42 -540,277.54 -550,276.66 -560,275.78 -570,274.9 -580,274.02 -590,273.15 -600,272.28 -610,271.4 -620,270.53 -630,269.67 -640,268.8 -650,267.93 -660,267.07 -670,266.2 -680,265.34 -690,264.48 -700,263.62 -710,262.76 -720,261.9 -730,261.05 -740,260.19 -750,259.34 -760,258.48 -770,257.63 -780,256.78 -790,255.92 -800,255.07 -810,254.22 -820,253.37 -830,252.53 -840,251.68 -850,250.83 -860,249.98 -870,249.14 -880,248.29 -890,247.45 -900,246.61 -910,245.76 -920,244.92 -930,244.08 -940,243.23 -950,242.39 -960,241.55 -970,240.71 -980,239.87 -990,239.03 -1000,238.19 -1010,237.35 -1020,236.51 -1030,235.68 -1040,234.84 -1050,234 -1060,233.16 -1070,232.33 -1080,231.49 -1090,230.65 -1100,229.82 -1110,228.98 -1120,228.14 -1130,227.31 -1140,226.47 -1150,225.63 -1160,224.8 -1170,223.96 -1180,223.13 -1190,222.29 -1200,221.46 -1210,220.62 -1220,219.79 -1230,218.95 -1240,218.11 -1250,217.28 -1260,216.44 -1270,215.61 -1280,214.77 -1290,213.93 -1300,213.1 -1310,212.26 -1320,211.43 -1330,210.59 -1340,209.75 -1350,208.92 -1360,208.08 -1370,207.24 -1380,206.4 -1390,205.56 -1400,204.73 -1410,203.89 -1420,203.05 -1430,202.21 -1440,201.37 -1450,200.53 -1460,199.69 -1470,198.85 -1480,198 -1490,197.16 -1500,196.32 -1510,195.48 -1520,194.63 -1530,193.79 -1540,192.94 -1550,192.1 -1560,191.25 -1570,190.4 -1580,189.56 -1590,188.71 -1600,187.86 -1610,187.01 -1620,186.16 -1630,185.31 -1640,184.46 -1650,183.6 -1660,182.75 -1670,181.89 -1680,181.04 -1690,180.18 -1700,179.32 -1710,178.47 -1720,177.61 -1730,176.75 -1740,175.88 -1750,175.02 -1760,174.16 -1770,173.29 -1780,172.42 -1790,171.56 -1800,170.69 -1810,169.82 -1820,168.95 -1830,168.07 -1840,167.2 -1850,166.32 -1860,165.44 -1870,164.57 -1880,163.68 -1890,162.8 -1900,161.92 -1910,161.03 -1920,160.14 -1930,159.26 -1940,158.36 -1950,157.47 -1960,156.58 -1970,155.68 -1980,154.78 -1990,153.88 -2000,152.98 -2010,152.07 -2020,151.16 -2030,150.26 -2040,149.34 -2050,148.43 -2060,147.51 -2070,146.59 -2080,145.67 -2090,144.75 -2100,143.82 -2110,142.89 -2120,141.96 -2130,141.02 -2140,140.08 -2150,139.14 -2160,138.2 -2170,137.25 -2180,136.3 -2190,135.34 -2200,134.38 -2210,133.42 -2220,132.46 -2230,131.49 -2240,130.51 -2250,129.54 -2260,128.56 -2270,127.57 -2280,126.58 -2290,125.59 -2300,124.59 -2310,123.59 -2320,122.58 -2330,121.57 -2340,120.55 -2350,119.53 -2360,118.5 -2370,117.47 -2380,116.43 -2390,115.39 -2400,114.34 -2410,113.28 -2420,112.22 -2430,111.15 -2440,110.07 -2450,108.99 -2460,107.9 -2470,106.8 -2480,105.7 -2490,104.59 -2500,103.47 -2510,102.34 -2520,101.2 -2530,100.05 -2540,98.897 -2550,97.731 -2560,96.555 -2570,95.369 -2580,94.171 -2590,92.963 -2600,91.743 -2610,90.51 -2620,89.265 -2630,88.006 -2640,86.734 -2650,85.447 -2660,84.144 -2670,82.826 -2680,81.491 -2690,80.138 -2700,78.767 -2710,77.376 -2720,75.965 -2730,74.531 -2740,73.075 -2750,71.594 -2760,70.087 -2770,68.552 -2780,66.987 -2790,65.39 -2800,63.759 -2810,62.09 -2820,60.382 -2830,58.63 -2840,56.829 -2850,54.977 -2860,53.066 -2870,51.091 -2880,49.043 -2890,46.913 -2900,44.691 -2910,42.359 -2920,39.901 -2930,37.29 -2940,34.492 -2950,31.458 -2960,28.111 -2970,24.321 -2980,19.838 -2990,14.013 -3000,0 diff --git a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp10.csv b/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp10.csv deleted file mode 100644 index 23c64184de6588387433606c0a0becc6ded62d5b..0000000000000000000000000000000000000000 --- a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp10.csv +++ /dev/null @@ -1,301 +0,0 @@ -0,680.09 -10,677.87 -20,675.64 -30,673.42 -40,671.18 -50,668.94 -60,666.69 -70,664.44 -80,662.18 -90,659.92 -100,657.66 -110,655.37 -120,653.09 -130,650.81 -140,648.51 -150,646.21 -160,643.91 -170,641.59 -180,639.27 -190,636.95 -200,634.61 -210,632.27 -220,629.92 -230,627.57 -240,625.21 -250,622.84 -260,620.47 -270,618.08 -280,615.69 -290,613.3 -300,610.89 -310,608.48 -320,606.07 -330,603.63 -340,601.2 -350,598.76 -360,596.3 -370,593.84 -380,591.38 -390,588.9 -400,586.41 -410,583.93 -420,581.42 -430,578.91 -440,576.39 -450,573.86 -460,571.32 -470,568.77 -480,566.21 -490,563.65 -500,561.07 -510,558.48 -520,555.89 -530,553.28 -540,550.66 -550,548.04 -560,545.4 -570,542.75 -580,540.1 -590,537.42 -600,534.74 -610,532.05 -620,529.34 -630,526.63 -640,523.89 -650,521.16 -660,518.41 -670,515.63 -680,512.86 -690,510.07 -700,507.26 -710,504.45 -720,501.61 -730,498.77 -740,495.91 -750,493.04 -760,490.16 -770,487.24 -780,484.33 -790,481.39 -800,478.45 -810,475.48 -820,472.5 -830,469.51 -840,466.48 -850,463.46 -860,460.41 -870,457.34 -880,454.26 -890,451.15 -900,448.03 -910,444.88 -920,441.72 -930,438.53 -940,435.33 -950,432.11 -960,428.86 -970,425.59 -980,422.3 -990,418.99 -1000,415.64 -1010,412.28 -1020,408.89 -1030,405.48 -1040,402.04 -1050,398.58 -1060,395.07 -1070,391.56 -1080,388 -1090,384.42 -1100,380.8 -1110,377.16 -1120,373.48 -1130,369.77 -1140,366.03 -1150,362.31 -1160,358.6 -1170,354.99 -1180,351.4 -1190,347.92 -1200,344.47 -1210,341.08 -1220,337.76 -1230,334.48 -1240,331.29 -1250,328.12 -1260,325.02 -1270,321.98 -1280,318.97 -1290,316.03 -1300,313.13 -1310,310.28 -1320,307.48 -1330,304.72 -1340,302.01 -1350,299.34 -1360,296.71 -1370,294.12 -1380,291.58 -1390,289.08 -1400,286.6 -1410,284.17 -1420,281.78 -1430,279.41 -1440,277.08 -1450,274.79 -1460,272.52 -1470,270.28 -1480,268.08 -1490,265.91 -1500,263.76 -1510,261.64 -1520,259.55 -1530,257.48 -1540,255.44 -1550,253.42 -1560,251.43 -1570,249.46 -1580,247.51 -1590,245.58 -1600,243.67 -1610,241.78 -1620,239.92 -1630,238.07 -1640,236.24 -1650,234.43 -1660,232.63 -1670,230.85 -1680,229.09 -1690,227.35 -1700,225.62 -1710,223.9 -1720,222.2 -1730,220.51 -1740,218.84 -1750,217.18 -1760,215.53 -1770,213.9 -1780,212.28 -1790,210.66 -1800,209.07 -1810,207.48 -1820,205.9 -1830,204.33 -1840,202.78 -1850,201.23 -1860,199.69 -1870,198.16 -1880,196.64 -1890,195.13 -1900,193.63 -1910,192.13 -1920,190.64 -1930,189.16 -1940,187.69 -1950,186.23 -1960,184.77 -1970,183.32 -1980,181.87 -1990,180.43 -2000,179 -2010,177.57 -2020,176.15 -2030,174.73 -2040,173.32 -2050,171.91 -2060,170.51 -2070,169.11 -2080,167.71 -2090,166.32 -2100,164.94 -2110,163.56 -2120,162.18 -2130,160.8 -2140,159.43 -2150,158.06 -2160,156.7 -2170,155.33 -2180,153.97 -2190,152.62 -2200,151.26 -2210,149.91 -2220,148.55 -2230,147.2 -2240,145.86 -2250,144.51 -2260,143.16 -2270,141.82 -2280,140.47 -2290,139.13 -2300,137.79 -2310,136.44 -2320,135.1 -2330,133.76 -2340,132.42 -2350,131.07 -2360,129.73 -2370,128.39 -2380,127.04 -2390,125.69 -2400,124.35 -2410,123 -2420,121.64 -2430,120.29 -2440,118.94 -2450,117.58 -2460,116.22 -2470,114.85 -2480,113.48 -2490,112.11 -2500,110.74 -2510,109.36 -2520,107.98 -2530,106.59 -2540,105.2 -2550,103.8 -2560,102.39 -2570,100.98 -2580,99.562 -2590,98.137 -2600,96.705 -2610,95.264 -2620,93.814 -2630,92.355 -2640,90.887 -2650,89.408 -2660,87.918 -2670,86.415 -2680,84.901 -2690,83.372 -2700,81.83 -2710,80.271 -2720,78.697 -2730,77.104 -2740,75.493 -2750,73.861 -2760,72.207 -2770,70.529 -2780,68.826 -2790,67.095 -2800,65.334 -2810,63.54 -2820,61.71 -2830,59.841 -2840,57.929 -2850,55.968 -2860,53.954 -2870,51.88 -2880,49.738 -2890,47.519 -2900,45.211 -2910,42.801 -2920,40.267 -2930,37.588 -2940,34.726 -2950,31.634 -2960,28.236 -2970,24.401 -2980,19.881 -2990,14.028 -3000,0 diff --git a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp11.csv b/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp11.csv deleted file mode 100644 index 9f5b504187361421ec31b51f751a9f479905f2d0..0000000000000000000000000000000000000000 --- a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp11.csv +++ /dev/null @@ -1,301 +0,0 @@ -0,725.4 -10,723.11 -20,720.82 -30,718.52 -40,716.22 -50,713.93 -60,711.61 -70,709.29 -80,706.98 -90,704.65 -100,702.31 -110,699.97 -120,697.64 -130,695.28 -140,692.92 -150,690.56 -160,688.2 -170,685.82 -180,683.44 -190,681.06 -200,678.65 -210,676.25 -220,673.85 -230,671.43 -240,669.01 -250,666.59 -260,664.16 -270,661.71 -280,659.26 -290,656.81 -300,654.34 -310,651.87 -320,649.4 -330,646.91 -340,644.42 -350,641.92 -360,639.42 -370,636.9 -380,634.38 -390,631.85 -400,629.31 -410,626.76 -420,624.21 -430,621.64 -440,619.07 -450,616.5 -460,613.9 -470,611.3 -480,608.7 -490,606.08 -500,603.45 -510,600.82 -520,598.17 -530,595.52 -540,592.86 -550,590.18 -560,587.5 -570,584.81 -580,582.1 -590,579.39 -600,576.67 -610,573.92 -620,571.18 -630,568.43 -640,565.65 -650,562.88 -660,560.09 -670,557.28 -680,554.47 -690,551.64 -700,548.8 -710,545.96 -720,543.09 -730,540.21 -740,537.33 -750,534.42 -760,531.51 -770,528.58 -780,525.63 -790,522.68 -800,519.7 -810,516.71 -820,513.72 -830,510.69 -840,507.67 -850,504.61 -860,501.55 -870,498.48 -880,495.37 -890,492.26 -900,489.13 -910,485.98 -920,482.82 -930,479.63 -940,476.43 -950,473.2 -960,469.96 -970,466.7 -980,463.42 -990,460.12 -1000,456.79 -1010,453.46 -1020,450.08 -1030,446.69 -1040,443.27 -1050,439.84 -1060,436.38 -1070,432.89 -1080,429.39 -1090,425.84 -1100,422.29 -1110,418.69 -1120,415.08 -1130,411.42 -1140,407.76 -1150,404.03 -1160,400.31 -1170,396.52 -1180,392.73 -1190,388.88 -1200,385.02 -1210,381.1 -1220,377.16 -1230,373.16 -1240,369.15 -1250,365.07 -1260,361.04 -1270,357.03 -1280,353.11 -1290,349.22 -1300,345.44 -1310,341.68 -1320,338.02 -1330,334.42 -1340,330.87 -1350,327.4 -1360,323.97 -1370,320.63 -1380,317.34 -1390,314.09 -1400,310.94 -1410,307.82 -1420,304.75 -1430,301.76 -1440,298.81 -1450,295.91 -1460,293.07 -1470,290.27 -1480,287.51 -1490,284.82 -1500,282.16 -1510,279.54 -1520,276.97 -1530,274.44 -1540,271.95 -1550,269.49 -1560,267.08 -1570,264.7 -1580,262.36 -1590,260.04 -1600,257.77 -1610,255.53 -1620,253.31 -1630,251.13 -1640,248.97 -1650,246.84 -1660,244.74 -1670,242.67 -1680,240.62 -1690,238.59 -1700,236.59 -1710,234.61 -1720,232.65 -1730,230.72 -1740,228.8 -1750,226.91 -1760,225.03 -1770,223.17 -1780,221.33 -1790,219.51 -1800,217.71 -1810,215.92 -1820,214.15 -1830,212.39 -1840,210.65 -1850,208.92 -1860,207.21 -1870,205.51 -1880,203.82 -1890,202.15 -1900,200.48 -1910,198.83 -1920,197.19 -1930,195.56 -1940,193.95 -1950,192.34 -1960,190.74 -1970,189.15 -1980,187.58 -1990,186.01 -2000,184.45 -2010,182.89 -2020,181.35 -2030,179.81 -2040,178.28 -2050,176.76 -2060,175.25 -2070,173.74 -2080,172.24 -2090,170.74 -2100,169.25 -2110,167.77 -2120,166.29 -2130,164.82 -2140,163.35 -2150,161.89 -2160,160.43 -2170,158.98 -2180,157.53 -2190,156.08 -2200,154.64 -2210,153.2 -2220,151.77 -2230,150.34 -2240,148.91 -2250,147.48 -2260,146.06 -2270,144.64 -2280,143.22 -2290,141.8 -2300,140.39 -2310,138.97 -2320,137.56 -2330,136.15 -2340,134.74 -2350,133.33 -2360,131.92 -2370,130.51 -2380,129.11 -2390,127.7 -2400,126.29 -2410,124.88 -2420,123.47 -2430,122.06 -2440,120.65 -2450,119.23 -2460,117.82 -2470,116.4 -2480,114.98 -2490,113.56 -2500,112.13 -2510,110.71 -2520,109.27 -2530,107.84 -2540,106.4 -2550,104.95 -2560,103.5 -2570,102.05 -2580,100.59 -2590,99.119 -2600,97.645 -2610,96.164 -2620,94.675 -2630,93.177 -2640,91.67 -2650,90.154 -2660,88.628 -2670,87.091 -2680,85.541 -2690,83.979 -2700,82.404 -2710,80.813 -2720,79.208 -2730,77.585 -2740,75.944 -2750,74.283 -2760,72.602 -2770,70.897 -2780,69.168 -2790,67.412 -2800,65.626 -2810,63.809 -2820,61.956 -2830,60.065 -2840,58.132 -2850,56.151 -2860,54.118 -2870,52.025 -2880,49.866 -2890,47.631 -2900,45.307 -2910,42.882 -2920,40.335 -2930,37.643 -2940,34.769 -2950,31.667 -2960,28.259 -2970,24.416 -2980,19.889 -2990,14.03 -3000,0 diff --git a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp2.csv b/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp2.csv deleted file mode 100644 index 71b9d9ee7634b0996e29a1ce3ae25f1992c1a492..0000000000000000000000000000000000000000 --- a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp2.csv +++ /dev/null @@ -1,301 +0,0 @@ -0,360.96 -10,359.14 -20,357.34 -30,355.6 -40,353.88 -50,352.22 -60,350.57 -70,348.96 -80,347.38 -90,345.82 -100,344.3 -110,342.78 -120,341.31 -130,339.85 -140,338.41 -150,336.99 -160,335.58 -170,334.2 -180,332.84 -190,331.49 -200,330.15 -210,328.83 -220,327.53 -230,326.24 -240,324.96 -250,323.7 -260,322.44 -270,321.2 -280,319.97 -290,318.74 -300,317.54 -310,316.33 -320,315.14 -330,313.96 -340,312.79 -350,311.62 -360,310.46 -370,309.31 -380,308.17 -390,307.04 -400,305.91 -410,304.79 -420,303.68 -430,302.57 -440,301.47 -450,300.37 -460,299.28 -470,298.19 -480,297.11 -490,296.04 -500,294.97 -510,293.91 -520,292.85 -530,291.79 -540,290.74 -550,289.7 -560,288.66 -570,287.62 -580,286.58 -590,285.55 -600,284.53 -610,283.51 -620,282.49 -630,281.47 -640,280.46 -650,279.45 -660,278.45 -670,277.44 -680,276.44 -690,275.45 -700,274.45 -710,273.46 -720,272.48 -730,271.49 -740,270.51 -750,269.53 -760,268.55 -770,267.57 -780,266.6 -790,265.63 -800,264.66 -810,263.7 -820,262.73 -830,261.77 -840,260.81 -850,259.85 -860,258.9 -870,257.94 -880,256.99 -890,256.04 -900,255.09 -910,254.15 -920,253.2 -930,252.26 -940,251.32 -950,250.38 -960,249.44 -970,248.5 -980,247.56 -990,246.63 -1000,245.7 -1010,244.77 -1020,243.84 -1030,242.91 -1040,241.98 -1050,241.05 -1060,240.13 -1070,239.21 -1080,238.28 -1090,237.36 -1100,236.44 -1110,235.52 -1120,234.6 -1130,233.69 -1140,232.77 -1150,231.86 -1160,230.94 -1170,230.03 -1180,229.12 -1190,228.2 -1200,227.29 -1210,226.38 -1220,225.47 -1230,224.57 -1240,223.66 -1250,222.75 -1260,221.84 -1270,220.94 -1280,220.03 -1290,219.13 -1300,218.23 -1310,217.32 -1320,216.42 -1330,215.52 -1340,214.62 -1350,213.71 -1360,212.81 -1370,211.91 -1380,211.01 -1390,210.11 -1400,209.21 -1410,208.31 -1420,207.41 -1430,206.52 -1440,205.62 -1450,204.72 -1460,203.82 -1470,202.92 -1480,202.03 -1490,201.13 -1500,200.23 -1510,199.33 -1520,198.43 -1530,197.54 -1540,196.64 -1550,195.74 -1560,194.84 -1570,193.95 -1580,193.05 -1590,192.15 -1600,191.25 -1610,190.35 -1620,189.45 -1630,188.55 -1640,187.65 -1650,186.75 -1660,185.85 -1670,184.95 -1680,184.05 -1690,183.15 -1700,182.25 -1710,181.34 -1720,180.44 -1730,179.53 -1740,178.63 -1750,177.72 -1760,176.82 -1770,175.91 -1780,175 -1790,174.09 -1800,173.18 -1810,172.27 -1820,171.36 -1830,170.45 -1840,169.54 -1850,168.62 -1860,167.71 -1870,166.79 -1880,165.87 -1890,164.95 -1900,164.03 -1910,163.11 -1920,162.19 -1930,161.26 -1940,160.34 -1950,159.41 -1960,158.48 -1970,157.55 -1980,156.62 -1990,155.68 -2000,154.75 -2010,153.81 -2020,152.87 -2030,151.93 -2040,150.99 -2050,150.04 -2060,149.09 -2070,148.14 -2080,147.19 -2090,146.24 -2100,145.28 -2110,144.32 -2120,143.36 -2130,142.39 -2140,141.43 -2150,140.46 -2160,139.49 -2170,138.51 -2180,137.53 -2190,136.55 -2200,135.57 -2210,134.58 -2220,133.59 -2230,132.59 -2240,131.59 -2250,130.59 -2260,129.59 -2270,128.58 -2280,127.57 -2290,126.55 -2300,125.53 -2310,124.5 -2320,123.47 -2330,122.44 -2340,121.4 -2350,120.35 -2360,119.3 -2370,118.25 -2380,117.19 -2390,116.12 -2400,115.05 -2410,113.98 -2420,112.89 -2430,111.81 -2440,110.71 -2450,109.61 -2460,108.5 -2470,107.38 -2480,106.26 -2490,105.13 -2500,103.99 -2510,102.84 -2520,101.69 -2530,100.53 -2540,99.353 -2550,98.171 -2560,96.978 -2570,95.776 -2580,94.563 -2590,93.339 -2600,92.104 -2610,90.856 -2620,89.597 -2630,88.324 -2640,87.037 -2650,85.736 -2660,84.42 -2670,83.089 -2680,81.741 -2690,80.375 -2700,78.992 -2710,77.589 -2720,76.165 -2730,74.721 -2740,73.253 -2750,71.761 -2760,70.243 -2770,68.698 -2780,67.123 -2790,65.516 -2800,63.875 -2810,62.197 -2820,60.48 -2830,58.719 -2840,56.91 -2850,55.05 -2860,53.131 -2870,51.149 -2880,49.094 -2890,46.958 -2900,44.729 -2910,42.392 -2920,39.928 -2930,37.312 -2940,34.51 -2950,31.471 -2960,28.12 -2970,24.327 -2980,19.841 -2990,14.014 -3000,0 diff --git a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp3.csv b/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp3.csv deleted file mode 100644 index 47153931101ba1c83eaa55a708d103c56940088c..0000000000000000000000000000000000000000 --- a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp3.csv +++ /dev/null @@ -1,301 +0,0 @@ -0,397.5 -10,395.6 -20,393.7 -30,391.8 -40,389.88 -50,387.96 -60,386.02 -70,384.08 -80,382.13 -90,380.17 -100,378.2 -110,376.22 -120,374.23 -130,372.23 -140,370.23 -150,368.21 -160,366.18 -170,364.14 -180,362.09 -190,360.08 -200,358.09 -210,356.16 -220,354.26 -230,352.4 -240,350.58 -250,348.79 -260,347.04 -270,345.31 -280,343.62 -290,341.95 -300,340.3 -310,338.69 -320,337.09 -330,335.52 -340,333.96 -350,332.43 -360,330.92 -370,329.42 -380,327.94 -390,326.48 -400,325.03 -410,323.61 -420,322.19 -430,320.79 -440,319.4 -450,318.02 -460,316.66 -470,315.31 -480,313.97 -490,312.64 -500,311.32 -510,310.02 -520,308.72 -530,307.43 -540,306.15 -550,304.88 -560,303.62 -570,302.37 -580,301.13 -590,299.89 -600,298.66 -610,297.44 -620,296.22 -630,295.02 -640,293.82 -650,292.62 -660,291.44 -670,290.26 -680,289.08 -690,287.91 -700,286.75 -710,285.59 -720,284.44 -730,283.29 -740,282.15 -750,281.01 -760,279.88 -770,278.75 -780,277.63 -790,276.51 -800,275.4 -810,274.29 -820,273.18 -830,272.08 -840,270.98 -850,269.89 -860,268.8 -870,267.71 -880,266.63 -890,265.55 -900,264.48 -910,263.41 -920,262.34 -930,261.28 -940,260.22 -950,259.16 -960,258.1 -970,257.05 -980,256 -990,254.96 -1000,253.91 -1010,252.87 -1020,251.84 -1030,250.8 -1040,249.77 -1050,248.74 -1060,247.71 -1070,246.69 -1080,245.67 -1090,244.65 -1100,243.63 -1110,242.61 -1120,241.6 -1130,240.59 -1140,239.58 -1150,238.58 -1160,237.57 -1170,236.57 -1180,235.57 -1190,234.57 -1200,233.57 -1210,232.58 -1220,231.59 -1230,230.6 -1240,229.61 -1250,228.62 -1260,227.63 -1270,226.65 -1280,225.67 -1290,224.68 -1300,223.7 -1310,222.73 -1320,221.75 -1330,220.77 -1340,219.8 -1350,218.83 -1360,217.85 -1370,216.88 -1380,215.91 -1390,214.95 -1400,213.98 -1410,213.01 -1420,212.05 -1430,211.08 -1440,210.12 -1450,209.16 -1460,208.2 -1470,207.24 -1480,206.28 -1490,205.32 -1500,204.36 -1510,203.4 -1520,202.45 -1530,201.49 -1540,200.54 -1550,199.58 -1560,198.63 -1570,197.67 -1580,196.72 -1590,195.77 -1600,194.82 -1610,193.86 -1620,192.91 -1630,191.96 -1640,191.01 -1650,190.06 -1660,189.11 -1670,188.16 -1680,187.21 -1690,186.26 -1700,185.3 -1710,184.35 -1720,183.4 -1730,182.45 -1740,181.5 -1750,180.55 -1760,179.6 -1770,178.65 -1780,177.7 -1790,176.74 -1800,175.79 -1810,174.84 -1820,173.88 -1830,172.93 -1840,171.98 -1850,171.02 -1860,170.07 -1870,169.11 -1880,168.15 -1890,167.19 -1900,166.23 -1910,165.27 -1920,164.31 -1930,163.35 -1940,162.39 -1950,161.42 -1960,160.46 -1970,159.49 -1980,158.53 -1990,157.56 -2000,156.59 -2010,155.61 -2020,154.64 -2030,153.67 -2040,152.69 -2050,151.71 -2060,150.73 -2070,149.75 -2080,148.77 -2090,147.78 -2100,146.79 -2110,145.8 -2120,144.81 -2130,143.82 -2140,142.82 -2150,141.82 -2160,140.82 -2170,139.82 -2180,138.81 -2190,137.8 -2200,136.79 -2210,135.77 -2220,134.76 -2230,133.74 -2240,132.71 -2250,131.68 -2260,130.65 -2270,129.62 -2280,128.58 -2290,127.54 -2300,126.49 -2310,125.44 -2320,124.39 -2330,123.33 -2340,122.27 -2350,121.2 -2360,120.13 -2370,119.05 -2380,117.97 -2390,116.89 -2400,115.79 -2410,114.7 -2420,113.59 -2430,112.48 -2440,111.37 -2450,110.25 -2460,109.12 -2470,107.98 -2480,106.84 -2490,105.69 -2500,104.53 -2510,103.37 -2520,102.2 -2530,101.01 -2540,99.823 -2550,98.624 -2560,97.415 -2570,96.196 -2580,94.967 -2590,93.727 -2600,92.476 -2610,91.213 -2620,89.938 -2630,88.65 -2640,87.349 -2650,86.034 -2660,84.704 -2670,83.359 -2680,81.998 -2690,80.619 -2700,79.223 -2710,77.807 -2720,76.372 -2730,74.915 -2740,73.436 -2750,71.932 -2760,70.403 -2770,68.847 -2780,67.262 -2790,65.645 -2800,63.995 -2810,62.307 -2820,60.581 -2830,58.811 -2840,56.994 -2850,55.126 -2860,53.199 -2870,51.209 -2880,49.147 -2890,47.004 -2900,44.769 -2910,42.425 -2920,39.956 -2930,37.334 -2940,34.527 -2950,31.484 -2960,28.13 -2970,24.333 -2980,19.845 -2990,14.015 -3000,0 diff --git a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp4.csv b/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp4.csv deleted file mode 100644 index 549937fd3cb202c9ae1dda4539a258e68ade50ec..0000000000000000000000000000000000000000 --- a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp4.csv +++ /dev/null @@ -1,301 +0,0 @@ -0,432.83 -10,430.92 -20,429 -30,427.08 -40,425.15 -50,423.21 -60,421.26 -70,419.31 -80,417.34 -90,415.37 -100,413.39 -110,411.4 -120,409.4 -130,407.4 -140,405.38 -150,403.35 -160,401.32 -170,399.28 -180,397.22 -190,395.16 -200,393.08 -210,391 -220,388.91 -230,386.81 -240,384.69 -250,382.57 -260,380.43 -270,378.29 -280,376.13 -290,373.96 -300,371.78 -310,369.58 -320,367.38 -330,365.16 -340,362.93 -350,360.73 -360,358.54 -370,356.43 -380,354.33 -390,352.31 -400,350.3 -410,348.34 -420,346.41 -430,344.51 -440,342.65 -450,340.81 -460,339.01 -470,337.23 -480,335.48 -490,333.75 -500,332.04 -510,330.36 -520,328.7 -530,327.06 -540,325.44 -550,323.83 -560,322.24 -570,320.67 -580,319.12 -590,317.58 -600,316.06 -610,314.55 -620,313.06 -630,311.57 -640,310.11 -650,308.65 -660,307.21 -670,305.78 -680,304.36 -690,302.95 -700,301.55 -710,300.17 -720,298.79 -730,297.42 -740,296.06 -750,294.71 -760,293.37 -770,292.04 -780,290.72 -790,289.4 -800,288.1 -810,286.8 -820,285.51 -830,284.22 -840,282.95 -850,281.68 -860,280.41 -870,279.16 -880,277.91 -890,276.67 -900,275.43 -910,274.2 -920,272.97 -930,271.76 -940,270.54 -950,269.33 -960,268.13 -970,266.94 -980,265.74 -990,264.56 -1000,263.38 -1010,262.2 -1020,261.03 -1030,259.86 -1040,258.7 -1050,257.54 -1060,256.39 -1070,255.24 -1080,254.1 -1090,252.96 -1100,251.82 -1110,250.69 -1120,249.56 -1130,248.43 -1140,247.31 -1150,246.2 -1160,245.08 -1170,243.97 -1180,242.87 -1190,241.76 -1200,240.66 -1210,239.57 -1220,238.47 -1230,237.38 -1240,236.3 -1250,235.21 -1260,234.13 -1270,233.05 -1280,231.98 -1290,230.91 -1300,229.84 -1310,228.77 -1320,227.7 -1330,226.64 -1340,225.58 -1350,224.53 -1360,223.47 -1370,222.42 -1380,221.37 -1390,220.32 -1400,219.27 -1410,218.23 -1420,217.19 -1430,216.15 -1440,215.11 -1450,214.08 -1460,213.04 -1470,212.01 -1480,210.98 -1490,209.95 -1500,208.92 -1510,207.9 -1520,206.87 -1530,205.85 -1540,204.83 -1550,203.81 -1560,202.79 -1570,201.77 -1580,200.76 -1590,199.74 -1600,198.73 -1610,197.72 -1620,196.71 -1630,195.7 -1640,194.69 -1650,193.68 -1660,192.67 -1670,191.67 -1680,190.66 -1690,189.65 -1700,188.65 -1710,187.65 -1720,186.64 -1730,185.64 -1740,184.64 -1750,183.64 -1760,182.63 -1770,181.63 -1780,180.63 -1790,179.63 -1800,178.63 -1810,177.63 -1820,176.63 -1830,175.63 -1840,174.63 -1850,173.63 -1860,172.63 -1870,171.63 -1880,170.63 -1890,169.63 -1900,168.62 -1910,167.62 -1920,166.62 -1930,165.62 -1940,164.61 -1950,163.61 -1960,162.6 -1970,161.6 -1980,160.59 -1990,159.58 -2000,158.58 -2010,157.57 -2020,156.56 -2030,155.54 -2040,154.53 -2050,153.52 -2060,152.5 -2070,151.49 -2080,150.47 -2090,149.45 -2100,148.43 -2110,147.4 -2120,146.38 -2130,145.35 -2140,144.33 -2150,143.29 -2160,142.26 -2170,141.23 -2180,140.19 -2190,139.15 -2200,138.11 -2210,137.06 -2220,136.02 -2230,134.97 -2240,133.92 -2250,132.86 -2260,131.8 -2270,130.74 -2280,129.67 -2290,128.61 -2300,127.53 -2310,126.46 -2320,125.38 -2330,124.29 -2340,123.21 -2350,122.12 -2360,121.02 -2370,119.92 -2380,118.81 -2390,117.7 -2400,116.59 -2410,115.47 -2420,114.34 -2430,113.21 -2440,112.07 -2450,110.93 -2460,109.78 -2470,108.62 -2480,107.46 -2490,106.29 -2500,105.11 -2510,103.93 -2520,102.74 -2530,101.54 -2540,100.33 -2550,99.11 -2560,97.883 -2570,96.646 -2580,95.4 -2590,94.143 -2600,92.875 -2610,91.595 -2620,90.304 -2630,89.001 -2640,87.684 -2650,86.353 -2660,85.009 -2670,83.649 -2680,82.273 -2690,80.881 -2700,79.47 -2710,78.042 -2720,76.593 -2730,75.123 -2740,73.631 -2750,72.116 -2760,70.575 -2770,69.008 -2780,67.411 -2790,65.784 -2800,64.122 -2810,62.425 -2820,60.689 -2830,58.91 -2840,57.083 -2850,55.206 -2860,53.271 -2870,51.273 -2880,49.204 -2890,47.054 -2900,44.812 -2910,42.461 -2920,39.985 -2930,37.359 -2940,34.546 -2950,31.499 -2960,28.14 -2970,24.339 -2980,19.848 -2990,14.016 -3000,0 diff --git a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp5.csv b/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp5.csv deleted file mode 100644 index 7c3819d59036a70edddc022aa7f841d2feb9b7cf..0000000000000000000000000000000000000000 --- a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp5.csv +++ /dev/null @@ -1,301 +0,0 @@ -0,468.81 -10,466.87 -20,464.92 -30,462.97 -40,461.01 -50,459.04 -60,457.06 -70,455.08 -80,453.09 -90,451.09 -100,449.08 -110,447.07 -120,445.04 -130,443.02 -140,440.97 -150,438.93 -160,436.87 -170,434.81 -180,432.73 -190,430.65 -200,428.56 -210,426.46 -220,424.35 -230,422.23 -240,420.1 -250,417.96 -260,415.82 -270,413.65 -280,411.49 -290,409.31 -300,407.12 -310,404.92 -320,402.71 -330,400.48 -340,398.26 -350,396.01 -360,393.75 -370,391.48 -380,389.21 -390,386.91 -400,384.61 -410,382.29 -420,379.96 -430,377.61 -440,375.26 -450,372.88 -460,370.5 -470,368.1 -480,365.69 -490,363.26 -500,360.86 -510,358.48 -520,356.18 -530,353.9 -540,351.68 -550,349.5 -560,347.35 -570,345.25 -580,343.17 -590,341.15 -600,339.14 -610,337.17 -620,335.23 -630,333.31 -640,331.43 -650,329.56 -660,327.72 -670,325.91 -680,324.11 -690,322.34 -700,320.59 -710,318.86 -720,317.14 -730,315.45 -740,313.77 -750,312.11 -760,310.47 -770,308.84 -780,307.23 -790,305.63 -800,304.05 -810,302.48 -820,300.92 -830,299.38 -840,297.85 -850,296.33 -860,294.83 -870,293.33 -880,291.85 -890,290.38 -900,288.92 -910,287.47 -920,286.03 -930,284.6 -940,283.18 -950,281.77 -960,280.37 -970,278.98 -980,277.59 -990,276.22 -1000,274.85 -1010,273.5 -1020,272.14 -1030,270.8 -1040,269.47 -1050,268.14 -1060,266.82 -1070,265.51 -1080,264.21 -1090,262.91 -1100,261.62 -1110,260.33 -1120,259.05 -1130,257.78 -1140,256.51 -1150,255.25 -1160,254 -1170,252.75 -1180,251.51 -1190,250.27 -1200,249.04 -1210,247.82 -1220,246.6 -1230,245.38 -1240,244.17 -1250,242.97 -1260,241.77 -1270,240.57 -1280,239.38 -1290,238.19 -1300,237.01 -1310,235.83 -1320,234.66 -1330,233.49 -1340,232.32 -1350,231.16 -1360,230.01 -1370,228.85 -1380,227.7 -1390,226.56 -1400,225.42 -1410,224.28 -1420,223.14 -1430,222.01 -1440,220.88 -1450,219.75 -1460,218.63 -1470,217.51 -1480,216.4 -1490,215.28 -1500,214.17 -1510,213.06 -1520,211.96 -1530,210.86 -1540,209.76 -1550,208.66 -1560,207.57 -1570,206.47 -1580,205.38 -1590,204.29 -1600,203.21 -1610,202.12 -1620,201.04 -1630,199.96 -1640,198.88 -1650,197.81 -1660,196.73 -1670,195.66 -1680,194.59 -1690,193.52 -1700,192.45 -1710,191.39 -1720,190.32 -1730,189.26 -1740,188.2 -1750,187.13 -1760,186.07 -1770,185.02 -1780,183.96 -1790,182.9 -1800,181.84 -1810,180.79 -1820,179.73 -1830,178.68 -1840,177.63 -1850,176.57 -1860,175.52 -1870,174.47 -1880,173.42 -1890,172.37 -1900,171.32 -1910,170.27 -1920,169.22 -1930,168.17 -1940,167.12 -1950,166.07 -1960,165.02 -1970,163.97 -1980,162.92 -1990,161.86 -2000,160.81 -2010,159.76 -2020,158.71 -2030,157.66 -2040,156.6 -2050,155.55 -2060,154.49 -2070,153.44 -2080,152.38 -2090,151.32 -2100,150.26 -2110,149.2 -2120,148.14 -2130,147.07 -2140,146.01 -2150,144.94 -2160,143.88 -2170,142.81 -2180,141.73 -2190,140.66 -2200,139.58 -2210,138.51 -2220,137.43 -2230,136.34 -2240,135.26 -2250,134.17 -2260,133.08 -2270,131.99 -2280,130.89 -2290,129.8 -2300,128.69 -2310,127.59 -2320,126.48 -2330,125.37 -2340,124.25 -2350,123.13 -2360,122.01 -2370,120.88 -2380,119.75 -2390,118.61 -2400,117.47 -2410,116.33 -2420,115.18 -2430,114.02 -2440,112.86 -2450,111.69 -2460,110.52 -2470,109.34 -2480,108.15 -2490,106.96 -2500,105.76 -2510,104.55 -2520,103.34 -2530,102.12 -2540,100.89 -2550,99.651 -2560,98.403 -2570,97.147 -2580,95.881 -2590,94.605 -2600,93.318 -2610,92.02 -2620,90.711 -2630,89.39 -2640,88.055 -2650,86.708 -2660,85.347 -2670,83.97 -2680,82.579 -2690,81.171 -2700,79.745 -2710,78.301 -2720,76.838 -2730,75.354 -2740,73.849 -2750,72.32 -2760,70.766 -2770,69.185 -2780,67.576 -2790,65.937 -2800,64.264 -2810,62.556 -2820,60.808 -2830,59.019 -2840,57.182 -2850,55.295 -2860,53.351 -2870,51.344 -2880,49.266 -2890,47.108 -2900,44.858 -2910,42.501 -2920,40.019 -2930,37.386 -2940,34.568 -2950,31.515 -2960,28.151 -2970,24.346 -2980,19.852 -2990,14.017 -3000,0 diff --git a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp6.csv b/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp6.csv deleted file mode 100644 index a9209a9581c8a102fdf1a78a38ed8a6e69b40360..0000000000000000000000000000000000000000 --- a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp6.csv +++ /dev/null @@ -1,301 +0,0 @@ -0,505.99 -10,504.02 -20,502.03 -30,500.05 -40,498.06 -50,496.05 -60,494.05 -70,492.03 -80,490.01 -90,487.98 -100,485.94 -110,483.91 -120,481.85 -130,479.79 -140,477.73 -150,475.65 -160,473.58 -170,471.48 -180,469.39 -190,467.28 -200,465.16 -210,463.04 -220,460.91 -230,458.78 -240,456.62 -250,454.47 -260,452.3 -270,450.12 -280,447.94 -290,445.74 -300,443.54 -310,441.33 -320,439.11 -330,436.87 -340,434.63 -350,432.37 -360,430.11 -370,427.83 -380,425.55 -390,423.25 -400,420.94 -410,418.62 -420,416.29 -430,413.95 -440,411.59 -450,409.23 -460,406.84 -470,404.45 -480,402.05 -490,399.63 -500,397.2 -510,394.76 -520,392.29 -530,389.82 -540,387.33 -550,384.83 -560,382.32 -570,379.78 -580,377.24 -590,374.67 -600,372.1 -610,369.5 -620,366.89 -630,364.25 -640,361.62 -650,359.04 -660,356.49 -670,354.01 -680,351.57 -690,349.17 -700,346.83 -710,344.51 -720,342.25 -730,340.01 -740,337.82 -750,335.66 -760,333.52 -770,331.43 -780,329.35 -790,327.31 -800,325.3 -810,323.3 -820,321.35 -830,319.41 -840,317.49 -850,315.6 -860,313.72 -870,311.87 -880,310.05 -890,308.23 -900,306.44 -910,304.67 -920,302.91 -930,301.17 -940,299.45 -950,297.74 -960,296.06 -970,294.38 -980,292.72 -990,291.08 -1000,289.45 -1010,287.83 -1020,286.23 -1030,284.64 -1040,283.06 -1050,281.5 -1060,279.95 -1070,278.41 -1080,276.88 -1090,275.36 -1100,273.86 -1110,272.36 -1120,270.88 -1130,269.4 -1140,267.94 -1150,266.49 -1160,265.04 -1170,263.61 -1180,262.18 -1190,260.76 -1200,259.35 -1210,257.96 -1220,256.57 -1230,255.18 -1240,253.81 -1250,252.44 -1260,251.08 -1270,249.73 -1280,248.39 -1290,247.05 -1300,245.72 -1310,244.4 -1320,243.09 -1330,241.78 -1340,240.47 -1350,239.18 -1360,237.89 -1370,236.6 -1380,235.33 -1390,234.06 -1400,232.79 -1410,231.53 -1420,230.27 -1430,229.02 -1440,227.78 -1450,226.54 -1460,225.31 -1470,224.08 -1480,222.85 -1490,221.63 -1500,220.42 -1510,219.2 -1520,218 -1530,216.8 -1540,215.6 -1550,214.4 -1560,213.21 -1570,212.03 -1580,210.84 -1590,209.66 -1600,208.49 -1610,207.32 -1620,206.15 -1630,204.98 -1640,203.82 -1650,202.66 -1660,201.51 -1670,200.35 -1680,199.2 -1690,198.05 -1700,196.91 -1710,195.77 -1720,194.63 -1730,193.49 -1740,192.35 -1750,191.22 -1760,190.09 -1770,188.96 -1780,187.84 -1790,186.71 -1800,185.59 -1810,184.47 -1820,183.35 -1830,182.23 -1840,181.11 -1850,180 -1860,178.88 -1870,177.77 -1880,176.66 -1890,175.55 -1900,174.44 -1910,173.34 -1920,172.23 -1930,171.12 -1940,170.02 -1950,168.91 -1960,167.81 -1970,166.71 -1980,165.6 -1990,164.5 -2000,163.4 -2010,162.29 -2020,161.19 -2030,160.09 -2040,158.99 -2050,157.89 -2060,156.78 -2070,155.68 -2080,154.58 -2090,153.47 -2100,152.37 -2110,151.27 -2120,150.16 -2130,149.05 -2140,147.95 -2150,146.84 -2160,145.73 -2170,144.62 -2180,143.51 -2190,142.39 -2200,141.28 -2210,140.16 -2220,139.04 -2230,137.92 -2240,136.8 -2250,135.68 -2260,134.55 -2270,133.42 -2280,132.29 -2290,131.16 -2300,130.02 -2310,128.89 -2320,127.74 -2330,126.6 -2340,125.45 -2350,124.3 -2360,123.14 -2370,121.99 -2380,120.82 -2390,119.66 -2400,118.49 -2410,117.31 -2420,116.13 -2430,114.95 -2440,113.76 -2450,112.56 -2460,111.36 -2470,110.15 -2480,108.94 -2490,107.72 -2500,106.5 -2510,105.27 -2520,104.03 -2530,102.78 -2540,101.53 -2550,100.27 -2560,98.996 -2570,97.717 -2580,96.429 -2590,95.131 -2600,93.823 -2610,92.504 -2620,91.174 -2630,89.832 -2640,88.478 -2650,87.112 -2660,85.731 -2670,84.336 -2680,82.926 -2690,81.5 -2700,80.057 -2710,78.597 -2720,77.117 -2730,75.617 -2740,74.096 -2750,72.551 -2760,70.982 -2770,69.387 -2780,67.764 -2790,66.111 -2800,64.425 -2810,62.704 -2820,60.944 -2830,59.143 -2840,57.295 -2850,55.397 -2860,53.442 -2870,51.425 -2880,49.338 -2890,47.17 -2900,44.912 -2910,42.546 -2920,40.056 -2930,37.416 -2940,34.592 -2950,31.533 -2960,28.164 -2970,24.355 -2980,19.856 -2990,14.019 -3000,0 diff --git a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp7.csv b/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp7.csv deleted file mode 100644 index a679118bb0e2ee5f70947d0ab9fdb6d65ae086c5..0000000000000000000000000000000000000000 --- a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp7.csv +++ /dev/null @@ -1,301 +0,0 @@ -0,546.81 -10,544.77 -20,542.74 -30,540.69 -40,538.64 -50,536.58 -60,534.52 -70,532.45 -80,530.37 -90,528.29 -100,526.2 -110,524.1 -120,522 -130,519.89 -140,517.76 -150,515.64 -160,513.51 -170,511.36 -180,509.22 -190,507.06 -200,504.9 -210,502.72 -220,500.54 -230,498.36 -240,496.16 -250,493.95 -260,491.74 -270,489.52 -280,487.29 -290,485.04 -300,482.8 -310,480.54 -320,478.27 -330,476 -340,473.71 -350,471.42 -360,469.11 -370,466.8 -380,464.47 -390,462.13 -400,459.79 -410,457.43 -420,455.07 -430,452.68 -440,450.3 -450,447.9 -460,445.49 -470,443.06 -480,440.63 -490,438.18 -500,435.72 -510,433.25 -520,430.77 -530,428.27 -540,425.76 -550,423.24 -560,420.7 -570,418.15 -580,415.58 -590,413.01 -600,410.41 -610,407.81 -620,405.18 -630,402.55 -640,399.89 -650,397.22 -660,394.53 -670,391.83 -680,389.1 -690,386.37 -700,383.61 -710,380.84 -720,378.04 -730,375.24 -740,372.4 -750,369.56 -760,366.68 -770,363.8 -780,360.94 -790,358.12 -800,355.36 -810,352.67 -820,350 -830,347.42 -840,344.85 -850,342.34 -860,339.87 -870,337.44 -880,335.05 -890,332.69 -900,330.37 -910,328.09 -920,325.83 -930,323.61 -940,321.42 -950,319.26 -960,317.12 -970,315.01 -980,312.93 -990,310.88 -1000,308.84 -1010,306.84 -1020,304.86 -1030,302.89 -1040,300.96 -1050,299.04 -1060,297.14 -1070,295.27 -1080,293.41 -1090,291.57 -1100,289.75 -1110,287.95 -1120,286.16 -1130,284.4 -1140,282.65 -1150,280.91 -1160,279.2 -1170,277.5 -1180,275.81 -1190,274.13 -1200,272.48 -1210,270.84 -1220,269.2 -1230,267.59 -1240,265.98 -1250,264.39 -1260,262.81 -1270,261.25 -1280,259.69 -1290,258.15 -1300,256.62 -1310,255.1 -1320,253.59 -1330,252.09 -1340,250.6 -1350,249.12 -1360,247.65 -1370,246.2 -1380,244.75 -1390,243.31 -1400,241.88 -1410,240.45 -1420,239.04 -1430,237.63 -1440,236.24 -1450,234.85 -1460,233.47 -1470,232.09 -1480,230.72 -1490,229.36 -1500,228.01 -1510,226.67 -1520,225.33 -1530,224 -1540,222.67 -1550,221.35 -1560,220.04 -1570,218.73 -1580,217.43 -1590,216.14 -1600,214.85 -1610,213.56 -1620,212.28 -1630,211.01 -1640,209.74 -1650,208.48 -1660,207.22 -1670,205.97 -1680,204.72 -1690,203.47 -1700,202.23 -1710,200.99 -1720,199.76 -1730,198.53 -1740,197.3 -1750,196.08 -1760,194.86 -1770,193.65 -1780,192.44 -1790,191.23 -1800,190.02 -1810,188.82 -1820,187.62 -1830,186.43 -1840,185.23 -1850,184.04 -1860,182.85 -1870,181.67 -1880,180.49 -1890,179.3 -1900,178.12 -1910,176.95 -1920,175.77 -1930,174.6 -1940,173.43 -1950,172.26 -1960,171.09 -1970,169.92 -1980,168.75 -1990,167.59 -2000,166.43 -2010,165.26 -2020,164.1 -2030,162.94 -2040,161.78 -2050,160.62 -2060,159.47 -2070,158.31 -2080,157.15 -2090,155.99 -2100,154.84 -2110,153.68 -2120,152.52 -2130,151.36 -2140,150.21 -2150,149.05 -2160,147.89 -2170,146.73 -2180,145.57 -2190,144.41 -2200,143.25 -2210,142.09 -2220,140.93 -2230,139.76 -2240,138.6 -2250,137.43 -2260,136.26 -2270,135.09 -2280,133.92 -2290,132.74 -2300,131.57 -2310,130.39 -2320,129.21 -2330,128.03 -2340,126.84 -2350,125.65 -2360,124.46 -2370,123.26 -2380,122.07 -2390,120.86 -2400,119.66 -2410,118.45 -2420,117.23 -2430,116.02 -2440,114.79 -2450,113.57 -2460,112.33 -2470,111.1 -2480,109.85 -2490,108.61 -2500,107.35 -2510,106.09 -2520,104.82 -2530,103.55 -2540,102.27 -2550,100.98 -2560,99.681 -2570,98.375 -2580,97.061 -2590,95.738 -2600,94.405 -2610,93.062 -2620,91.708 -2630,90.343 -2640,88.966 -2650,87.577 -2660,86.174 -2670,84.757 -2680,83.327 -2690,81.88 -2700,80.417 -2710,78.936 -2720,77.438 -2730,75.919 -2740,74.379 -2750,72.818 -2760,71.231 -2770,69.62 -2780,67.98 -2790,66.311 -2800,64.61 -2810,62.874 -2820,61.101 -2830,59.285 -2840,57.424 -2850,55.513 -2860,53.547 -2870,51.518 -2880,49.419 -2890,47.242 -2900,44.973 -2910,42.598 -2920,40.099 -2930,37.451 -2940,34.619 -2950,31.553 -2960,28.179 -2970,24.364 -2980,19.862 -2990,14.021 -3000,0 diff --git a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp8.csv b/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp8.csv deleted file mode 100644 index 765d8bb7f75fc5f1a0489a91a492f588a590863e..0000000000000000000000000000000000000000 --- a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp8.csv +++ /dev/null @@ -1,301 +0,0 @@ -0,587.65 -10,585.58 -20,583.49 -30,581.41 -40,579.32 -50,577.22 -60,575.11 -70,573.01 -80,570.89 -90,568.76 -100,566.64 -110,564.5 -120,562.36 -130,560.21 -140,558.05 -150,555.89 -160,553.72 -170,551.54 -180,549.36 -190,547.17 -200,544.97 -210,542.77 -220,540.55 -230,538.33 -240,536.1 -250,533.86 -260,531.62 -270,529.37 -280,527.1 -290,524.84 -300,522.56 -310,520.27 -320,517.98 -330,515.68 -340,513.37 -350,511.05 -360,508.72 -370,506.38 -380,504.03 -390,501.68 -400,499.31 -410,496.93 -420,494.55 -430,492.15 -440,489.75 -450,487.33 -460,484.91 -470,482.47 -480,480.02 -490,477.57 -500,475.1 -510,472.62 -520,470.13 -530,467.62 -540,465.11 -550,462.58 -560,460.05 -570,457.49 -580,454.93 -590,452.35 -600,449.76 -610,447.16 -620,444.54 -630,441.92 -640,439.27 -650,436.62 -660,433.94 -670,431.25 -680,428.55 -690,425.83 -700,423.1 -710,420.35 -720,417.59 -730,414.8 -740,412.01 -750,409.19 -760,406.36 -770,403.5 -780,400.64 -790,397.75 -800,394.84 -810,391.91 -820,388.97 -830,386 -840,383.01 -850,380 -860,376.97 -870,373.92 -880,370.84 -890,367.74 -900,364.61 -910,361.47 -920,358.41 -930,355.37 -940,352.42 -950,349.51 -960,346.65 -970,343.84 -980,341.07 -990,338.37 -1000,335.69 -1010,333.07 -1020,330.48 -1030,327.93 -1040,325.43 -1050,322.96 -1060,320.52 -1070,318.13 -1080,315.75 -1090,313.43 -1100,311.13 -1110,308.85 -1120,306.62 -1130,304.4 -1140,302.22 -1150,300.07 -1160,297.94 -1170,295.83 -1180,293.76 -1190,291.71 -1200,289.67 -1210,287.67 -1220,285.69 -1230,283.73 -1240,281.79 -1250,279.87 -1260,277.98 -1270,276.09 -1280,274.24 -1290,272.4 -1300,270.58 -1310,268.78 -1320,266.99 -1330,265.22 -1340,263.47 -1350,261.73 -1360,260.02 -1370,258.31 -1380,256.62 -1390,254.95 -1400,253.29 -1410,251.64 -1420,250.01 -1430,248.39 -1440,246.78 -1450,245.19 -1460,243.61 -1470,242.04 -1480,240.48 -1490,238.93 -1500,237.4 -1510,235.87 -1520,234.36 -1530,232.85 -1540,231.36 -1550,229.88 -1560,228.4 -1570,226.93 -1580,225.48 -1590,224.03 -1600,222.59 -1610,221.16 -1620,219.74 -1630,218.33 -1640,216.92 -1650,215.52 -1660,214.13 -1670,212.75 -1680,211.37 -1690,210 -1700,208.63 -1710,207.28 -1720,205.92 -1730,204.58 -1740,203.24 -1750,201.91 -1760,200.58 -1770,199.25 -1780,197.94 -1790,196.63 -1800,195.32 -1810,194.02 -1820,192.72 -1830,191.42 -1840,190.13 -1850,188.85 -1860,187.57 -1870,186.29 -1880,185.02 -1890,183.75 -1900,182.48 -1910,181.22 -1920,179.96 -1930,178.71 -1940,177.45 -1950,176.2 -1960,174.96 -1970,173.71 -1980,172.47 -1990,171.23 -2000,169.99 -2010,168.76 -2020,167.53 -2030,166.3 -2040,165.07 -2050,163.84 -2060,162.61 -2070,161.39 -2080,160.17 -2090,158.94 -2100,157.72 -2110,156.5 -2120,155.28 -2130,154.07 -2140,152.85 -2150,151.63 -2160,150.42 -2170,149.2 -2180,147.98 -2190,146.77 -2200,145.55 -2210,144.34 -2220,143.12 -2230,141.9 -2240,140.69 -2250,139.47 -2260,138.25 -2270,137.03 -2280,135.81 -2290,134.59 -2300,133.36 -2310,132.14 -2320,130.91 -2330,129.68 -2340,128.45 -2350,127.22 -2360,125.98 -2370,124.75 -2380,123.51 -2390,122.26 -2400,121.02 -2410,119.77 -2420,118.51 -2430,117.26 -2440,116 -2450,114.73 -2460,113.46 -2470,112.19 -2480,110.91 -2490,109.63 -2500,108.34 -2510,107.04 -2520,105.74 -2530,104.43 -2540,103.12 -2550,101.8 -2560,100.47 -2570,99.135 -2580,97.791 -2590,96.438 -2600,95.076 -2610,93.705 -2620,92.323 -2630,90.931 -2640,89.527 -2650,88.112 -2660,86.684 -2670,85.243 -2680,83.787 -2690,82.317 -2700,80.831 -2710,79.328 -2720,77.807 -2730,76.266 -2740,74.706 -2750,73.123 -2760,71.518 -2770,69.887 -2780,68.229 -2790,66.542 -2800,64.823 -2810,63.07 -2820,61.28 -2830,59.448 -2840,57.572 -2850,55.647 -2860,53.667 -2870,51.624 -2880,49.513 -2890,47.323 -2900,45.043 -2910,42.658 -2920,40.149 -2930,37.491 -2940,34.651 -2950,31.577 -2960,28.196 -2970,24.375 -2980,19.867 -2990,14.023 -3000,0 diff --git a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp9.csv b/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp9.csv deleted file mode 100644 index c7bd86f40668a2a963f1449b59a60492f18502a6..0000000000000000000000000000000000000000 --- a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterp9.csv +++ /dev/null @@ -1,301 +0,0 @@ -0,632.1 -10,629.96 -20,627.82 -30,625.67 -40,623.51 -50,621.35 -60,619.19 -70,617.01 -80,614.84 -90,612.66 -100,610.46 -110,608.26 -120,606.07 -130,603.85 -140,601.64 -150,599.42 -160,597.18 -170,594.95 -180,592.71 -190,590.46 -200,588.2 -210,585.94 -220,583.67 -230,581.39 -240,579.11 -250,576.81 -260,574.52 -270,572.21 -280,569.89 -290,567.58 -300,565.24 -310,562.9 -320,560.56 -330,558.2 -340,555.84 -350,553.48 -360,551.09 -370,548.71 -380,546.31 -390,543.9 -400,541.49 -410,539.07 -420,536.63 -430,534.2 -440,531.74 -450,529.28 -460,526.82 -470,524.33 -480,521.84 -490,519.34 -500,516.83 -510,514.32 -520,511.78 -530,509.24 -540,506.69 -550,504.12 -560,501.55 -570,498.96 -580,496.37 -590,493.76 -600,491.13 -610,488.51 -620,485.85 -630,483.2 -640,480.53 -650,477.84 -660,475.15 -670,472.43 -680,469.71 -690,466.97 -700,464.22 -710,461.45 -720,458.67 -730,455.88 -740,453.06 -750,450.24 -760,447.39 -770,444.54 -780,441.66 -790,438.77 -800,435.86 -810,432.93 -820,429.99 -830,427.02 -840,424.05 -850,421.04 -860,418.04 -870,414.99 -880,411.94 -890,408.85 -900,405.76 -910,402.63 -920,399.49 -930,396.32 -940,393.14 -950,389.91 -960,386.69 -970,383.41 -980,380.13 -990,376.81 -1000,373.48 -1010,370.1 -1020,366.71 -1030,363.28 -1040,359.89 -1050,356.54 -1060,353.28 -1070,350.04 -1080,346.9 -1090,343.78 -1100,340.73 -1110,337.73 -1120,334.77 -1130,331.88 -1140,329.02 -1150,326.22 -1160,323.45 -1170,320.72 -1180,318.06 -1190,315.42 -1200,312.82 -1210,310.27 -1220,307.74 -1230,305.26 -1240,302.82 -1250,300.4 -1260,298.03 -1270,295.69 -1280,293.37 -1290,291.09 -1300,288.84 -1310,286.62 -1320,284.42 -1330,282.26 -1340,280.13 -1350,278.01 -1360,275.93 -1370,273.87 -1380,271.84 -1390,269.82 -1400,267.84 -1410,265.87 -1420,263.93 -1430,262 -1440,260.1 -1450,258.22 -1460,256.36 -1470,254.51 -1480,252.69 -1490,250.89 -1500,249.1 -1510,247.32 -1520,245.57 -1530,243.83 -1540,242.11 -1550,240.4 -1560,238.71 -1570,237.03 -1580,235.36 -1590,233.71 -1600,232.07 -1610,230.45 -1620,228.84 -1630,227.24 -1640,225.65 -1650,224.07 -1660,222.51 -1670,220.95 -1680,219.41 -1690,217.88 -1700,216.36 -1710,214.84 -1720,213.34 -1730,211.84 -1740,210.36 -1750,208.88 -1760,207.42 -1770,205.96 -1780,204.5 -1790,203.06 -1800,201.62 -1810,200.19 -1820,198.77 -1830,197.36 -1840,195.95 -1850,194.55 -1860,193.15 -1870,191.76 -1880,190.38 -1890,189 -1900,187.63 -1910,186.26 -1920,184.9 -1930,183.54 -1940,182.19 -1950,180.84 -1960,179.5 -1970,178.16 -1980,176.83 -1990,175.5 -2000,174.17 -2010,172.85 -2020,171.53 -2030,170.21 -2040,168.9 -2050,167.59 -2060,166.28 -2070,164.98 -2080,163.68 -2090,162.38 -2100,161.08 -2110,159.79 -2120,158.5 -2130,157.21 -2140,155.92 -2150,154.63 -2160,153.35 -2170,152.06 -2180,150.78 -2190,149.5 -2200,148.22 -2210,146.94 -2220,145.66 -2230,144.38 -2240,143.1 -2250,141.83 -2260,140.55 -2270,139.27 -2280,137.99 -2290,136.71 -2300,135.44 -2310,134.16 -2320,132.88 -2330,131.59 -2340,130.31 -2350,129.03 -2360,127.74 -2370,126.45 -2380,125.16 -2390,123.87 -2400,122.58 -2410,121.28 -2420,119.98 -2430,118.68 -2440,117.38 -2450,116.07 -2460,114.76 -2470,113.44 -2480,112.12 -2490,110.8 -2500,109.47 -2510,108.13 -2520,106.79 -2530,105.45 -2540,104.1 -2550,102.74 -2560,101.38 -2570,100 -2580,98.625 -2590,97.239 -2600,95.844 -2610,94.44 -2620,93.026 -2630,91.602 -2640,90.168 -2650,88.723 -2660,87.266 -2670,85.796 -2680,84.313 -2690,82.815 -2700,81.302 -2710,79.773 -2720,78.227 -2730,76.662 -2740,75.077 -2750,73.472 -2760,71.843 -2770,70.191 -2780,68.511 -2790,66.803 -2800,65.065 -2810,63.292 -2820,61.483 -2830,59.634 -2840,57.741 -2850,55.799 -2860,53.803 -2870,51.745 -2880,49.619 -2890,47.416 -2900,45.123 -2910,42.725 -2920,40.205 -2930,37.537 -2940,34.687 -2950,31.604 -2960,28.215 -2970,24.387 -2980,19.874 -2990,14.025 -3000,0 diff --git a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterpHeights.csv b/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterpHeights.csv deleted file mode 100644 index 42623accbdfa535b0646ec0c60f0cfcc1d3f23f9..0000000000000000000000000000000000000000 --- a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterpHeights.csv +++ /dev/null @@ -1,301 +0,0 @@ -0 -10 -20 -30 -40 -50 -60 -70 -80 -90 -100 -110 -120 -130 -140 -150 -160 -170 -180 -190 -200 -210 -220 -230 -240 -250 -260 -270 -280 -290 -300 -310 -320 -330 -340 -350 -360 -370 -380 -390 -400 -410 -420 -430 -440 -450 -460 -470 -480 -490 -500 -510 -520 -530 -540 -550 -560 -570 -580 -590 -600 -610 -620 -630 -640 -650 -660 -670 -680 -690 -700 -710 -720 -730 -740 -750 -760 -770 -780 -790 -800 -810 -820 -830 -840 -850 -860 -870 -880 -890 -900 -910 -920 -930 -940 -950 -960 -970 -980 -990 -1000 -1010 -1020 -1030 -1040 -1050 -1060 -1070 -1080 -1090 -1100 -1110 -1120 -1130 -1140 -1150 -1160 -1170 -1180 -1190 -1200 -1210 -1220 -1230 -1240 -1250 -1260 -1270 -1280 -1290 -1300 -1310 -1320 -1330 -1340 -1350 -1360 -1370 -1380 -1390 -1400 -1410 -1420 -1430 -1440 -1450 -1460 -1470 -1480 -1490 -1500 -1510 -1520 -1530 -1540 -1550 -1560 -1570 -1580 -1590 -1600 -1610 -1620 -1630 -1640 -1650 -1660 -1670 -1680 -1690 -1700 -1710 -1720 -1730 -1740 -1750 -1760 -1770 -1780 -1790 -1800 -1810 -1820 -1830 -1840 -1850 -1860 -1870 -1880 -1890 -1900 -1910 -1920 -1930 -1940 -1950 -1960 -1970 -1980 -1990 -2000 -2010 -2020 -2030 -2040 -2050 -2060 -2070 -2080 -2090 -2100 -2110 -2120 -2130 -2140 -2150 -2160 -2170 -2180 -2190 -2200 -2210 -2220 -2230 -2240 -2250 -2260 -2270 -2280 -2290 -2300 -2310 -2320 -2330 -2340 -2350 -2360 -2370 -2380 -2390 -2400 -2410 -2420 -2430 -2440 -2450 -2460 -2470 -2480 -2490 -2500 -2510 -2520 -2530 -2540 -2550 -2560 -2570 -2580 -2590 -2600 -2610 -2620 -2630 -2640 -2650 -2660 -2670 -2680 -2690 -2700 -2710 -2720 -2730 -2740 -2750 -2760 -2770 -2780 -2790 -2800 -2810 -2820 -2830 -2840 -2850 -2860 -2870 -2880 -2890 -2900 -2910 -2920 -2930 -2940 -2950 -2960 -2970 -2980 -2990 -3000 diff --git a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterpVelocities.csv b/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterpVelocities.csv deleted file mode 100644 index 949eadcd85f941fb498654a016332aaf8bb4c2f3..0000000000000000000000000000000000000000 --- a/data/Pyxis_Portugal_October_2022/Trajectories_CSV/referenceInterpVelocities.csv +++ /dev/null @@ -1,301 +0,0 @@ -356.06,671.63 -354.45,669.51 -352.83,667.38 -351.22,665.25 -349.62,663.12 -348.06,660.98 -346.51,658.83 -344.99,656.68 -343.5,654.53 -342.03,652.37 -340.59,650.2 -339.16,648.03 -337.75,645.85 -336.36,643.66 -334.99,641.48 -333.64,639.28 -332.3,637.08 -330.98,634.88 -329.67,632.67 -328.37,630.44 -327.09,628.22 -325.82,625.99 -324.57,623.75 -323.33,621.51 -322.09,619.26 -320.88,617 -319.66,614.74 -318.46,612.48 -317.27,610.19 -316.09,607.91 -314.92,605.63 -313.76,603.33 -312.6,601.02 -311.46,598.72 -310.32,596.4 -309.18,594.07 -308.06,591.75 -306.94,589.4 -305.83,587.05 -304.73,584.71 -303.63,582.34 -302.54,579.97 -301.45,577.6 -300.37,575.2 -299.29,572.81 -298.22,570.41 -297.16,568 -296.1,565.58 -295.05,563.16 -294,560.72 -292.95,558.28 -291.91,555.82 -290.87,553.36 -289.84,550.89 -288.81,548.41 -287.79,545.92 -286.77,543.43 -285.75,540.91 -284.74,538.39 -283.73,535.87 -282.72,533.33 -281.72,530.78 -280.72,528.22 -279.72,525.65 -278.73,523.08 -277.74,520.48 -276.75,517.88 -275.77,515.27 -274.79,512.64 -273.81,510.02 -272.83,507.36 -271.86,504.71 -270.89,502.04 -269.92,499.35 -268.95,496.66 -267.99,493.95 -267.03,491.23 -266.07,488.5 -265.11,485.75 -264.16,483 -263.2,480.22 -262.25,477.43 -261.3,474.63 -260.36,471.81 -259.41,468.99 -258.47,466.14 -257.53,463.28 -256.59,460.4 -255.65,457.51 -254.71,454.6 -253.78,451.67 -252.85,448.74 -251.91,445.77 -250.98,442.81 -250.06,439.8 -249.13,436.8 -248.2,433.76 -247.28,430.72 -246.36,427.64 -245.43,424.56 -244.51,421.45 -243.6,418.32 -242.68,415.17 -241.76,412 -240.85,408.8 -239.93,405.58 -239.02,402.35 -238.11,399.08 -237.2,395.8 -236.29,392.48 -235.38,389.14 -234.47,385.78 -233.56,382.39 -232.66,378.97 -231.75,375.52 -230.85,372.05 -229.94,368.53 -229.04,365 -228.14,361.42 -227.24,357.83 -226.34,354.19 -225.44,350.56 -224.54,346.99 -223.64,343.48 -222.74,340.02 -221.85,336.64 -220.95,333.29 -220.06,330.03 -219.16,326.81 -218.27,323.63 -217.37,320.53 -216.48,317.47 -215.58,314.47 -214.69,311.52 -213.8,308.6 -212.91,305.76 -212.02,302.95 -211.12,300.18 -210.23,297.47 -209.34,294.8 -208.45,292.17 -207.56,289.58 -206.67,287.04 -205.78,284.53 -204.89,282.06 -204,279.63 -203.11,277.23 -202.22,274.86 -201.33,272.54 -200.45,270.25 -199.56,267.98 -198.67,265.75 -197.78,263.55 -196.89,261.38 -196,259.23 -195.11,257.11 -194.22,255.03 -193.33,252.96 -192.44,250.92 -191.55,248.91 -190.66,246.91 -189.77,244.95 -188.87,243 -187.98,241.08 -187.09,239.17 -186.2,237.29 -185.3,235.42 -184.41,233.58 -183.52,231.75 -182.62,229.94 -181.73,228.15 -180.83,226.37 -179.93,224.61 -179.04,222.87 -178.14,221.14 -177.24,219.43 -176.34,217.73 -175.44,216.04 -174.54,214.37 -173.64,212.71 -172.73,211.06 -171.83,209.43 -170.92,207.81 -170.02,206.2 -169.11,204.6 -168.2,203.01 -167.29,201.43 -166.38,199.86 -165.47,198.3 -164.56,196.75 -163.64,195.21 -162.73,193.68 -161.81,192.16 -160.89,190.64 -159.97,189.14 -159.05,187.64 -158.13,186.15 -157.2,184.66 -156.28,183.19 -155.35,181.72 -154.42,180.25 -153.49,178.8 -152.55,177.35 -151.62,175.9 -150.68,174.46 -149.74,173.03 -148.79,171.6 -147.85,170.18 -146.9,168.76 -145.95,167.34 -145,165.93 -144.05,164.53 -143.09,163.13 -142.13,161.73 -141.17,160.34 -140.21,158.94 -139.24,157.56 -138.27,156.17 -137.29,154.79 -136.32,153.41 -135.34,152.04 -134.36,150.67 -133.37,149.29 -132.38,147.92 -131.39,146.56 -130.39,145.19 -129.39,143.83 -128.38,142.47 -127.37,141.1 -126.36,139.74 -125.34,138.38 -124.32,137.03 -123.3,135.67 -122.27,134.31 -121.23,132.95 -120.19,131.59 -119.15,130.23 -118.09,128.87 -117.04,127.51 -115.98,126.15 -114.91,124.79 -113.84,123.43 -112.76,122.06 -111.67,120.7 -110.58,119.33 -109.48,117.96 -108.38,116.58 -107.27,115.21 -106.15,113.83 -105.02,112.44 -103.88,111.06 -102.74,109.67 -101.59,108.27 -100.43,106.87 -99.259,105.47 -98.08,104.06 -96.891,102.64 -95.691,101.22 -94.482,99.795 -93.261,98.36 -92.028,96.918 -90.784,95.468 -89.527,94.009 -88.256,92.541 -86.973,91.064 -85.675,89.577 -84.361,88.078 -83.032,86.568 -81.687,85.045 -80.324,83.509 -78.943,81.959 -77.542,80.393 -76.122,78.811 -74.679,77.212 -73.213,75.594 -71.724,73.955 -70.208,72.295 -68.665,70.611 -67.092,68.902 -65.488,67.166 -63.849,65.399 -62.173,63.6 -60.457,61.764 -58.698,59.89 -56.891,57.973 -55.033,56.008 -53.116,53.99 -51.135,51.912 -49.082,49.766 -46.947,47.543 -44.72,45.232 -42.384,42.818 -39.921,40.282 -37.306,37.599 -34.505,34.735 -31.467,31.641 -28.118,28.241 -24.325,24.404 -19.84,19.883 -14.013,14.028 -0,0 diff --git a/data/Pyxis_Roccaraso_September_2022/Trajectories.mat b/data/Pyxis_Roccaraso_September_2022/Trajectories.mat deleted file mode 100644 index 3c1abd851f7e0c0b125d96c1d05dc3436d577274..0000000000000000000000000000000000000000 Binary files a/data/Pyxis_Roccaraso_September_2022/Trajectories.mat and /dev/null differ diff --git a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp1.csv b/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp1.csv deleted file mode 100644 index 43b75bc4031f627afab9a0c531edf12af77dac99..0000000000000000000000000000000000000000 --- a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp1.csv +++ /dev/null @@ -1,96 +0,0 @@ -0,150.63 -10,149.68 -20,148.72 -30,147.76 -40,146.8 -50,145.84 -60,144.87 -70,143.9 -80,142.93 -90,141.96 -100,140.98 -110,140 -120,139.02 -130,138.04 -140,137.05 -150,136.06 -160,135.06 -170,134.06 -180,133.06 -190,132.06 -200,131.05 -210,130.03 -220,129.02 -230,128 -240,126.97 -250,125.94 -260,124.91 -270,123.87 -280,122.83 -290,121.79 -300,120.73 -310,119.68 -320,118.62 -330,117.55 -340,116.48 -350,115.4 -360,114.32 -370,113.23 -380,112.13 -390,111.03 -400,109.92 -410,108.8 -420,107.68 -430,106.55 -440,105.41 -450,104.27 -460,103.11 -470,101.95 -480,100.78 -490,99.599 -500,98.41 -510,97.211 -520,96.001 -530,94.782 -540,93.551 -550,92.309 -560,91.055 -570,89.788 -580,88.509 -590,87.215 -600,85.908 -610,84.586 -620,83.248 -630,81.893 -640,80.521 -650,79.131 -660,77.722 -670,76.293 -680,74.842 -690,73.368 -700,71.87 -710,70.346 -720,68.795 -730,67.214 -740,65.602 -750,63.955 -760,62.272 -770,60.549 -780,58.783 -790,56.968 -800,55.103 -810,53.179 -820,51.192 -830,49.132 -840,46.991 -850,44.758 -860,42.416 -870,39.948 -880,37.328 -890,34.522 -900,31.479 -910,28.125 -920,24.329 -930,19.842 -940,14.013 -950,0 diff --git a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp10.csv b/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp10.csv deleted file mode 100644 index 03e7c59620c663604b278ef19e013de6485b434b..0000000000000000000000000000000000000000 --- a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp10.csv +++ /dev/null @@ -1,96 +0,0 @@ -0,185.6 -10,183.88 -20,182.16 -30,180.46 -40,178.77 -50,177.09 -60,175.42 -70,173.76 -80,172.11 -90,170.46 -100,168.83 -110,167.2 -120,165.58 -130,163.97 -140,162.36 -150,160.76 -160,159.17 -170,157.58 -180,156 -190,154.43 -200,152.86 -210,151.29 -220,149.73 -230,148.18 -240,146.63 -250,145.08 -260,143.54 -270,142 -280,140.47 -290,138.94 -300,137.41 -310,135.88 -320,134.36 -330,132.84 -340,131.32 -350,129.8 -360,128.28 -370,126.77 -380,125.25 -390,123.74 -400,122.22 -410,120.71 -420,119.2 -430,117.68 -440,116.17 -450,114.65 -460,113.13 -470,111.61 -480,110.09 -490,108.57 -500,107.04 -510,105.51 -520,103.98 -530,102.44 -540,100.89 -550,99.344 -560,97.79 -570,96.23 -580,94.662 -590,93.088 -600,91.505 -610,89.913 -620,88.312 -630,86.701 -640,85.078 -650,83.444 -660,81.796 -670,80.134 -680,78.457 -690,76.763 -700,75.05 -710,73.319 -720,71.566 -730,69.789 -740,67.987 -750,66.158 -760,64.298 -770,62.404 -780,60.474 -790,58.502 -800,56.485 -810,54.416 -820,52.29 -830,50.099 -840,47.833 -850,45.481 -860,43.029 -870,40.457 -880,37.741 -890,34.846 -900,31.724 -910,28.299 -920,24.44 -930,19.901 -940,14.033 -950,0 diff --git a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp11.csv b/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp11.csv deleted file mode 100644 index 03e7c59620c663604b278ef19e013de6485b434b..0000000000000000000000000000000000000000 --- a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp11.csv +++ /dev/null @@ -1,96 +0,0 @@ -0,185.6 -10,183.88 -20,182.16 -30,180.46 -40,178.77 -50,177.09 -60,175.42 -70,173.76 -80,172.11 -90,170.46 -100,168.83 -110,167.2 -120,165.58 -130,163.97 -140,162.36 -150,160.76 -160,159.17 -170,157.58 -180,156 -190,154.43 -200,152.86 -210,151.29 -220,149.73 -230,148.18 -240,146.63 -250,145.08 -260,143.54 -270,142 -280,140.47 -290,138.94 -300,137.41 -310,135.88 -320,134.36 -330,132.84 -340,131.32 -350,129.8 -360,128.28 -370,126.77 -380,125.25 -390,123.74 -400,122.22 -410,120.71 -420,119.2 -430,117.68 -440,116.17 -450,114.65 -460,113.13 -470,111.61 -480,110.09 -490,108.57 -500,107.04 -510,105.51 -520,103.98 -530,102.44 -540,100.89 -550,99.344 -560,97.79 -570,96.23 -580,94.662 -590,93.088 -600,91.505 -610,89.913 -620,88.312 -630,86.701 -640,85.078 -650,83.444 -660,81.796 -670,80.134 -680,78.457 -690,76.763 -700,75.05 -710,73.319 -720,71.566 -730,69.789 -740,67.987 -750,66.158 -760,64.298 -770,62.404 -780,60.474 -790,58.502 -800,56.485 -810,54.416 -820,52.29 -830,50.099 -840,47.833 -850,45.481 -860,43.029 -870,40.457 -880,37.741 -890,34.846 -900,31.724 -910,28.299 -920,24.44 -930,19.901 -940,14.033 -950,0 diff --git a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp2.csv b/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp2.csv deleted file mode 100644 index 7ee4ffbc1e236bac86846b7c122a0e09c7ea0f1c..0000000000000000000000000000000000000000 --- a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp2.csv +++ /dev/null @@ -1,96 +0,0 @@ -0,152.92 -10,151.92 -20,150.92 -30,149.92 -40,148.92 -50,147.91 -60,146.9 -70,145.89 -80,144.88 -90,143.86 -100,142.85 -110,141.83 -120,140.81 -130,139.78 -140,138.76 -150,137.73 -160,136.69 -170,135.66 -180,134.62 -190,133.58 -200,132.54 -210,131.49 -220,130.44 -230,129.38 -240,128.32 -250,127.26 -260,126.2 -270,125.13 -280,124.05 -290,122.97 -300,121.89 -310,120.8 -320,119.71 -330,118.61 -340,117.51 -350,116.4 -360,115.29 -370,114.17 -380,113.05 -390,111.92 -400,110.78 -410,109.64 -420,108.49 -430,107.33 -440,106.17 -450,105 -460,103.82 -470,102.63 -480,101.44 -490,100.24 -500,99.024 -510,97.802 -520,96.57 -530,95.328 -540,94.076 -550,92.812 -560,91.537 -570,90.25 -580,88.95 -590,87.638 -600,86.311 -610,84.969 -620,83.613 -630,82.24 -640,80.851 -650,79.443 -660,78.017 -670,76.571 -680,75.104 -690,73.614 -700,72.101 -710,70.562 -720,68.996 -730,67.402 -740,65.775 -750,64.116 -760,62.42 -770,60.684 -780,58.906 -790,57.081 -800,55.204 -810,53.27 -820,51.272 -830,49.203 -840,47.053 -850,44.811 -860,42.461 -870,39.985 -880,37.358 -890,34.546 -900,31.497 -910,28.138 -920,24.337 -930,19.846 -940,14.014 -950,0 diff --git a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp3.csv b/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp3.csv deleted file mode 100644 index a9be4708d682380a298a48510c9208ca9666d149..0000000000000000000000000000000000000000 --- a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp3.csv +++ /dev/null @@ -1,96 +0,0 @@ -0,155.53 -10,154.48 -20,153.43 -30,152.37 -40,151.32 -50,150.27 -60,149.21 -70,148.15 -80,147.09 -90,146.03 -100,144.97 -110,143.9 -120,142.84 -130,141.77 -140,140.7 -150,139.62 -160,138.55 -170,137.47 -180,136.39 -190,135.31 -200,134.22 -210,133.14 -220,132.04 -230,130.95 -240,129.85 -250,128.75 -260,127.65 -270,126.54 -280,125.43 -290,124.32 -300,123.2 -310,122.08 -320,120.95 -330,119.82 -340,118.68 -350,117.54 -360,116.4 -370,115.25 -380,114.09 -390,112.93 -400,111.76 -410,110.59 -420,109.41 -430,108.22 -440,107.03 -450,105.83 -460,104.62 -470,103.41 -480,102.19 -490,100.96 -500,99.717 -510,98.469 -520,97.212 -530,95.945 -540,94.668 -550,93.38 -560,92.081 -570,90.771 -580,89.449 -590,88.113 -600,86.764 -610,85.402 -620,84.024 -630,82.631 -640,81.222 -650,79.794 -660,78.349 -670,76.884 -680,75.399 -690,73.892 -700,72.361 -710,70.806 -720,69.223 -730,67.613 -740,65.971 -750,64.297 -760,62.586 -770,60.837 -780,59.046 -790,57.207 -800,55.318 -810,53.372 -820,51.363 -830,49.283 -840,47.123 -850,44.871 -860,42.512 -870,40.027 -880,37.392 -890,34.572 -900,31.518 -910,28.153 -920,24.346 -930,19.851 -940,14.016 -950,0 diff --git a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp4.csv b/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp4.csv deleted file mode 100644 index 820dd8270b0adadefc6f89191698e528a3f81910..0000000000000000000000000000000000000000 --- a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp4.csv +++ /dev/null @@ -1,96 +0,0 @@ -0,158.48 -10,157.37 -20,156.26 -30,155.15 -40,154.04 -50,152.93 -60,151.82 -70,150.7 -80,149.59 -90,148.48 -100,147.36 -110,146.24 -120,145.12 -130,144.01 -140,142.88 -150,141.76 -160,140.64 -170,139.51 -180,138.38 -190,137.25 -200,136.12 -210,134.99 -220,133.85 -230,132.71 -240,131.57 -250,130.43 -260,129.28 -270,128.13 -280,126.98 -290,125.83 -300,124.67 -310,123.5 -320,122.34 -330,121.17 -340,119.99 -350,118.82 -360,117.63 -370,116.45 -380,115.25 -390,114.06 -400,112.85 -410,111.65 -420,110.43 -430,109.21 -440,107.99 -450,106.76 -460,105.52 -470,104.27 -480,103.02 -490,101.76 -500,100.49 -510,99.214 -520,97.928 -530,96.633 -540,95.329 -550,94.014 -560,92.689 -570,91.352 -580,90.004 -590,88.644 -600,87.271 -610,85.884 -620,84.483 -630,83.067 -640,81.635 -650,80.186 -660,78.719 -670,77.234 -680,75.728 -690,74.201 -700,72.651 -710,71.077 -720,69.476 -730,67.848 -740,66.189 -750,64.498 -760,62.772 -770,61.007 -780,59.201 -790,57.348 -800,55.445 -810,53.486 -820,51.464 -830,49.372 -840,47.2 -850,44.938 -860,42.568 -870,40.074 -880,37.43 -890,34.602 -900,31.54 -910,28.169 -920,24.357 -930,19.856 -940,14.018 -950,0 diff --git a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp5.csv b/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp5.csv deleted file mode 100644 index 587b905bf83e089b730ca14dc93880143d171d39..0000000000000000000000000000000000000000 --- a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp5.csv +++ /dev/null @@ -1,96 +0,0 @@ -0,161.81 -10,160.63 -20,159.46 -30,158.28 -40,157.1 -50,155.93 -60,154.75 -70,153.57 -80,152.4 -90,151.22 -100,150.05 -110,148.87 -120,147.69 -130,146.51 -140,145.34 -150,144.16 -160,142.98 -170,141.8 -180,140.61 -190,139.43 -200,138.25 -210,137.06 -220,135.87 -230,134.69 -240,133.5 -250,132.3 -260,131.11 -270,129.91 -280,128.71 -290,127.51 -300,126.3 -310,125.1 -320,123.89 -330,122.67 -340,121.46 -350,120.24 -360,119.01 -370,117.78 -380,116.55 -390,115.31 -400,114.07 -410,112.83 -420,111.57 -430,110.32 -440,109.06 -450,107.79 -460,106.51 -470,105.23 -480,103.95 -490,102.65 -500,101.35 -510,100.04 -520,98.723 -530,97.396 -540,96.061 -550,94.716 -560,93.361 -570,91.996 -580,90.619 -590,89.232 -600,87.831 -610,86.418 -620,84.991 -630,83.549 -640,82.092 -650,80.619 -660,79.129 -670,77.62 -680,76.092 -690,74.543 -700,72.972 -710,71.376 -720,69.756 -730,68.108 -740,66.43 -750,64.721 -760,62.976 -770,61.195 -780,59.371 -790,57.503 -800,55.585 -810,53.611 -820,51.575 -830,49.47 -840,47.286 -850,45.011 -860,42.63 -870,40.126 -880,37.472 -890,34.635 -900,31.565 -910,28.186 -920,24.368 -930,19.862 -940,14.02 -950,0 diff --git a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp6.csv b/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp6.csv deleted file mode 100644 index 0519c7bccf2b351ffab84f7a2970548119ef7d18..0000000000000000000000000000000000000000 --- a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp6.csv +++ /dev/null @@ -1,96 +0,0 @@ -0,165.55 -10,164.3 -20,163.04 -30,161.79 -40,160.53 -50,159.28 -60,158.03 -70,156.79 -80,155.54 -90,154.29 -100,153.05 -110,151.8 -120,150.56 -130,149.31 -140,148.07 -150,146.83 -160,145.59 -170,144.34 -180,143.1 -190,141.86 -200,140.61 -210,139.37 -220,138.12 -230,136.88 -240,135.63 -250,134.38 -260,133.13 -270,131.88 -280,130.63 -290,129.38 -300,128.12 -310,126.86 -320,125.6 -330,124.34 -340,123.07 -350,121.81 -360,120.54 -370,119.26 -380,117.98 -390,116.7 -400,115.42 -410,114.13 -420,112.83 -430,111.54 -440,110.23 -450,108.93 -460,107.61 -470,106.29 -480,104.97 -490,103.64 -500,102.3 -510,100.95 -520,99.598 -530,98.237 -540,96.867 -550,95.489 -560,94.101 -570,92.704 -580,91.296 -590,89.877 -600,88.447 -610,87.004 -620,85.548 -630,84.078 -640,82.594 -650,81.094 -660,79.578 -670,78.043 -680,76.491 -690,74.917 -700,73.322 -710,71.705 -720,70.062 -730,68.392 -740,66.694 -750,64.964 -760,63.201 -770,61.4 -780,59.558 -790,57.673 -800,55.738 -810,53.748 -820,51.697 -830,49.577 -840,47.379 -850,45.091 -860,42.698 -870,40.182 -880,37.518 -890,34.671 -900,31.592 -910,28.206 -920,24.38 -930,19.869 -940,14.022 -950,0 diff --git a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp7.csv b/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp7.csv deleted file mode 100644 index f3354e0139bd8f2e79c9d6d09975832369e5da8e..0000000000000000000000000000000000000000 --- a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp7.csv +++ /dev/null @@ -1,96 +0,0 @@ -0,169.75 -10,168.4 -20,167.05 -30,165.71 -40,164.37 -50,163.03 -60,161.7 -70,160.37 -80,159.04 -90,157.72 -100,156.39 -110,155.07 -120,153.75 -130,152.43 -140,151.11 -150,149.8 -160,148.48 -170,147.17 -180,145.86 -190,144.55 -200,143.23 -210,141.92 -220,140.61 -230,139.3 -240,137.99 -250,136.68 -260,135.37 -270,134.06 -280,132.75 -290,131.44 -300,130.13 -310,128.81 -320,127.5 -330,126.18 -340,124.86 -350,123.54 -360,122.22 -370,120.89 -380,119.56 -390,118.23 -400,116.9 -410,115.56 -420,114.22 -430,112.88 -440,111.53 -450,110.17 -460,108.82 -470,107.45 -480,106.09 -490,104.71 -500,103.33 -510,101.95 -520,100.56 -530,99.158 -540,97.75 -550,96.335 -560,94.912 -570,93.479 -580,92.036 -590,90.584 -600,89.12 -610,87.645 -620,86.157 -630,84.657 -640,83.142 -650,81.613 -660,80.068 -670,78.505 -680,76.925 -690,75.326 -700,73.705 -710,72.062 -720,70.395 -730,68.702 -740,66.981 -750,65.229 -760,63.445 -770,61.623 -780,59.762 -790,57.857 -800,55.904 -810,53.897 -820,51.829 -830,49.694 -840,47.481 -850,45.178 -860,42.772 -870,40.244 -880,37.568 -890,34.71 -900,31.622 -910,28.226 -920,24.394 -930,19.876 -940,14.025 -950,0 diff --git a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp8.csv b/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp8.csv deleted file mode 100644 index 9116c55adc2caf7a5dae4686b27707e4c53a28cb..0000000000000000000000000000000000000000 --- a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp8.csv +++ /dev/null @@ -1,96 +0,0 @@ -0,174.44 -10,172.99 -20,171.54 -30,170.09 -40,168.65 -50,167.22 -60,165.79 -70,164.36 -80,162.94 -90,161.52 -100,160.11 -110,158.7 -120,157.29 -130,155.89 -140,154.49 -150,153.09 -160,151.69 -170,150.3 -180,148.91 -190,147.52 -200,146.13 -210,144.75 -220,143.37 -230,141.98 -240,140.6 -250,139.22 -260,137.84 -270,136.47 -280,135.09 -290,133.71 -300,132.33 -310,130.96 -320,129.58 -330,128.2 -340,126.82 -350,125.44 -360,124.06 -370,122.68 -380,121.29 -390,119.91 -400,118.52 -410,117.13 -420,115.74 -430,114.34 -440,112.94 -450,111.54 -460,110.14 -470,108.73 -480,107.31 -490,105.89 -500,104.47 -510,103.04 -520,101.6 -530,100.16 -540,98.713 -550,97.258 -560,95.794 -570,94.323 -580,92.842 -590,91.353 -600,89.853 -610,88.342 -620,86.82 -630,85.286 -640,83.738 -650,82.177 -660,80.6 -670,79.007 -680,77.397 -690,75.769 -700,74.12 -710,72.45 -720,70.756 -730,69.038 -740,67.292 -750,65.516 -760,63.708 -770,61.864 -780,59.982 -790,58.057 -800,56.084 -810,54.058 -820,51.972 -830,49.819 -840,47.59 -850,45.272 -860,42.852 -870,40.31 -880,37.622 -890,34.753 -900,31.653 -910,28.249 -920,24.408 -930,19.884 -940,14.027 -950,0 diff --git a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp9.csv b/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp9.csv deleted file mode 100644 index 7df13ed356837b81abc6c913fb0adea0df5fef9b..0000000000000000000000000000000000000000 --- a/data/Pyxis_Roccaraso_September_2022/Trajectories_CSV/referenceInterp9.csv +++ /dev/null @@ -1,96 +0,0 @@ -0,179.7 -10,178.12 -20,176.55 -30,174.99 -40,173.43 -50,171.89 -60,170.35 -70,168.81 -80,167.28 -90,165.76 -100,164.24 -110,162.73 -120,161.22 -130,159.72 -140,158.22 -150,156.73 -160,155.24 -170,153.76 -180,152.28 -190,150.81 -200,149.33 -210,147.86 -220,146.4 -230,144.93 -240,143.47 -250,142.02 -260,140.56 -270,139.11 -280,137.65 -290,136.2 -300,134.75 -310,133.31 -320,131.86 -330,130.41 -340,128.97 -350,127.52 -360,126.08 -370,124.63 -380,123.19 -390,121.74 -400,120.29 -410,118.84 -420,117.39 -430,115.94 -440,114.49 -450,113.03 -460,111.57 -470,110.11 -480,108.64 -490,107.18 -500,105.7 -510,104.22 -520,102.74 -530,101.25 -540,99.76 -550,98.26 -560,96.753 -570,95.239 -580,93.717 -590,92.186 -600,90.647 -610,89.098 -620,87.537 -630,85.966 -640,84.383 -650,82.786 -660,81.175 -670,79.55 -680,77.907 -690,76.247 -700,74.568 -710,72.868 -720,71.146 -730,69.4 -740,67.627 -750,65.826 -760,63.992 -770,62.125 -780,60.219 -790,58.272 -800,56.277 -810,54.231 -820,52.126 -830,49.955 -840,47.708 -850,45.373 -860,42.938 -870,40.381 -880,37.679 -890,34.798 -900,31.687 -910,28.273 -920,24.424 -930,19.892 -940,14.03 -950,0 diff --git a/simulator/configs/configControl.m b/simulator/configs/configControl.m index 7662ce90d74c8f3a01ce979ff4aeacfc94bc7188..c34c9b2b06c054aaa49fb64550877f41f9852682 100644 --- a/simulator/configs/configControl.m +++ b/simulator/configs/configControl.m @@ -11,7 +11,7 @@ All the parameters are stored in the "contSetting" structure. %} %% LOAD CD COEFFICIENTS -data = load(strcat(dataPath, '/CAinterpCoeffs')); +data = load(strcat(mission.dataPath, '/CAinterpCoeffs')); contSettings.coeff_Cd = data.coeffs; %% CONTROL PARAMETERS @@ -41,8 +41,8 @@ contSettings.alpha_degree_prec = 0; contSettings.iteration_flag = 1; contSettings.saturation = false; -contSettings.g = settings.g0; -contSettings.D = settings.C; +contSettings.g = environment.g0; +contSettings.D = rocket.diameter; contSettings.S0 = (pi*contSettings.D^2)/4; % Parameters for the function get extension from angle @@ -56,7 +56,7 @@ contSettings.filter_coeff = 0.5; % se % delay from motor shutdown to air brakes opening: contSettings.ABK_shutdown_delay = 0.5; % [s] time between engine shutdown command and ABK phase -if contains(settings.mission, "Roccaraso") +if contains(mission.name, "Roccaraso") contSettings.ABK_shadowmode = 1.5; % [s] else contSettings.ABK_shadowmode = 3.8; % [s] @@ -116,4 +116,8 @@ contSettings.WES.N = 0; contSettings.WES.state = 1; %% MEA and shutdown -contSettings.N_prediction_threshold = 5; \ No newline at end of file +contSettings.N_prediction_threshold = 5; + +%% Identification settings for algorithms +rocket.airbrakes.identification = settings.identification; +rocket.parachutes(2,2).controlParams.identification = settings.identification; \ No newline at end of file diff --git a/simulator/configs/configControlParams.m b/simulator/configs/configControlParams.m index ba75191fc7ef6303a302f303b222730e834dc543..760c18aae6cb1bce1c7d48139d42b0faa432fef9 100644 --- a/simulator/configs/configControlParams.m +++ b/simulator/configs/configControlParams.m @@ -5,9 +5,9 @@ %} % Possible range of values for the control variable -switch settings.mission +switch mission.name - case 'Lynx_Portugal_October_2021' + case '2021_Lynx_Portugal_October' contSettings.delta_S_available = (0.0:0.001/4:0.01017)'; contSettings.filter_coeff0 = 0.9; % starting value, then linear decrease until max Altitude @@ -19,11 +19,11 @@ switch settings.mission settings.stopPitotAltitude = 2800; settings.CD_correction = 1; % set to 1 if you want to use CD from DATCOM in the simulation (and also in the accelerometer ascent), otherwise multiplies CD (only CD, not the others) for it - case 'Lynx_Roccaraso_September_2021' + case '2021_Lynx_Roccaraso_September' contSettings.delta_S_available = (0.0:0.001/4:0.01017)'; - case 'Pyxis_Portugal_October_2022' + case '2022_Pyxis_Portugal_October' % only for PID contSettings.delta_S_available = (0.0:0.001/4:settings.arb.surfPol*settings.servo.maxAngle)'; @@ -41,7 +41,7 @@ switch settings.mission settings.stopPitotAltitude = 2800; settings.CD_correction = 1; % set to 1 if you want to use CD from DATCOM in the simulation (and also in the accelerometer ascent), otherwise multiplies CD (only CD, not the others) for it - case 'Pyxis_Roccaraso_September_2022' + case '2022_Pyxis_Roccaraso_September' contSettings.delta_S_available = (0.0:0.001/4:settings.arb.surfPol*settings.servo.maxAngle)'; @@ -64,7 +64,7 @@ switch settings.mission settings.stopPitotAltitude = 800; settings.CD_correction = 1; % set to 1 if you want to use CD from DATCOM in the simulation (and also in the accelerometer ascent), otherwise multiplies CD (only CD, not the others) for it - case 'Gemini_Portugal_October_2023' + case '2023_Gemini_Portugal_October' contSettings.traj_choice = 1; % if 1 performs trajectory choice, if zero it doesn't N_mass = 11; % number of references to generate @@ -98,7 +98,7 @@ switch settings.mission settings.CD_correction = 1; % set to 1 if you want to use CD from DATCOM in the simulation (and also in the accelerometer ascent), otherwise multiplies CD (only CD, not the others) for it - case 'Gemini_Roccaraso_September_2023' + case '2023_Gemini_Roccaraso_September' contSettings.traj_choice = 1; % if 1 performs trajectory choice, if zero it doesn't N_mass = 11; % number of references to generate @@ -131,7 +131,7 @@ switch settings.mission settings.CD_correction = 0.80; % set to 1 if you want to use CD from DATCOM in the simulation (and also in the accelerometer ascent), otherwise multiplies CD (only CD, not the others) for it - case 'Lyra_Portugal_October_2024' + case '2024_Lyra_Portugal_October' contSettings.traj_choice = 1; % if 1 performs trajectory choice, if zero it doesn't N_mass = 11; % number of references to generate @@ -165,7 +165,7 @@ switch settings.mission settings.CD_correction = 1; % set to 1 if you want to use CD from DATCOM in the simulation (and also in the accelerometer ascent), otherwise multiplies CD (only CD, not the others) for it - case 'Lyra_Roccaraso_September_2024' + case '2024_Lyra_Roccaraso_September' contSettings.traj_choice = 1; % if 1 performs trajectory choice, if zero it doesn't N_mass = 11; % number of references to generate diff --git a/simulator/configs/configFlags.m b/simulator/configs/configFlags.m index f9876bef89a08a603c53f3e19d3a96a276f5aced..1f0f3bb519739cc1a4bc3c64decfc2371175b91e 100644 --- a/simulator/configs/configFlags.m +++ b/simulator/configs/configFlags.m @@ -27,7 +27,7 @@ scenarios explanation: % scenario configuration -conf.scenario = "controlled ascent"; +conf.scenario = "full flight"; conf.board = "main"; % Either "main" or "payload" conf.HIL = false; @@ -177,7 +177,7 @@ settings.scenario = conf.scenario; %% %% uncomment when the MSA toolkit is updated -% if settings.mission == 'NewRocket_2023' +% if mission.name == 'NewRocket_2023' % settings.HRE = true; % else % settings.HRE = false; diff --git a/simulator/configs/configMission.m b/simulator/configs/configMission.m index d3f2a7b59f17823af6406cbb0eee85af869847b4..d4ae76b5624ea576dff695dd27635265bbcbdd3c 100644 --- a/simulator/configs/configMission.m +++ b/simulator/configs/configMission.m @@ -14,12 +14,12 @@ switch conf.year switch conf.flight case "roccaraso" - settings.mission = 'Lynx_Roccaraso_September_2021'; - settings.missionMSA = '2021_Lynx_Roccaraso_September'; + mission.name = 'Lynx_Roccaraso_September_2021'; + mission.nameMSA = '2021_Lynx_Roccaraso_September'; case "pds" - settings.mission = 'Lynx_Portugal_October_2021'; - settings.missionMSA = '2021_Lynx_Portugal_October'; + mission.name = 'Lynx_Portugal_October_2021'; + mission.nameMSA = '2021_Lynx_Portugal_October'; end case 2022 @@ -27,12 +27,12 @@ switch conf.year switch conf.flight case "roccaraso" - settings.mission = 'Pyxis_Roccaraso_September_2022'; - settings.missionMSA = '2022_Pyxis_Roccaraso_September'; + mission.name = 'Pyxis_Roccaraso_September_2022'; + mission.nameMSA = '2022_Pyxis_Roccaraso_September'; case "pds" - settings.mission = 'Pyxis_Portugal_October_2022'; - settings.missionMSA = '2022_Pyxis_Portugal_October'; + mission.name = 'Pyxis_Portugal_October_2022'; + mission.nameMSA = '2022_Pyxis_Portugal_October'; end @@ -41,12 +41,12 @@ switch conf.year switch conf.flight case "roccaraso" - settings.mission = 'Gemini_Roccaraso_September_2023'; - settings.missionMSA = '2023_Gemini_Roccaraso_September'; + mission.name = 'Gemini_Roccaraso_September_2023'; + mission.nameMSA = '2023_Gemini_Roccaraso_September'; case "pds" - settings.mission = 'Gemini_Portugal_October_2023'; - settings.missionMSA = '2023_Gemini_Portugal_October'; + mission.name = 'Gemini_Portugal_October_2023'; + mission.nameMSA = '2023_Gemini_Portugal_October'; end @@ -55,12 +55,12 @@ switch conf.year switch conf.flight case "roccaraso" - settings.mission = 'Lyra_Roccaraso_September_2024'; - settings.missionMSA = '2024_Lyra_Roccaraso_September'; + mission.name = 'Lyra_Roccaraso_September_2024'; + mission.nameMSA = '2024_Lyra_Roccaraso_September'; case "pds" - settings.mission = 'Lyra_Portugal_October_2024'; - settings.missionMSA = '2024_Lyra_Portugal_October'; + mission.name = 'Lyra_Portugal_October_2024'; + mission.nameMSA = '2024_Lyra_Portugal_October'; end end diff --git a/simulator/configs/configMontecarlo.m b/simulator/configs/configMontecarlo.m index 088998c2ec41603ca110d14d4d6cdbca9756eab3..5c63b169552e3f3ca29a9a7dc9bbfd9076c4a6e9 100644 --- a/simulator/configs/configMontecarlo.m +++ b/simulator/configs/configMontecarlo.m @@ -14,7 +14,7 @@ if settings.montecarlo %% %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% settable parameters %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% % how many simulations -N_sim = 10; % set to at least 500 +N_sim = 16; % set to at least 500 simulationType_thrust = "gaussian"; % "gaussian", "exterme" displayIter = true; % set to false if you don't want to see the iteration number (maybe if you want to run Montecarlos on hpe) @@ -35,7 +35,7 @@ displayIter = true; % set to false if you don't want to see the iteration number mu_t = 1; % thrust_percentage mean value thrust_percentage = normrnd(mu_t,sigma_t,N_sim,1); %generate normally distributed values ( [0.8 1.20] = 3sigma) % serve il toolbox - stoch.thrust = thrust_percentage*settings.motor.expThrust; % thrust - the notation used creates a matrix where each row is the expThrust multiplied by one coefficient in the thrust percentage array + stoch.thrust = thrust_percentage*rocket.motor.thrust; % thrust - the notation used creates a matrix where each row is the expThrust multiplied by one coefficient in the thrust percentage array %%% in questo modo però il burning time rimane fissato perchè è @@ -49,10 +49,32 @@ displayIter = true; % set to false if you don't want to see the iteration number stoch.delta_Kt = normrnd(mu_Kt, sigma_Kt, N_sim, 1); impulse_uncertainty = normrnd(1,0.05/3,N_sim,1); - stoch.expThrust = diag(impulse_uncertainty)*((1./thrust_percentage) * settings.motor.expTime); % burning time - same notation as thrust here + stoch.expTime = diag(impulse_uncertainty)*((1./thrust_percentage) * rocket.motor.time); % burning time - same notation as thrust here + + for ii = 1:N_sim + if stoch.expTime(ii, end) <= rocket.motor.time(end) + continue + end + expTime = stoch.expTime(ii, stoch.expTime(ii, :) <= rocket.motor.time(end)); + time_diff = diff(expTime); + k = length(rocket.motor.time) - length(expTime); + [max_val, max_pos] = maxk(time_diff, k); + max_pos = sort(max_pos); + + newTimes = expTime(max_pos) + (expTime(max_pos+1) - expTime(max_pos))/2; + padTime = paddata(expTime, length(expTime) + k); + + for jj = 1:k + padTime(max_pos(jj)+1:end) = [newTimes(jj) padTime(max_pos(jj)+1:end-1)]; + max_pos = max_pos+1; + end + + stoch.expTime(ii, :) = padTime; + end + %%% for i =1:N_sim - stoch.State.xcgTime(:,i) = settings.State.xcgTime/settings.tb .* stoch.expThrust(i,end); % Xcg time + stoch.State.xcgTime(:,i) = rocket.coefficients.state.xcgTime/rocket.motor.time(end) .* stoch.expTime(i,end); % Xcg time end %%% Aero coefficients uncertainty @@ -62,19 +84,53 @@ displayIter = true; % set to false if you don't want to see the iteration number stoch.aer_percentage = normrnd(mu_aer,sigma_aer,N_sim,1); %%% wind parameters - settings.wind.MagMin = 0; % [m/s] Minimum Wind Magnitude - settings.wind.MagMax = 10; % [m/s] Maximum Wind Magnitude - settings.wind.ElMin = - deg2rad(5); - settings.wind.ElMax = + deg2rad(5); - settings.wind.AzMin = + deg2rad(0); - settings.wind.AzMax = + deg2rad(360); - - switch settings.windModel - case "constant" - [stoch.wind.uw, stoch.wind.vw, stoch.wind.ww, stoch.wind.Az, stoch.wind.El ] = windConstGeneratorMontecarlo(settings.wind,N_sim,simulationType_thrust); - case "multiplicative" - [stoch.wind.Mag,stoch.wind.Az,stoch.wind.unc] = windMultGeneratorMontecarlo(settings.wind,N_sim); + stoch.wind_params.altitudes = [0 3000]; + stoch.wind_params.MagMin = [0 2]; % [m/s] Minimum Wind Magnitude + stoch.wind_params.MagMax = [10 4]; % [m/s] Maximum Wind Magnitude + stoch.wind_params.MagType = "u"; + stoch.wind_params.ElMin = - deg2rad([5 5]); + stoch.wind_params.ElMax = + deg2rad([5 5]); + stoch.wind_params.ElType = "g"; + stoch.wind_params.AzMin = + deg2rad([0 0]); + stoch.wind_params.AzMax = + deg2rad([360 360]); + stoch.wind_params.AzType = "u"; + + wind = WindCustom(mission); + + wind.altitudes = stoch.wind_params.altitudes; + switch stoch.wind_params.MagType + case "u" + wind.magnitudeDistribution = repmat("u", size(wind.altitudes)); + wind.magnitudeParameters = [stoch.wind_params.MagMin; stoch.wind_params.MagMax]; + case "g" + mu_Mag = (stoch.wind_params.MagMax + stoch.wind_params.MagMin) / 2; + sigma_Mag = (stoch.wind_params.MagMax - mu_Mag)/3; + wind.magnitudeDistribution = repmat("g", size(wind.altitudes)); + wind.magnitudeParameters = [mu_Mag; sigma_Mag]; end + switch stoch.wind_params.ElType + case "u" + wind.elevationDistribution = repmat("u", size(wind.altitudes)); + wind.elevationParameters = [stoch.wind_params.ElMin; stoch.wind_params.ElMax]; + case "g" + mu_El = (stoch.wind_params.ElMax + stoch.wind_params.ElMin) / 2; + sigma_El = (stoch.wind_params.ElMax - mu_El)/3; + wind.elevationDistribution = repmat("g", size(wind.altitudes)); + wind.elevationParameters = [mu_El; sigma_El]; + end + switch stoch.wind_params.AzType + case "u" + wind.azimuthDistribution = repmat("u", size(wind.altitudes)); + wind.azimuthParameters = [stoch.wind_params.AzMin; stoch.wind_params.AzMax]; + case "g" + mu_Az = (stoch.wind_params.AzMax + stoch.wind_params.AzMin) / 2; + sigma_Az = (stoch.wind_params.AzMax - mu_Az)/3; + wind.magnitudeDistribution = repmat("g", size(wind.altitudes)); + wind.magnitudeParameters = [mu_Az; sigma_Az]; + end + + wind.updateAll(); + stoch.wind = wind; %%% mass offset distribution sigma_m = 1/3; % 1 [kg] of offset (uncertainty on refueling mass) @@ -84,25 +140,72 @@ displayIter = true; % set to false if you don't want to see the iteration number % launch rail orientation sigma_om = 2/3 *pi/180; % 2 [deg] of offset (uncertainty on ramp elevation angle) - mu_om = settings.OMEGA; + mu_om = environment.omega; stoch.OMEGA_rail = normrnd(mu_om,sigma_om,N_sim,1); % launch rail orientation sigma_phi = 5/3 *pi/180; % 2 [deg]of offset (uncertainty on ramp azimuth angle) - mu_phi = settings.PHI; + mu_phi = environment.phi; stoch.PHI_rail = normrnd(mu_phi,sigma_phi,N_sim,1); case "extreme" thrust_percentage = [0.9;1.1]; % this is overwritten in the next step, but it sets the values to retrieve in the parameter generation + Az_vec = deg2rad([-180 -90 0 90]); + El_vec = deg2rad([-60 60]); + + [A,B,C] = meshgrid(Az_vec,El_vec,thrust_percentage); + Az = []; + El = []; + thrust_percentage = []; + for i = 1:size(A,1) + for j = 1:size(A,2) + for k = 1:size(A,3) + Az = [Az; A(i,j,k)]; + El = [El; B(i,j,k)]; + thrust_percentage = [thrust_percentage; C(i,j,k)]; + end + end + end - %%% wind parameters - [stoch.wind.uw, stoch.wind.vw, stoch.wind.ww, stoch.wind.Az, stoch.wind.El ,thrust_percentage, N_sim] = windConstGeneratorMontecarlo(settings.wind,N_sim,simulationType_thrust,thrust_percentage); + N_sim = length(Az); - stoch.thrust = thrust_percentage*settings.motor.expThrust; % thrust - the notation used creates a matrix where each row is the expThrust multiplied by one coefficient in the thrust percentage array - %%% - stoch.expThrust = (1./thrust_percentage) * settings.motor.expTime; % burning time - same notation as thrust here + wind = WindCustom(mission); + wind.altitudes = 0; + wind.magnitudeDistribution = "u"; + wind.azimuthDistribution = "u"; + wind.elevationDistribution = "u"; + wind.magnitudeParameters = 5; + + wind_vec = cell(N_sim, 1); + + for ii = 1:N_sim + wind_vec{ii} = copy(wind); + wind_vec{ii}.azimuthParameters = Az(ii); + wind_vec{ii}.elevationParameters = El(ii); + wind_vec{ii}.updateAll(); + end + + stoch.thrust = thrust_percentage*rocket.motor.thrust; % thrust - the notation used creates a matrix where each row is the expThrust multiplied by one coefficient in the thrust percentage array + stoch.expTime = (1./thrust_percentage) * rocket.motor.time; % burning time - same notation as thrust here + stoch.delta_Kt = zeros(N_sim, 1); + + for i =1:N_sim + stoch.State.xcgTime(:,i) = rocket.coefficients.state.xcgTime/rocket.motor.time(end) .* stoch.expTime(i,end); % Xcg time + end + + % aero coeffs + stoch.aer_percentage = zeros(N_sim,1); + + % mass offset distribution + stoch.mass_offset = zeros(N_sim, 1); + + % launch rail orientation + stoch.OMEGA_rail = ones(N_sim,1) .* environment.omega; + + % launch rail orientation + stoch.PHI_rail = ones(N_sim,1) .* environment.phi; end @@ -116,10 +219,10 @@ displayIter = true; % set to false if you don't want to see the iteration number else settings.mass_offset = 0;%2*(-0.5+rand(1)); % initialise to 0 the value of the mass offset, in order to not consider its uncertainty on the nominal simulations - % mass_flow_rate = diff(settings.motor.expM([end,1]))/settings.tb; % [kg/s] + % mass_flow_rate = diff(settings.motor.expM([end,1]))/rocket.motor.time(end); % [kg/s] % real_tb = (settings.mass_offset + settings.motor.mOx)/ mass_flow_rate; - % if real_tb < settings.tb - % settings.tb = real_tb; + % if real_tb < rocket.motor.time(end) + % rocket.motor.time(end) = real_tb; % end end \ No newline at end of file diff --git a/simulator/configs/configPath.m b/simulator/configs/configPath.m index b49f9bcdd607f9d7479adca87db99b476f796fab..9cc927366738a072886d2fa8b835904c0b1cd62b 100644 --- a/simulator/configs/configPath.m +++ b/simulator/configs/configPath.m @@ -5,17 +5,16 @@ folder path configuration script %} % Retrieve MSA-Toolkit rocket data -dataPath = strcat('../common/missions/', settings.missionMSA); -addpath(dataPath); -run([dataPath,'/simulationsData.m']); + +% commonFunctionsPath = '../common/functions/'; addpath(genpath(commonFunctionsPath)) % Retrieve Control rocket data -ConDataPath = strcat('../data/', settings.mission); +ConDataPath = strcat('../data/', mission.name); addpath(ConDataPath); - run(strcat('config', settings.mission)); + % Control common functions commonFunctionsPath = '../commonFunctions'; diff --git a/simulator/configs/configPayload.m b/simulator/configs/configPayload.m index 5caa89b3101cc88e401759afd013a95e090270ae..16cd3a9161ae4a6a387af53399b9a21209deb7d1 100644 --- a/simulator/configs/configPayload.m +++ b/simulator/configs/configPayload.m @@ -4,46 +4,6 @@ x_target = -500; y_target = 500; z_target = 0; -% Geometry -settings.payload.mass = 4.2; % [kg] mass -settings.payload.b = 2.55/2; % [m] semiwingspan - vela nuova: 2.55/2; - vela vecchia: 2.06/2; -settings.payload.c = 0.8; % [m] mean aero chord -settings.payload.S = 2.04; % [m^2] payload surface - vela nuova 2.04; - vela vecchia: 1.64; -settings.payload.inertia = [0.42, 0, 0.03; - 0, 0.4, 0; - 0.03, 0, 0.053]; % [kg m^2] [3x3] inertia matrix payload+payload -settings.payload.inverseInertia = inv(settings.payload.inertia); - -% Aerodynamic constants -settings.payload.CD0 = 0.25; -settings.payload.CDAlpha2 = 0.12; -settings.payload.CL0 = 0.091; -settings.payload.CLAlpha = 0.9; -settings.payload.Cm0 = 0.35; -settings.payload.CmAlpha = -0.72; -settings.payload.Cmq = -1.49; -settings.payload.CLDeltaA = -0.0035; -settings.payload.Cnr = -0.27; -settings.payload.CnDeltaA = 0.0115; -settings.payload.CDDeltaA = 0.01; -settings.payload.Clp = -0.84; -settings.payload.ClPhi = -0.1; -settings.payload.ClDeltaA = 0.01; -settings.payload.deltaSMax = 0.1; - -% %% Enviornment -% % Gravity -% const.g = 9.81; % [m/s^2] Gravity acceleration -% -% % Wind velocity -% environment.wind = [1; 1; 0]; % [m/s] [3x1] Wind velocity vector - -% %% Intial conditions -% settings.payload.omega0 = [0;0;0]; % [rad/s] [3x1] Initial angular velocity -% settings.payload.velBody0 = [7.3;0;0]; % [m/s] [3x1] Initial velocity -% settings.payload.initPos = [0;0;-400]; % [m] [3x1] Initial position -% settings.payload.attitude = [0;0;0]; % [rad] [3x1] Initial attitude - %% Target settings.payload.target = [x_target; y_target; z_target]; % [m] [3x1] target (IPI) @@ -73,17 +33,17 @@ contSettings.WES.deltaA = 0.05; % [-] DeltaA before guidance payload.simParam.incControl = true; % Subtract the wind from the velocity -payload.simParam.wind_sub = 1; % Set as 1 for subtracting and 0 otherwise +% payload.simParam.wind_sub = 1; % Set as 1 for subtracting and 0 otherwise % payload.simParam.WES0 = environment.wind; % Windspeed considered in the subtraction % P and PI controller -contSettings.payload.Kp = 0.4; -contSettings.payload.Ki = 0.08; -contSettings.payload.uMax = 0.1; -contSettings.payload.uMin = -0.1; -contSettings.payload.deltaA_tau = 0.4; % [s], absolutely arbitrary value -contSettings.payload.deltaA_delay = 0; % [s], absolutely arbitrary value -contSettings.payload.deltaA_maxSpeed = deg2rad(300); +rocket.parachutes(2,2).controlParams.Kp = 0.4; +rocket.parachutes(2,2).controlParams.Ki = 0.08; +rocket.parachutes(2,2).controlParams.uMax = 0.1; +rocket.parachutes(2,2).controlParams.uMin = -0.1; +rocket.parachutes(2,2).controlParams.deltaA_tau = 0.4; % [s], absolutely arbitrary value +rocket.parachutes(2,2).controlParams.deltaA_delay = 0; % [s], absolutely arbitrary value +rocket.parachutes(2,2).controlParams.deltaA_maxSpeed = deg2rad(300); %% Guidance algorithm % Algorithm selection: choose from "closed loop", "t-approach" diff --git a/simulator/configs/configReferences.m b/simulator/configs/configReferences.m index e0a1787964736f2ec95f37eedf6d092ac6727af3..8b43c64ef9f2587f948cbd836338da27c63fba7b 100644 --- a/simulator/configs/configReferences.m +++ b/simulator/configs/configReferences.m @@ -17,9 +17,9 @@ contSettings.data_trajectories = struct_trajectories.trajectories_saving; %% LOAD REFERENCES % select the trajectories for the rocket used in the simulation -switch settings.mission +switch mission.name - case 'Lynx_Portugal_October_2021' + case '2021_Lynx_Portugal_October' load("reference_gdtozero.mat") for i = 1:size(all_Vz,2) @@ -29,7 +29,7 @@ switch settings.mission reference.z_min = 466.738; reference.z_max = 1307.4; - case 'Pyxis_Portugal_October_2022' + case '2022_Pyxis_Portugal_October' load("Trajectories.mat") for i = 1:size(trajectories_saving,1) @@ -47,7 +47,7 @@ switch settings.mission reference.z_min = 466.738; reference.z_max = 1307.4; - case 'Pyxis_Roccaraso_September_2022' + case '2022_Pyxis_Roccaraso_September' load('Trajectories.mat'); for i = 1:size(trajectories_saving,1) reference.vz_ref{i,1} = trajectories_saving{i}.VZ_ref; @@ -59,7 +59,7 @@ switch settings.mission reference.Vnorm_ref{i,1}(j) = norm([reference.vz_ref{i,1}(j) reference.vx_ref{i,1}(j) reference.vy_ref{i,1}(j)]); end end - case 'Gemini_Portugal_October_2023' + case '2023_Gemini_Portugal_October' load("Trajectories.mat") for i = 1:size(trajectories_saving,1) @@ -74,7 +74,7 @@ switch settings.mission end end end - case 'Gemini_Roccaraso_September_2023' + case '2023_Gemini_Roccaraso_September' load("Trajectories.mat") for i = 1:size(trajectories_saving,1) @@ -89,7 +89,7 @@ switch settings.mission end end end - case 'Lyra_Portugal_October_2024' + case '2024_Lyra_Portugal_October' load("Trajectories.mat") for i = 1:size(trajectories_saving,1) @@ -104,7 +104,7 @@ switch settings.mission end end end - case 'Lyra_Roccaraso_September_2024' + case '2024_Lyra_Roccaraso_September' load("Trajectories.mat") for i = 1:size(trajectories_saving,1) @@ -124,7 +124,7 @@ end contSettings.reference.deltaZ = 10; heights = (0:contSettings.reference.deltaZ:settings.z_final)'; -if str2double(settings.mission(end)) > 2 +if contains(mission.name,'2024') || contains(mission.name,'2023') V_rescale = cell( size(reference.altitude_ref,1),size(reference.altitude_ref,2) ); for j = 1 : size(reference.altitude_ref,2) diff --git a/simulator/configs/configSimulator.m b/simulator/configs/configSimulator.m index 3e92fed832968a9102f4b9c99689df479cd111b2..a1433d263c10cecd8c3c9e40bf995eb813f735e9 100644 --- a/simulator/configs/configSimulator.m +++ b/simulator/configs/configSimulator.m @@ -14,28 +14,28 @@ SPDX-License-Identifier: GPL-3.0-or-later %} - - -%% 1) MISSION FILE -configMission; - %% 2) SIMULATION SETTINGS configFlags; +%% Mission parameters +mission = Mission(true); +rocket = Rocket(mission); +environment = Environment(mission, rocket.motor); + %% 3) LOAD DATAPATH configPath; +%% CONFIG CONTROL +run(strcat('config', mission.name)); +if conf.HIL + run('HILconfig.m'); +end %% 4) TRAJECTORY GENERATION SETUP if conf.script == "trajectory generation" config_TrajectoryGen; end -%% 5) LAUNCH SETUP -configLaunchRail; - -%% 6) WIND DETAILS -configWind; %% 8) PLOTS? configPlots; @@ -59,7 +59,7 @@ if conf.script ~= "trajectory generation" %% 14) REFERENCES configReferences; %% 15) SPECIAL CONDITIONS? -% config_SpecialConditions; + % config_SpecialConditions; end diff --git a/simulator/configs/config_SpecialConditions.m b/simulator/configs/config_SpecialConditions.m index 28e61bb1d553434c3c7e64712eb80dd54ae9f81a..123d86ed0551a8d0f7cda8ee91c8961b9fec43a5 100644 --- a/simulator/configs/config_SpecialConditions.m +++ b/simulator/configs/config_SpecialConditions.m @@ -13,7 +13,7 @@ conf.motor_Thrust_Factor = 1.; % default: = 1; conf.motor_Time_Factor = 1; % default: % mach control -conf.mach_control = 0.85; % default: = settings.MachControl; +conf.mach_control = 0.85; % default: = rocket.airbrakes.maxMach; % steps in advance contSettings.N_forward = 2; @@ -29,7 +29,7 @@ settings.wind.input = false; %% changed parameters -settings.motor.expThrust = conf.motor_Thrust_Factor.* settings.motor.expThrust; -settings.motor.expTime = conf.motor_Time_Factor .* settings.motor.expTime; +rocket.motor.thrust = conf.motor_Thrust_Factor.* rocket.motor.thrust; +rocket.motor.time = conf.motor_Time_Factor .* rocket.motor.time; settings.mach_control = conf.mach_control; diff --git a/simulator/mainMontecarlo.m b/simulator/mainMontecarlo.m index 7fcde1d8fa671444588fda2a62095f3c27aabf16..fb88171bdd802a2655ee9a6b5eb4d020c669df70 100644 --- a/simulator/mainMontecarlo.m +++ b/simulator/mainMontecarlo.m @@ -26,6 +26,7 @@ end % adds folders to the path and retrieves rocket, mission, simulation, etc % data. +restoredefaultpath; filePath = fileparts(mfilename('fullpath')); currentPath = pwd; if not(strcmp(filePath, currentPath)) @@ -38,6 +39,10 @@ addpath(genpath(currentPath)); % Common Functions path addpath(genpath(commonFunctionsPath)); +% add common data path +dataPath = strcat('../common'); +addpath(genpath(dataPath)); + %% CHECK IF MSA-TOOLKIT IS UPDATED % msaToolkitURL = 'https://github.com/skyward-er/msa-toolkit'; % localRepoPath = '../data/msa-toolkit'; @@ -89,6 +94,11 @@ clearvars msaToolkitURL Itot %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%CONFIG%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% settings_mont_init = struct('x',[]); +rocket_vec = cell(N_sim, 1); + +if ~exist("wind_vec", 'var') + wind_vec = cell(N_sim, 1); +end %% start simulation for alg_index = 4 @@ -105,43 +115,33 @@ for alg_index = 4 motor_K = settings.motor.K; parfor i = 1:N_sim + rocket_vec{i} = copy(rocket); settings_mont = settings_mont_init; settings_mont.motor.expThrust = stoch.thrust(i,:); % initialize the thrust vector of the current simulation (parfor purposes) - settings_mont.motor.expTime = stoch.expThrust(i,:); % initialize the time vector for thrust of the current simulation (parfor purposes) + settings_mont.motor.expTime = stoch.expTime(i,:); % initialize the time vector for thrust of the current simulation (parfor purposes) settings_mont.motor.K = motor_K + stoch.delta_Kt(i,:); % - settings_mont.tb = max( stoch.expThrust(i,stoch.expThrust(i,:)<=settings.tb) ); % initialize the burning time of the current simulation (parfor purposes) settings_mont.State.xcgTime = stoch.State.xcgTime(:,i); % initialize the baricenter position time vector settings_mont.mass_offset = stoch.mass_offset(i); settings_mont.OMEGA = stoch.OMEGA_rail(i); settings_mont.PHI = stoch.PHI_rail(i); - - - - % Define coeffs matrix for the i-th simulation - settings_mont.Coeffs = settings.Coeffs* (1+stoch.aer_percentage(i)); - -stoch; - % set the wind parameters - switch settings.windModel - case "constant" - settings_mont.wind.uw = stoch.wind.uw(i); - settings_mont.wind.vw = stoch.wind.vw(i); - settings_mont.wind.ww = stoch.wind.ww(i); - settings_mont.wind.Az = stoch.wind.Az(i); - settings_mont.wind.El = stoch.wind.El(i); - case "multiplicative" - settings_mont.wind.Mag = stoch.wind.Mag(i); - settings_mont.wind.Az = stoch.wind.Az(i,:); - settings_mont.wind.unc = stoch.wind.unc(i,:); + if isempty(wind_vec{i}) + wind_vec{i} = copy(stoch.wind); + wind_vec{i}.updateAll(); end + settings_mont.wind = wind_vec{i}; + + % Define coeffs matrix for the i-th simulation + settings_mont.Coeffs = rocket.coefficients.total * (1+stoch.aer_percentage(i)); + + if displayIter == true fprintf("simulation = " + num2str(i) + " of " + num2str(N_sim) + ", algorithm: " + contSettings.algorithm +", scenario: "+ settings.scenario +"\n"); end %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%STD_RUN%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% - [simOutput] = std_run(settings,contSettings,settings_mont); + [simOutput] = std_run(settings,contSettings,rocket_vec{i},environment,mission,settings_mont); %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%STD_RUN%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% save_thrust{i} = simOutput; @@ -174,14 +174,13 @@ stoch; % time of engine shutdown t_shutdown.value(i) = save_thrust{i}.sensors.mea.t_shutdown; - if ~settings.wind.model && ~settings.wind.input - % wind magnitude - wind_Mag(i) = save_thrust{i}.wind.Mag; - % wind azimuth - wind_az(i) = save_thrust{i}.wind.Az; - %wind elevation - wind_el(i) = save_thrust{i}.wind.El; - end + % wind magnitude + wind_Mag(i) = wind_vec{i}.magnitude(1); + % wind azimuth + wind_az(i) = wind_vec{i}.azimuth(1); + %wind elevation + wind_el(i) = wind_vec{i}.elevation(1); + %reached apogee time apogee.times(i) = save_thrust{i}.apogee.time; apogee.prediction(i) = save_thrust{i}.sensors.mea.prediction(end); @@ -328,35 +327,31 @@ stoch; folder = []; if flagSaveOffline == "yes" || flagSaveOffline == "y" - switch settings.mission + switch mission.name case 'Pyxis_Portugal_October_2022' - folder = [folder ; "MontecarloResults\"+settings.mission+"\"+contSettings.algorithm+"\"+num2str(N_sim)+"sim_Mach"+num2str(100*settings.MachControl)+"_"+simulationType_thrust+"_"+saveDate]; % offline + folder = [folder ; "MontecarloResults\"+mission.name+"\"+contSettings.algorithm+"\"+num2str(N_sim)+"sim_Mach"+num2str(100*rocket.airbrakes.maxMach)+"_"+simulationType_thrust+"_"+saveDate]; % offline case 'Gemini_Portugal_October_2023' - folder = [folder ; "MontecarloResults\"+settings.mission+"\"+contSettings.algorithm+"\"+num2str(N_sim)+"sim_Mach"+num2str(100*settings.MachControl)+"_"+simulationType_thrust+"_"+saveDate]; % offline + folder = [folder ; "MontecarloResults\"+mission.name+"\"+contSettings.algorithm+"\"+num2str(N_sim)+"sim_Mach"+num2str(100*rocket.airbrakes.maxMach)+"_"+simulationType_thrust+"_"+saveDate]; % offline case 'Pyxis_Roccaraso_September_2022' - folder = [folder ; "MontecarloResults\"+settings.mission+"\z_f_"+settings.z_final+"\"+contSettings.algorithm+"\"+num2str(N_sim)+"sim_Mach"+num2str(100*settings.MachControl)+"_"+simulationType_thrust+"_"+saveDate]; % offline + folder = [folder ; "MontecarloResults\"+mission.name+"\z_f_"+settings.z_final+"\"+contSettings.algorithm+"\"+num2str(N_sim)+"sim_Mach"+num2str(100*rocket.airbrakes.maxMach)+"_"+simulationType_thrust+"_"+saveDate]; % offline case 'Gemini_Roccaraso_September_2023' - folder = [folder ; "MontecarloResults\"+settings.mission+"\"+contSettings.algorithm+"\"+num2str(N_sim)+"sim_Mach"+num2str(100*settings.MachControl)+"_"+simulationType_thrust+"_"+saveDate]; % offline + folder = [folder ; "MontecarloResults\"+mission.name+"\"+contSettings.algorithm+"\"+num2str(N_sim)+"sim_Mach"+num2str(100*rocket.airbrakes.maxMach)+"_"+simulationType_thrust+"_"+saveDate]; % offline - case 'Lyra_Portugal_October_2024' - folder = [folder ; "MontecarloResults\"+settings.mission+"\"+contSettings.algorithm+"\"+num2str(N_sim)+"sim_Mach"+num2str(100*settings.MachControl)+"_"+simulationType_thrust+"_"+saveDate]; % offline - - case 'Lyra_Roccaraso_September_2024' - folder = [folder ; "MontecarloResults\"+settings.mission+"\"+contSettings.algorithm+"\"+num2str(N_sim)+"sim_Mach"+num2str(100*settings.MachControl)+"_"+simulationType_thrust+"_"+saveDate]; % offline - + case {'2024_Lyra_Portugal_October', '2024_Lyra_Roccaraso_September'} + folder = [folder ; "MontecarloResults\"+mission.name+"\"+contSettings.algorithm+"\"+num2str(N_sim)+"sim_Mach"+num2str(100*rocket.airbrakes.maxMach)+"_"+simulationType_thrust+"_"+saveDate]; % offline end end if flagSaveOnline == "yes" || flagSaveOnline == "y" if computer == "Marco" || computer == "marco" - folder = [folder ; "C:\Users\marco\OneDrive - Politecnico di Milano\SKYWARD\AIR BRAKES\MONTECARLO E TUNING\"+settings.mission+"\"+conf.scenario+"\"+contSettings.algorithm+"\"+num2str(N_sim)+"_"+simulationType_thrust+"_"+saveDate]; % online + folder = [folder ; "C:\Users\marco\OneDrive - Politecnico di Milano\SKYWARD\AIR BRAKES\MONTECARLO E TUNING\"+mission.name+"\"+conf.scenario+"\"+contSettings.algorithm+"\"+num2str(N_sim)+"_"+simulationType_thrust+"_"+saveDate]; % online end if computer == "Max" || computer == "max" - folder = [folder ; "C:\Users\Max\OneDrive - Politecnico di Milano\SKYWARD\AIR BRAKES\MONTECARLO E TUNING\"+settings.mission+"\"+conf.scenario+"\"+contSettings.algorithm+"\"+num2str(N_sim)+"_"+simulationType_thrust+"_"+saveDate]; % online + folder = [folder ; "C:\Users\Max\OneDrive - Politecnico di Milano\SKYWARD\AIR BRAKES\MONTECARLO E TUNING\"+mission.name+"\"+conf.scenario+"\"+contSettings.algorithm+"\"+num2str(N_sim)+"_"+simulationType_thrust+"_"+saveDate]; % online end end @@ -386,7 +381,7 @@ stoch; fprintf(fid,'Algorithm: %s \n',contSettings.algorithm ); fprintf(fid,'Engine shut-down control frequency: %d Hz \n',settings.frequencies.controlFrequency); fprintf(fid,'Airbrakes control frequency: %d Hz \n',settings.frequencies.arbFrequency ); - fprintf(fid,'Initial Mach number at which the control algorithm starts: %.3f \n\n',settings.MachControl); + fprintf(fid,'Initial Mach number at which the control algorithm starts: %.3f \n\n',rocket.airbrakes.maxMach); fprintf(fid,'Other parameters specific of the simulation: \n'); fprintf(fid,'Filter coefficient: %.3f \n', contSettings.filter_coeff); fprintf(fid,'Target for shutdown: %d \n',settings.mea.z_shutdown); @@ -410,27 +405,32 @@ stoch; % % end %%%%%%%%%%%%%%%%%%%%%%%%%%% - fprintf(fid,'WIND \n\n '); - fprintf(fid,'Wind model: %s \n',settings.windModel); - if settings.windModel == "constant" - fprintf(fid,'Wind model parameters: \n'); % inserisci tutti i parametri del vento - fprintf(fid,'Wind Magnitude: 0-%d m/s\n',settings.wind.MagMax); - fprintf(fid,'Wind minimum azimuth: %d [°] \n',rad2deg(settings.wind.AzMin)); - fprintf(fid,'Wind maximum azimuth: %d [°] \n',rad2deg(settings.wind.AzMax)); - fprintf(fid,'Wind minimum elevation: %d [°] \n', rad2deg(settings.wind.ElMin)); - fprintf(fid,'Wind maximum elevation: %d [°] \n\n\n',rad2deg(settings.wind.ElMax)); - else - fprintf(fid,'Wind model parameters: \n'); % inserisci tutti i parametri del vento - fprintf(fid,'Ground wind Magnitude: 0-%d m/s\n\n\n',settings.wind.MagMax); + fprintf(fid,'WIND \n\n'); + fprintf(fid,'Wind model parameters: \n'); % inserisci tutti i parametri del vento + fprintf(fid,'Wind altitudes: '+string(repmat('%.2f m ', [1 length(wind.altitudes)]))+"\n\n", wind.altitudes); + for ii = 1:length(wind.altitudes) + fprintf(fid,'Wind magnitude distribution at %.2f m: \"%s\"\n', wind.altitudes(ii), string(wind.magnitudeDistribution(ii))); + fprintf(fid,'Wind magnitude parameters at %.2f m: %d-%d m/s\n',wind.altitudes(ii), stoch.wind_params.MagMin(ii), stoch.wind_params.MagMax(ii)); + end + fprintf(fid, '\n'); + for ii = 1:length(wind.altitudes) + fprintf(fid,'Wind azimuth distribution at %.2f m: \"%s\"\n', wind.altitudes(ii), string(wind.azimuthDistribution(ii))); + fprintf(fid,'Wind azimuth parameters at %.2f m: %d-%d [°] \n', wind.altitudes(ii), rad2deg(stoch.wind_params.AzMin(ii)), rad2deg(stoch.wind_params.AzMax(ii))); + end + fprintf(fid, '\n'); + for ii = 1:length(wind.altitudes) + fprintf(fid,'Wind elevation distribution at %.2f m: \"%s\"\n', wind.altitudes(ii), string(wind.elevationDistribution(ii))); + fprintf(fid,'Wind elevation parameters at %.2f m: %d-%d [°] \n', wind.altitudes(ii), rad2deg(stoch.wind_params.ElMin(ii)), rad2deg(stoch.wind_params.ElMax(ii))); end + fprintf(fid,'\n\n'); %%%%%%%%%%%%%%%%%%%%%%%%%%% if (settings.scenario == "descent" || settings.scenario == "full flight") && settings.parafoil fprintf(fid,'PARAFOIL \n\n'); fprintf(fid,'Guidance approach %s \n',contSettings.payload.guidance_alg); - fprintf(fid,'PID proportional gain %s \n',contSettings.payload.Kp); - fprintf(fid,'PID integral gain %s \n',contSettings.payload.Ki); - fprintf(fid,'Opening altitude %s \n',settings.para(1).z_cut); + fprintf(fid,'PID proportional gain %s \n',rocket.parachutes(2,2).controlParams.Kp); + fprintf(fid,'PID integral gain %s \n',rocket.parachutes(2,2).controlParams.Ki); + fprintf(fid,'Opening altitude %s \n',settings.ada.para.z_cut); end fprintf(fid,'MASS: \n\n'); fprintf(fid,'Interval : +-%d at 3sigma \n',3*sigma_m ); @@ -477,8 +477,8 @@ end %% generate file for rocketpy (euroc 2023 prelaunch) % for i = 1:N_sim -% [apogee.coordinates(i,1),apogee.coordinates(i,2),apogee.coordinates(i,3)] = ned2geodetic(save_thrust{i}.apogee.position(1),save_thrust{i}.apogee.position(2),save_thrust{i}.apogee.position(3),settings.lat0,settings.lon0,settings.z0,wgs84Ellipsoid); -% [landing.coordinates(i,1),landing.coordinates(i,2),landing.coordinates(i,3)] = ned2geodetic(save_thrust{i}.Y(end,1),save_thrust{i}.Y(end,2),save_thrust{i}.Y(end,3),settings.lat0,settings.lon0,settings.z0,wgs84Ellipsoid); +% [apogee.coordinates(i,1),apogee.coordinates(i,2),apogee.coordinates(i,3)] = ned2geodetic(save_thrust{i}.apogee.position(1),save_thrust{i}.apogee.position(2),save_thrust{i}.apogee.position(3),environment.lat0,environment.lon0,environment.z0,wgs84Ellipsoid); +% [landing.coordinates(i,1),landing.coordinates(i,2),landing.coordinates(i,3)] = ned2geodetic(save_thrust{i}.Y(end,1),save_thrust{i}.Y(end,2),save_thrust{i}.Y(end,3),environment.lat0,environment.lon0,environment.z0,wgs84Ellipsoid); % end % landing.coordinates = landing.coordinates(:,1:2); % diff --git a/simulator/mainSimulator.m b/simulator/mainSimulator.m index b5dca78b930aec563d5afee4e0a5859caa17096d..0123a22efdf0c28b486a02f0f281f82979a2368a 100644 --- a/simulator/mainSimulator.m +++ b/simulator/mainSimulator.m @@ -51,6 +51,10 @@ addpath(genpath(currentPath)); % Common Functions path addpath(genpath(commonFunctionsPath)); +% add MSA data path +dataPath = strcat('../common'); +addpath(genpath(dataPath)); + %% CHECK SUBMODULES UPDATES % if ~exist('flagSubmodulesUpdated','var') % checkSubmodules; @@ -81,13 +85,13 @@ end % Y = State = ( x y z | u v w | p q r | q0 q1 q2 q3 | thetax thetay thetaz | ap_ref ) also for Ya,Yf corresponding to T %% simulation: -[simOutput] = std_run(settings,contSettings); +[simOutput] = std_run(settings,contSettings,rocket,environment,mission); %% PLOTS if ~exist("../commonFunctions/graphics/general-utilities/","dir") warning('To export file you need to download the repository, read the README file in the folder') end -std_plots(simOutput,settings,contSettings) +std_plots(simOutput,settings,contSettings,mission,rocket,environment) sensor_plots(simOutput) % report_plots(simOutput,settings,contSettings) diff --git a/simulator/montecarlo/plotsMontecarlo.m b/simulator/montecarlo/plotsMontecarlo.m index b3ef455e677fc4a697b7a8f356653cf3c0fff8b0..b3118d4b9b5b5c6c40bcc1a389a90102ae8524cf 100644 --- a/simulator/montecarlo/plotsMontecarlo.m +++ b/simulator/montecarlo/plotsMontecarlo.m @@ -247,12 +247,6 @@ if (strcmp(contSettings.algorithm,'engine') || strcmp(contSettings.algorithm,'co end %% PLOT APOGEE 3D -if ~settings.wind.model && ~settings.wind.input - for i = 1:N_sim - wind_Mag(i) = save_thrust{i}.wind.Mag; - wind_az(i) = save_thrust{i}.wind.Az; - wind_el(i) = save_thrust{i}.wind.El; - end montFigures.apogee_3D_wind_thrust = figure; %%%%%%%%%% wind magnitude - thrust - apogee subplot(2,2,1) @@ -295,7 +289,7 @@ zlabel('Apogee') % zlim([settings.z_final-200,settings.z_final+200]) view(30,20) legend(contSettings.algorithm); -end + diff --git a/simulator/report_images/report_plots.m b/simulator/report_images/report_plots.m index 5d7939b49b5de2e935951faeee81068b27f1be00..43f8e0008a482a2a5661aaa452f7f0a9a5932740 100644 --- a/simulator/report_images/report_plots.m +++ b/simulator/report_images/report_plots.m @@ -6,7 +6,7 @@ function report_plots(structIn,settings,contSettings) % figures.trajectory = figure('Name', 'Trajectory','ToolBar','auto','Position',[100,100,600,400]); % plot3(structIn.Y(1:end-10, 2), structIn.Y(1:end-10, 1), -structIn.Y(1:end-10, 3),'DisplayName','True trajectory'); % hold on; grid on; -% % plot3(structIn.NAS(1:end-10, 2), structIn.NAS(1:end-10, 1), -structIn.NAS(1:end-10, 3)-settings.z0,'DisplayName','NAS trajectory'); +% % plot3(structIn.NAS(1:end-10, 2), structIn.NAS(1:end-10, 1), -structIn.NAS(1:end-10, 3)-environment.z0,'DisplayName','NAS trajectory'); % % if not(settings.scenario == "descent") % plot3(structIn.ARB_openingPosition(2),structIn.ARB_openingPosition(1),structIn.ARB_openingPosition(3),'ko','DisplayName','Airbrake deployment') @@ -30,13 +30,13 @@ function report_plots(structIn,settings,contSettings) % axis equal % view([0,90]) % legend -% exportStandardizedFigure(figures.trajectory,"report_images\"+settings.mission+"\src_trajectory.pdf",0.9,'forcedMarkers',10) +% exportStandardizedFigure(figures.trajectory,"report_images\"+mission.name+"\src_trajectory.pdf",0.9,'forcedMarkers',10) % % %% Trajectory % figures.trajectory = figure('Name', 'Trajectory','ToolBar','auto','Position',[100,100,600,400]); % plot(structIn.Y(1:end-10, 2), structIn.Y(1:end-10, 1),'DisplayName','Trajectory'); % hold on; grid on; -% % plot3(structIn.NAS(1:end-10, 2), structIn.NAS(1:end-10, 1), -structIn.NAS(1:end-10, 3)-settings.z0,'DisplayName','NAS trajectory'); +% % plot3(structIn.NAS(1:end-10, 2), structIn.NAS(1:end-10, 1), -structIn.NAS(1:end-10, 3)-environment.z0,'DisplayName','NAS trajectory'); % % if not(settings.scenario == "descent") % plot(structIn.ARB_openingPosition(2),structIn.ARB_openingPosition(1),'ko','DisplayName','Airbrake deployment') @@ -63,7 +63,7 @@ function report_plots(structIn,settings,contSettings) % title('Trajectory (ENU)'); % axis equal % legend -% exportStandardizedFigure(figures.trajectory,"report_images\"+settings.mission+"\src_trajectory.pdf",0.7,'forcedMarkers',10) +% exportStandardizedFigure(figures.trajectory,"report_images\"+mission.name+"\src_trajectory.pdf",0.7,'forcedMarkers',10) % % % %% parafoil control action @@ -77,7 +77,7 @@ function report_plots(structIn,settings,contSettings) % sgtitle('Parafoil control action') % xlabel('Time [s]') % ylabel('Normalized control action [-]') -% exportStandardizedFigure(figures.parafoil_servo_action,"report_images\"+settings.mission+"\prf_control_action.pdf",0.7,'forcedMarkers',10) +% exportStandardizedFigure(figures.parafoil_servo_action,"report_images\"+mission.name+"\prf_control_action.pdf",0.7,'forcedMarkers',10) %% Reference figures.ABK_wrt_referenceTrajectory = figure; diff --git a/simulator/src/export_HILdataABK.m b/simulator/src/export_HILdataABK.m index 8cd1279229b10a6f4f7668a0b05b9705ee702040..1e29492cc088ce4dfd48f32d251db7f00c269444 100644 --- a/simulator/src/export_HILdataABK.m +++ b/simulator/src/export_HILdataABK.m @@ -7,7 +7,7 @@ % % check also export_HILdataPRF for parafoil HIL and software testing -switch settings.mission +switch mission.name case {"Gemini_Portugal_October_2023", "Gemini_Roccaraso_September_2023"} folder = "HIL_CPP_files_ABK"; @@ -36,7 +36,7 @@ switch settings.mission reference_export_table(:,i) = table(reference_export(:,i)); end reference_export_table.Properties.VariableNames = varNames; - writetable(reference_export_table,ConDataPath+"/"+folder+"/ABK_references_"+settings.mission+".csv") + writetable(reference_export_table,ConDataPath+"/"+folder+"/ABK_references_"+mission.name+".csv") % second file: configuration for the air brakes configABK_export_table = table; @@ -46,7 +46,7 @@ switch settings.mission configABK_export_table(1,i) = table(configValues(1,i)); end configABK_export_table.Properties.VariableNames = configABKvarNames; - writetable(configABK_export_table,ConDataPath+"/"+folder+"/ABK_configABK_"+settings.mission+".csv") + writetable(configABK_export_table,ConDataPath+"/"+folder+"/ABK_configABK_"+mission.name+".csv") % third file: input extrapolation: % first column - timestamps of the NAS system @@ -61,7 +61,7 @@ switch settings.mission trajectory_export_table(:,i) = table(trajectory(:,i)); end trajectory_export_table.Properties.VariableNames = traj_varNames; - writetable(trajectory_export_table,ConDataPath+"/"+folder+"/ABK_trajectories_"+settings.mission+".csv") + writetable(trajectory_export_table,ConDataPath+"/"+folder+"/ABK_trajectories_"+mission.name+".csv") % fourth file: input extrapolation: % first column - data with air brakes timestamps; @@ -87,7 +87,7 @@ switch settings.mission outputABK_export_table(:,i) = table(ABK_recall(:,i)); end outputABK_export_table.Properties.VariableNames = ABK_varNames; - writetable(outputABK_export_table,ConDataPath+"/"+folder+"/ABK_outputABK_"+settings.mission+".csv") + writetable(outputABK_export_table,ConDataPath+"/"+folder+"/ABK_outputABK_"+mission.name+".csv") end \ No newline at end of file diff --git a/simulator/src/export_HILdataADA.m b/simulator/src/export_HILdataADA.m index 2729806ad1b041b8e30a177761c38e4da7e6c486..77b2140a40e1d0bd62166eef1e3bfb699bbaccc2 100644 --- a/simulator/src/export_HILdataADA.m +++ b/simulator/src/export_HILdataADA.m @@ -1,7 +1,7 @@ %{ export configuration files for ADA algorithm (for our friends of software development) %} -switch settings.mission +switch mission.name case {"Gemini_Portugal_October_2023", "Gemini_Roccaraso_September_2023"} folder = "HIL_CPP_files_ADA"; @@ -17,7 +17,7 @@ switch settings.mission configADA_export_table(1,i) = table(configValues(1,i)); end configADA_export_table.Properties.VariableNames = configADAvarNames; - writetable(configADA_export_table,ConDataPath+"/"+folder+"/ADA_configADA_"+settings.mission+".csv") + writetable(configADA_export_table,ConDataPath+"/"+folder+"/ADA_configADA_"+mission.name+".csv") end \ No newline at end of file diff --git a/simulator/src/export_HILdataMTR.m b/simulator/src/export_HILdataMTR.m index e5eae8c863e6e6fdb6971e6b9544a1d378800d8b..04b939f7c93070fb8c5b9db65fbb11ba61d6d400 100644 --- a/simulator/src/export_HILdataMTR.m +++ b/simulator/src/export_HILdataMTR.m @@ -3,7 +3,7 @@ %} -switch settings.mission +switch mission.name case {"Gemini_Portugal_October_2023", "Gemini_Roccaraso_September_2023"} folder_MTR = "HIL_CPP_files_MTR"; if ~exist(ConDataPath+"/"+folder_MTR,"dir") @@ -20,18 +20,18 @@ switch settings.mission CD_coeff_table(:,i) = table(CD_coefficients(:,i)); end CD_coeff_table.Properties.VariableNames = varNames; - writetable(CD_coeff_table,ConDataPath+"/"+folder_MTR+"/MTR_CDcoeffShutDown_"+settings.mission+".csv") + writetable(CD_coeff_table,ConDataPath+"/"+folder_MTR+"/MTR_CDcoeffShutDown_"+mission.name+".csv") % second file: configuration for mass estimation algorithm configMTR_export_table = table; - configValues = [settings.frequencies.MEAFrequency,settings.mea.t_lower_shadowmode,settings.mea.t_higher_shadowmode,contSettings.N_prediction_threshold,settings.mea.Q(1,1),settings.mea.Q(2,2),settings.mea.Q(3,3),settings.mea.R,settings.m0,settings.mea.z_shutdown]; + configValues = [settings.frequencies.MEAFrequency,settings.mea.t_lower_shadowmode,settings.mea.t_higher_shadowmode,contSettings.N_prediction_threshold,settings.mea.Q(1,1),settings.mea.Q(2,2),settings.mea.Q(3,3),settings.mea.R,rocket.mass(1),settings.mea.z_shutdown]; configMTRvarNames = {'MEA_FREQUENCY','MEA_SHADOWMODE','SHUTDOWN_MAX_TIME','MEA_PREDICTION_THRESHOLD','MEA_Q_11','MEA_Q_22','MEA_Q_33','MEA_R','MEA_INIT_MASS','MEA_SHUTDOWN_TARGET_APOGEE'}; for i = 1:size(configValues,2) configMTR_export_table(1,i) = table(configValues(1,i)); end configMTR_export_table.Properties.VariableNames = configMTRvarNames; - writetable(configMTR_export_table,ConDataPath+"/"+folder_MTR+"/MTR_configMTR_"+settings.mission+".csv") + writetable(configMTR_export_table,ConDataPath+"/"+folder_MTR+"/MTR_configMTR_"+mission.name+".csv") % third file: configuration for the air brakes configMEA_MODEL_export_table = table; @@ -41,7 +41,7 @@ switch settings.mission configMEA_MODEL_export_table(1,i) = table(configValues(1,i)); end configMEA_MODEL_export_table.Properties.VariableNames = configMEA_MODELvarNames; - writetable(configMEA_MODEL_export_table,ConDataPath+"/"+folder_MTR+"/MTR_mea_model_"+settings.mission+".csv") + writetable(configMEA_MODEL_export_table,ConDataPath+"/"+folder_MTR+"/MTR_mea_model_"+mission.name+".csv") end \ No newline at end of file diff --git a/simulator/src/export_HILdataNAS.m b/simulator/src/export_HILdataNAS.m index cba945b7ba873d5cb04cd1742734535f81425a0b..b60125394f1c8cb112c271b80d77bf782d6762be 100644 --- a/simulator/src/export_HILdataNAS.m +++ b/simulator/src/export_HILdataNAS.m @@ -1,7 +1,7 @@ %{ export configuration files for NAS algorithm (for our friends of software development) %} -switch settings.mission +switch mission.name case {"Gemini_Portugal_October_2023", "Gemini_Roccaraso_September_2023"} folder = "HIL_CPP_files_NAS"; @@ -17,7 +17,7 @@ switch settings.mission configNAS_export_table(1,i) = table(configValues(1,i)); end configNAS_export_table.Properties.VariableNames = configNASvarNames; - writetable(configNAS_export_table,ConDataPath+"/"+folder+"/NAS_configNAS_"+settings.mission+".csv") + writetable(configNAS_export_table,ConDataPath+"/"+folder+"/NAS_configNAS_"+mission.name+".csv") end \ No newline at end of file diff --git a/simulator/src/export_HILdataPRF.m b/simulator/src/export_HILdataPRF.m index ec44d00e5b90fa8ca29bd29f9362cb6c294c66b4..b5b5fe39d22b9b37f64582498f61a98696863b0f 100644 --- a/simulator/src/export_HILdataPRF.m +++ b/simulator/src/export_HILdataPRF.m @@ -7,7 +7,7 @@ % % check also export_HILdataABK for air brakes HIL and software testing -switch settings.mission +switch mission.name case "Gemini_Portugal_October_2023" if ~exist(ConDataPath+"/HIL_CPP_files_PRF","dir") @@ -21,7 +21,7 @@ switch settings.mission PRFtrajectory = zeros(size(simOutput.t_nas(simOutput.events.mainChuteIndex:end)')); PRFtrajectory(:,1) = simOutput.NAS(simOutput.events.mainChuteIndex:end,1); PRFtrajectory(:,2) = simOutput.NAS(simOutput.events.mainChuteIndex:end,2); - PRFtrajectory(:,3) = simOutput.NAS(simOutput.events.mainChuteIndex:end,3)+settings.z0; + PRFtrajectory(:,3) = simOutput.NAS(simOutput.events.mainChuteIndex:end,3)+environment.z0; PRFtrajectory(:,4) = simOutput.NAS(simOutput.events.mainChuteIndex:end,4); PRFtrajectory(:,5) = simOutput.NAS(simOutput.events.mainChuteIndex:end,5); traj_varNames = {'N','E','D','Vn','Ve'}; @@ -29,7 +29,7 @@ switch settings.mission trajectory_export_table(:,i) = table(PRFtrajectory(:,i)); end trajectory_export_table.Properties.VariableNames = traj_varNames; - writetable(trajectory_export_table,ConDataPath+"/HIL_CPP_files_PRF/PRF_trajectories_"+settings.mission+".csv") + writetable(trajectory_export_table,ConDataPath+"/HIL_CPP_files_PRF/PRF_trajectories_"+mission.name+".csv") % second file: WES output extrapolation: @@ -49,7 +49,7 @@ switch settings.mission outputWES_export_table(:,i) = table(WES_output(:,i)); end outputWES_export_table.Properties.VariableNames = WES_varNames; - writetable(outputWES_export_table,ConDataPath+"/HIL_CPP_files_PRF/PRF_outputWES_"+settings.mission+".csv") + writetable(outputWES_export_table,ConDataPath+"/HIL_CPP_files_PRF/PRF_outputWES_"+mission.name+".csv") % third file: configuration file for WES configPRF_export_table = table; @@ -63,7 +63,7 @@ switch settings.mission configPRF_export_table(1,i) = table(configValues(1,i)); end configPRF_export_table.Properties.VariableNames = configPRFvarNames; - writetable(configPRF_export_table,ConDataPath+"/HIL_CPP_files_PRF/PRF_configGuidance_"+settings.mission+".csv") + writetable(configPRF_export_table,ConDataPath+"/HIL_CPP_files_PRF/PRF_configGuidance_"+mission.name+".csv") % fourth file: guidance output @@ -80,7 +80,7 @@ switch settings.mission outputGuidance_export_table(:,i) = table(guidance_output(:,i)); end outputGuidance_export_table.Properties.VariableNames = WES_varNames; - writetable(outputGuidance_export_table,ConDataPath+"/HIL_CPP_files_PRF/PRF_outputGuidance_"+settings.mission+".csv") + writetable(outputGuidance_export_table,ConDataPath+"/HIL_CPP_files_PRF/PRF_outputGuidance_"+mission.name+".csv") % fifth file: control output % recall contSettings @@ -121,7 +121,7 @@ switch settings.mission outputPRFcontrol_export_table(:,i) = table(PRFcontrol_output(:,i)); end outputPRFcontrol_export_table.Properties.VariableNames = PRFcontrol_varNames; - writetable(outputPRFcontrol_export_table,ConDataPath+"/HIL_CPP_files_PRF/PRF_outputControl_"+settings.mission+".csv") + writetable(outputPRFcontrol_export_table,ConDataPath+"/HIL_CPP_files_PRF/PRF_outputControl_"+mission.name+".csv") end \ No newline at end of file diff --git a/simulator/src/std_plots.m b/simulator/src/std_plots.m index 163f64f0880356a132d685388a165a5b2baaf54e..b5cfba20fb1f49b33fa52d3034d8a5653a3facae 100644 --- a/simulator/src/std_plots.m +++ b/simulator/src/std_plots.m @@ -1,7 +1,7 @@ -function std_plots(simOutput, settings,contSettings) +function std_plots(simOutput, settings,contSettings,mission,rocket,environment) -if ~exist("report_images\"+settings.mission,"dir") - mkdir("report_images\"+settings.mission) +if ~exist("report_images\"+mission.name,"dir") + mkdir("report_images\"+mission.name) end %% post process data @@ -12,7 +12,7 @@ eul = rad2deg(eul); v_ned = quatrotate(quatconj(simOutput.Y(:, 10:13)), simOutput.Y(:, 4:6)); %% MASS ESTIMATION ALGORITHM -if contains(settings.mission, '2023') || contains(settings.mission, '2024') +if contains(mission.name, '2023') || contains(mission.name, '2024') if (strcmp(contSettings.algorithm,'engine') || strcmp(contSettings.algorithm,'complete')) figures.MEA = figure('Name', 'Predicted apogee','ToolBar','auto'); sgtitle('MEA') @@ -66,7 +66,7 @@ if ~settings.electronics end end plot( -simOutput.Y(:, 3), -v_ned(:,3),'b','DisplayName','Traj') -plot( -simOutput.sensors.nas.states(:,3)-settings.z0, -simOutput.sensors.nas.states(:,6),'m--','DisplayName','NAS') +plot( -simOutput.sensors.nas.states(:,3)-environment.z0, -simOutput.sensors.nas.states(:,6),'m--','DisplayName','NAS') % plot( structIn.ADA(:,4), structIn.ADA(:,5),'b','DisplayName','ADA z') yyaxis right plot( -simOutput.Y(:, 3), simOutput.Y(:, 14),'g','DisplayName','arb') @@ -136,7 +136,7 @@ if not(settings.scenario == "descent") legend('simulated','reference values','Airbrakes deployment','Apogee') if settings.flagExportPLOTS == true - exportStandardizedFigure(figures.servo_angle,"report_images\"+settings.mission+"\src_servo_angle.pdf",0.9) + exportStandardizedFigure(figures.servo_angle,"report_images\"+mission.name+"\src_servo_angle.pdf",0.9) end end % parafoil @@ -156,7 +156,7 @@ end figures.trajectory = figure('Name', 'Trajectory','ToolBar','auto','Position',[100,100,600,400]); plot3(simOutput.Y(1:end-10, 2), simOutput.Y(1:end-10, 1), -simOutput.Y(1:end-10, 3),'DisplayName','True trajectory'); hold on; grid on; -plot3(simOutput.sensors.nas.states(1:end-10, 2), simOutput.sensors.nas.states(1:end-10, 1), -simOutput.sensors.nas.states(1:end-10, 3)-settings.z0,'DisplayName','NAS trajectory'); +plot3(simOutput.sensors.nas.states(1:end-10, 2), simOutput.sensors.nas.states(1:end-10, 1), -simOutput.sensors.nas.states(1:end-10, 3)-environment.z0,'DisplayName','NAS trajectory'); if not(settings.scenario == "descent") plot3(simOutput.ARB.openingPosition(2),simOutput.ARB.openingPosition(1),simOutput.ARB.openingPosition(3),'ko','DisplayName','Airbrake deployment') @@ -180,7 +180,7 @@ axis equal view([157,55]) legend if settings.flagExportPLOTS == true - exportStandardizedFigure(figures.trajectory,"report_images\"+settings.mission+"\src_trajectory.pdf",0.49) + exportStandardizedFigure(figures.trajectory,"report_images\"+mission.name+"\src_trajectory.pdf",0.49) end %% Velocities BODY w.r.t. time against NAS @@ -237,7 +237,7 @@ ylabel('V_z [m/s]'); sgtitle('Velocities BODY'); legend if settings.flagExportPLOTS == true - exportStandardizedFigure(figures.velocities_BODY,"report_images\"+settings.mission+"\src_velocities_BODY.pdf",0.9) + exportStandardizedFigure(figures.velocities_BODY,"report_images\"+mission.name+"\src_velocities_BODY.pdf",0.9) end %% Velocities NED w.r.t. time against NAS @@ -277,12 +277,12 @@ ylabel('V_z [m/s]'); sgtitle('Velocities NED'); legend if settings.flagExportPLOTS == true - exportStandardizedFigure(figures.velocities_NED,"report_images\"+settings.mission+"\src_velocities_NED.pdf",0.9) + exportStandardizedFigure(figures.velocities_NED,"report_images\"+mission.name+"\src_velocities_NED.pdf",0.9) end %% check consistency of NAS: -altitude = simOutput.sensors.nas.states(:,3)+settings.z0; +altitude = simOutput.sensors.nas.states(:,3)+environment.z0; v_int_NAS = 0; v_int_simulation = 0; for i = 2:length(simOutput.sensors.nas.states(:,6)) @@ -388,7 +388,7 @@ ylabel('r [rad/s]'); sgtitle('Angular rotations BODY'); legend if settings.flagExportPLOTS == true - exportStandardizedFigure(figures.velocities,"report_images\"+settings.mission+"\src_Angular_rotations_BODY.pdf",0.9) + exportStandardizedFigure(figures.velocities,"report_images\"+mission.name+"\src_Angular_rotations_BODY.pdf",0.9) end diff --git a/simulator/src/std_run.m b/simulator/src/std_run.m index 7851d4855a78687925ccce9f930fc40c6dd85837..0b54998b9b7731082da43d094963111c303d4705 100644 --- a/simulator/src/std_run.m +++ b/simulator/src/std_run.m @@ -1,4 +1,4 @@ -function [struct_out] = std_run(settings, contSettings, varargin) +function [struct_out] = std_run(settings, contSettings, rocket, environment, mission, varargin) %{ STD_RUN_BALLISTIC - This function runs a standard ballistic (non-stochastic) simulation @@ -40,30 +40,24 @@ Revision date: 11/04/2022 %} -if nargin > 2 +if nargin > 5 settings_mont = varargin{1}; - settings.motor.expThrust = settings_mont.motor.expThrust; - settings.motor.expTime = settings_mont.motor.expTime; - settings.motor.K = settings_mont.motor.K; - settings.tb = settings_mont.tb; - settings.Coeffs = settings_mont.Coeffs; - switch settings.windModel - case "constant" - settings.wind.uw = settings_mont.wind.uw; - settings.wind.vw = settings_mont.wind.vw; - settings.wind.ww = settings_mont.wind.ww; - settings.wind.Az = settings_mont.wind.Az; - settings.wind.El = settings_mont.wind.El; - case "multiplicative" - settings.wind.inputGround = settings_mont.wind.Mag; - % settings.wind.inputAzimut = settings_mont.wind.Az; - settings.wind.input_uncertainty = settings_mont.wind.unc; - end - - settings.State.xcgTime = settings_mont.State.xcgTime; + rocket.motor.thrust = settings_mont.motor.expThrust; + rocket.motor.time = settings_mont.motor.expTime; + % rocket.motor.time(end) = settings_mont.tb; settings.mass_offset = settings_mont.mass_offset; - settings.OMEGA = settings_mont.OMEGA; - settings.PHI = settings_mont.PHI; + settings.motor.K = settings_mont.motor.K; + rocket.coefficients.total = settings_mont.Coeffs; + wind = settings_mont.wind; + + rocket.coefficients.state.xcgTime = settings_mont.State.xcgTime; + environment.omega = settings_mont.OMEGA; + environment.phi = settings_mont.PHI; +end + +if ~exist("wind", "var") + % If the wind was not already defined, generate new one + wind = WindCustom(mission); end if settings.electronics % global variables slow down a bit the comunication over thread, we don't need these for montecarlo analysis @@ -72,20 +66,20 @@ if settings.electronics % global variables slow down a bit the comunication over end %% ode states initialization ( initial conditions ) - % Attitude initial condition +% Attitude initial condition if settings.scenario ~= "descent" % Attitude - Q0 = angle2quat(settings.PHI, settings.OMEGA, 0*pi/180, 'ZYX')'; + Q0 = angle2quat(environment.phi, environment.omega, 0*pi/180, 'ZYX')'; % State X0 = [0; 0; 0]; % Position initial condition V0 = [0; 0; 0]; % Velocity initial condition W0 = [0; 0; 0]; % Angular speed initial condition else % Attitude - Q0 = angle2quat(settings.PHI, 0, 0, 'ZYX')'; - % State + Q0 = angle2quat(environment.phi, 0, 0, 'ZYX')'; + % State X0 = [0; 0; -settings.z_final]; % Position initial condition -settings.z_final V0 = [0; 0; -settings.Vz_final]; % Velocity initial condition W0 = [0; 0; 0]; % Angular speed initial condition @@ -98,15 +92,12 @@ initialCond = [X0; V0; W0; Q0; ap0; deltaA0]; Y0 = initialCond'; %% WIND GENERATION -[uw, vw, ww, Az , El, Mag] = std_setWind(settings); -settings.constWind = [uw, vw, ww]; -settings.wind.Mag = Mag; -settings.wind.El = El; -settings.wind.Az = Az; +% [uw, vw, ww, Az , El, Mag] = std_setWind(settings); +% settings.constWind = [uw, vw, ww]; +% settings.wind.Mag = Mag; +% settings.wind.El = El; +% settings.wind.Az = Az; -%% stochastic parameter settings: -settings.ms = settings.ms + settings.mass_offset; -settings.mTotalTime = settings.mTotalTime + settings.mass_offset; %% INTEGRATION % integration time @@ -121,9 +112,11 @@ if mod(dt/dt_ode,1)~= 0 end std_setInitialParams; +rocket.massNoMotor = rocket.massNoMotor + settings.mass_offset; +rocket.updateMass; %% SENSORS INIT -run(strcat('initSensors', settings.mission)); +run(strcat('initSensors', mission.name)); %% MAGNETIC FIELD MODEL std_magneticField; @@ -186,7 +179,7 @@ while settings.flagStopIntegration && n_old < nmax % St lastFlagAscent = settings.flagAscent; % Saves the last value of the flagAscent to recall it later lastFlagExpulsion2 = eventExpulsion2; % saves the last value of the expulsion to recall the opening of the second chute later - + if settings.launchWindow if not(settings.lastLaunchFlag) && launchFlag std_setInitialParams @@ -208,15 +201,15 @@ while settings.flagStopIntegration && n_old < nmax % St flagFlight = false; flagAeroBrakes = false; settings.flagAscent = false; - + % Transition to powered_ascent if launchFlag && t0 > time_on_ground state_lastTime(currentState) = t0; - + % Exit condition of on_ground / Entry condition of powered_ascent: - % Here are setup all the time variables - % that require to be offset depending on when the liftoff actually happens, - % i.e. all the engine time variables that otherwise require the simulation time t0 + % Here are setup all the time variables + % that require to be offset depending on when the liftoff actually happens, + % i.e. all the engine time variables that otherwise require the simulation time t0 % to be reset to 0 flagFlight = true; engineT0 = t0-dt; @@ -229,7 +222,7 @@ while settings.flagStopIntegration && n_old < nmax % St end end case availableStates.powered_ascent - + flagFlight = true; settings.flagAscent = true; lastAscentIndex = n_old-1; @@ -251,8 +244,8 @@ while settings.flagStopIntegration && n_old < nmax % St settings.flagAscent = true; lastAscentIndex = n_old-1; - % Transitions out of unpowered_ascent: - % drogue_descent if full_flight, + % Transitions out of unpowered_ascent: + % drogue_descent if full_flight, % landed if apogee was never detected if flagApogee state_lastTime(currentState) = t0; @@ -281,7 +274,7 @@ while settings.flagStopIntegration && n_old < nmax % St flagAeroBrakes = false; lastDrogueIndex = n_old-1; - % Transition out of drogue_descent: + % Transition out of drogue_descent: % parachute_descent if main parachute, payload_descent if parafoil if flagOpenPara state_lastTime(currentState) = t0; @@ -300,7 +293,7 @@ while settings.flagStopIntegration && n_old < nmax % St disp("Transition to parachute descent"); end end - + end case availableStates.parachute_descent @@ -342,21 +335,24 @@ while settings.flagStopIntegration && n_old < nmax % St otherwise error("Invalid state requested"); end - + % For ascent only we stop the simulation once the ode apogee has been reached if vz(end) < 0 && flagFlight && settings.ascentOnly break; end - + %% dynamics (ODE) %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% tspan = t0:dt_ode:t1; + control.angleRef = ap_ref; + control.timeChangeRef = t_change_ref_ABK; if flagFlight if settings.ballisticFligth Y0_ode = Y0(1:14); - [Tf, Yd] = ode4(@ascentControl, tspan, Y0_ode, settings,[], ap_ref, t_change_ref_ABK, engineT0); - parout = RecallOdeFcn(@ascentControl, Tf, Yd, settings,[], Yd(:,14), t_change_ref_ABK,engineT0,'apVec'); + [Tf, Yd] = ode4(@ballistic, tspan, Y0_ode, rocket, environment, wind, control, engineT0); + control.angleRef = Yd(:,14); + parout = RecallOdeFcn(@ballistic, Tf, Yd, rocket, environment, wind, control, engineT0); [nd, ~] = size(Yd); Yf = [Yd, ones(nd,1)*Y0(end,15)]; para = NaN; @@ -364,30 +360,39 @@ while settings.flagStopIntegration && n_old < nmax % St switch currentState case {availableStates.powered_ascent, availableStates.unpowered_ascent} Y0_ode = Y0(1:14); - [Tf, Yd] = ode4(@ascentControl, tspan, Y0_ode, settings,[], ap_ref, t_change_ref_ABK, engineT0); - parout = RecallOdeFcn(@ascentControl, Tf, Yd, settings,[], Yd(:,14), t_change_ref_ABK,engineT0,'apVec'); + [Tf, Yd] = ode4(@ballistic, tspan, Y0_ode, rocket, environment, wind, control, engineT0); + control.angleRef = Yd(:,14); + parout = RecallOdeFcn(@ballistic, Tf, Yd, rocket, environment, wind, control, engineT0); [nd, ~] = size(Yd); Yf = [Yd, ones(nd,1)*Y0(end,15)]; para = NaN; case availableStates.drogue_descent - para = 1; + if settings.parafoil; descentData.stage = 2; else; descentData.stage = 1; end + descentData.para = 1; Y0_ode = Y0(:,1:6); - [Tf, Yd] = ode4(@descentParachute, tspan, Y0_ode, settings, uw, vw, ww, para, Y0(end,10:13),tLaunch); % ..., para, uncert); - parout = RecallOdeFcn(@descentParachute, Tf, Yd, settings, uw, vw, ww, para, Y0(end,10:13),tLaunch); + Q0_ode = Y0(end, 10:13); + [Tf, Yd] = ode4(@descentParachute, tspan, Y0_ode, rocket, environment, wind, descentData, [], Q0_ode); + parout = RecallOdeFcn(@descentParachute, Tf, Yd, rocket, environment, wind, descentData, [], Q0_ode); [nd, ~] = size(Yd); Yf = [Yd, zeros(nd, 3), ones(nd,1).*Y0(end,10:13), zeros(nd,2)]; case availableStates.parachute_descent - para = 2; + descentData.para = 2; + descentData.stage = 1; Y0_ode = Y0(:,1:6); - [Tf, Yd] = ode4(@descentParachute, tspan, Y0_ode, settings, uw, vw, ww, para, Y0(end,10:13),tLaunch); % ..., para, uncert); - parout = RecallOdeFcn(@descentParachute, Tf, Yd, settings, uw, vw, ww, para, Y0(end,10:13)); + Q0_ode = Y0(end, 10:13); + [Tf, Yd] = ode4(@descentParachute, tspan, Y0_ode, rocket, environment, wind, descentData, [], Q0_ode); + parout = RecallOdeFcn(@descentParachute, Tf, Yd, rocket, environment, wind, descentData, [], Q0_ode); [nd, ~] = size(Yd); Yf = [Yd, zeros(nd, 3), ones(nd,1).*Y0(end,10:13), zeros(nd,2)]; case availableStates.payload_descent + descentData.para = 2; + descentData.stage = 2; Y0_ode = Y0(:,[1:13,15]); - [Tf, Yd] = ode4(@descentParafoil, tspan, Y0_ode, settings,contSettings, deltaA_ref, t_change_ref_PRF,tLaunch); - parout = RecallOdeFcn(@descentParafoil, Tf, Yd, settings,contSettings, Yd(:,14),t_change_ref_PRF,tLaunch,'apVec'); + control.deltaARef = deltaA_ref; + control.timeChangeRef = t_change_ref_PRF; + [Tf, Yd] = ode4(@descentParafoil, tspan, Y0_ode, rocket, environment, wind, descentData, control, engineT0); + parout = RecallOdeFcn(@descentParafoil, Tf, Yd, rocket, environment, wind, descentData, control, engineT0); [nd, ~] = size(Yd); Yf = [Yd(:,1:13), zeros(nd,1),Yd(:,14)]; end @@ -397,15 +402,16 @@ while settings.flagStopIntegration && n_old < nmax % St Yf = [Y0; Y0]; para = NaN; end - + % recall some useful parameters settings.parout.partial_time = Tf; - if currentState == availableStates.on_ground - % If the rocket is on groud, the accelerometer should measure + control.partialTime = Tf; + if currentState == availableStates.on_ground + % If the rocket is on groud, the accelerometer should measure % the gravity acceleration on ramp. Q_acc = quat2rotm(Q0'); settings.parout.acc = (Q_acc'*[zeros(length(Tf),2) -9.81*ones(length(Tf), 1)]')'; - settings.parout.m = settings.mTotalTime(1)*ones(1,length(Tf)); + settings.parout.m = rocket.mass(1)*ones(1,length(Tf)); elseif currentState == availableStates.landed settings.parout.acc = [zeros(length(Tf),2) -9.81*ones(length(Tf),1)]; settings.parout.m = ones(1,length(Tf))*settings.parout.m(end); @@ -414,8 +420,7 @@ while settings.flagStopIntegration && n_old < nmax % St settings.parout.m = parout.interp.mass; end - - ext = extension_From_Angle(Yf(end,14),settings); % bug fix, check why this happens because sometimes happens that the integration returns a value slightly larger than the max value of extension for airbrakes and this mess things up + ext = extension_From_Angle(Yf(end,14),settings,mission); % bug fix, check why this happens because sometimes happens that the integration returns a value slightly larger than the max value of extension for airbrakes and this mess things up if ext > settings.arb.maxExt ext = settings.arb.maxExt; warning("the extension of the airbrakes exceeds the maximum value of "+num2str(settings.arb.maxExt)+": ext = "+num2str(ext)) @@ -424,14 +429,16 @@ while settings.flagStopIntegration && n_old < nmax % St %% simulate sensors % [sensorData] = manageSignalFrequencies(magneticFieldApprox, settings.flagAscent, settings,sensorData, Yf, Tf, uw, vw, ww); - wind = [uw, vw, ww]; - [sensorData] = generateSensorMeasurements(magneticFieldApprox, Yf, Tf, wind, sensorData,sensorTot, settings, engineT0, currentState, availableStates); - + % wind = [uw, vw, ww]; + [uw, vw, ww] = wind.getVels(-Yf(end, 3)); + wind_vector = [uw, vw, ww]; + [sensorData] = generateSensorMeasurements(magneticFieldApprox, Yf, Tf, wind_vector, sensorData,sensorTot, settings, engineT0, currentState, availableStates, environment, mission, rocket); + % simulate sensor acquisition if settings.dataNoise - [sensorData, sensorTot] = acquisition_Sys(sensorData, sensorSettings, sensorTot, settings, t0); + [sensorData, sensorTot] = acquisition_Sys(sensorData, sensorSettings, sensorTot, t0, mission); end - + %% subsystems % SIMU SIMU SIMU SIMU SIMU SIMU SIMU SIMU SIMU SIMU @@ -448,10 +455,10 @@ while settings.flagStopIntegration && n_old < nmax % St % airbrakes reference update (for the ODE) ap_ref = [ ap_ref_old ap_ref_new ]; - + % parafoil control action update for the ODE deltaA_ref = [ deltaA_ref_old deltaA_ref_new ]; - + %% vertical velocity for update of the state machine if settings.flagAscent || (not(settings.flagAscent) && settings.ballisticFligth) || currentState == availableStates.parachute_descent @@ -461,7 +468,7 @@ while settings.flagStopIntegration && n_old < nmax % St vx = vels(2); % north vy = vels(1); % east else - vz = - Yf(end, 6); + vz = - Yf(end, 6); vx = Yf(end, 5); vy = Yf(end, 4); end @@ -473,11 +480,11 @@ while settings.flagStopIntegration && n_old < nmax % St % the current simulation step, because the parac Q = Yf(end, 10:13); vels = quatrotate(quatconj(Q), Yf(end, 4:6)); - Y0 = [Yf(end, 1:3), vels, Yf(end, 7:end)]; - elseif ~lastFlagExpulsion2 && eventExpulsion2 && not(settings.scenario == "ballistic") - Q = Yf(end, 10:13); - vels = quatrotate(Q, Yf(end, 4:6)); Y0 = [Yf(end, 1:3), vels, Yf(end, 7:end)]; + % elseif ~lastFlagExpulsion2 && eventExpulsion2 && not(settings.scenario == "ballistic") + % Q = Yf(end, 10:13); + % vels = quatrotate(Q, Yf(end, 4:6)); + % Y0 = [Yf(end, 1:3), vels, Yf(end, 7:end)]; else Y0 = Yf(end, :); end @@ -488,23 +495,23 @@ while settings.flagStopIntegration && n_old < nmax % St normV = norm([vz vx vy]); mach = normV/a; - %% wind update - if settings.windModel == "multiplicative" + %%% wind update + % if settings.windModel == "multiplicative" + % + % [uw, vw, ww] = windInputGenerator(settings, -Y0(3), settings.wind.inputUncertainty); + % + % settings.constWind = [uw, vw, ww]; + % + % windMag = [windMag sqrt(uw^2+vw^2+ww^2)]; + % windAz = [windAz atan2(sqrt(uw^2+vw^2+ww^2)/vw,sqrt(uw^2+vw^2+ww^2)/uw)]; + % end - [uw, vw, ww] = windInputGenerator(settings, -Y0(3), settings.wind.inputUncertainty); - - settings.constWind = [uw, vw, ww]; - - windMag = [windMag sqrt(uw^2+vw^2+ww^2)]; - windAz = [windAz atan2(sqrt(uw^2+vw^2+ww^2)/vw,sqrt(uw^2+vw^2+ww^2)/uw)]; - end - if t1-t_last_arb_control >= 1/settings.frequencies.arbFrequency - 1e-6 t_change_ref_ABK = t1 + settings.servo.delay; end if t1-t_last_prf_control >= 1/settings.frequencies.prfFrequency - 1e-6 - t_change_ref_PRF = t1 + contSettings.payload.deltaA_delay; + t_change_ref_PRF = t1 + rocket.parachutes(2,2).controlParams.deltaA_delay; end % assemble total state [n, ~] = size(Yf); @@ -517,7 +524,7 @@ while settings.flagStopIntegration && n_old < nmax % St sensorTot.sfd.time(iTimes) = t1; sensorTot.sfd.pressure(iTimes) = sensorData.barometer.measures(end); % sensorTot.sfd.faults(iTimes,:) = settings.faulty_sensors; - dataRecall.true_mass(n_old:n_old+n-1, 1) = settings.parout.m'; % if you want to save other parameters, remember to go down and remove the last two values + dataRecall.true_mass(n_old:n_old+n-1, 1) = settings.parout.m'; % if you want to save other parameters, remember to go down and remove the last two values n_old = n_old + n -1; @@ -529,11 +536,11 @@ while settings.flagStopIntegration && n_old < nmax % St if not(settings.montecarlo) if settings.flagAscent - disp("z: " + (-Yf(end,3)+settings.z0) +", z_est: " + -sensorData.kalman.z + ", ap_ref: " + ap_ref_new + ", ap_ode: " + Yf(end,14)); % + ", quatNorm: "+ vecnorm(Yf(end,10:13)) + disp("z: " + (-Yf(end,3)+environment.z0) +", z_est: " + -sensorData.kalman.z + ", ap_ref: " + ap_ref_new + ", ap_ode: " + Yf(end,14)); % + ", quatNorm: "+ vecnorm(Yf(end,10:13)) elseif currentState == availableStates.payload_descent - disp("z: " + (-Yf(end,3)+settings.z0) +", z_est: " + -sensorData.kalman.z + ", deltaA_ref: " + deltaA_ref_new + ", deltaA_ode: " + Yf(end,15)); % +", quatNorm: "+ vecnorm(Yf(end,10:13)) + disp("z: " + (-Yf(end,3)+environment.z0) +", z_est: " + -sensorData.kalman.z + ", deltaA_ref: " + deltaA_ref_new + ", deltaA_ode: " + Yf(end,15)); % +", quatNorm: "+ vecnorm(Yf(end,10:13)) else - disp("z: " + (-Yf(end,3)+settings.z0) +", z_est: " + -sensorData.kalman.z); + disp("z: " + (-Yf(end,3)+environment.z0) +", z_est: " + -sensorData.kalman.z); end end @@ -556,7 +563,7 @@ end t_ada = settings.ada.t_ada; settings.flagMatr = settings.flagMatr(1:n_old, :); -%% RETRIVE PARAMETERS FROM THE ODE (RECALL ODE) +%% RETRIVE PARAMETERS FROM THE ODE (RECALL ODE) % if ~settings.electronics && ~settings.montecarlo && not(settings.scenario == "descent") % settings.wind.output_time = Tf; @@ -575,9 +582,9 @@ struct_out.Y = Yf; % struct_out.flags = settings.flagMatr; struct_out.state_lastTimes = state_lastTime; % wind -struct_out.wind.Mag = settings.wind.Mag; -struct_out.wind.Az = settings.wind.Az; -struct_out.wind.El = settings.wind.El; +struct_out.wind.Mag = wind.magnitude(1); +struct_out.wind.Az = wind.azimuth(1); +% struct_out.wind.El = wind.El(1); struct_out.wind.Vel = [uw, vw, ww]; % sensors (ADA, NAS, MEA, SFD, and all sensor data are stored here) @@ -631,7 +638,7 @@ if settings.scenario == "descent" || settings.scenario == "full flight" struct_out.PRF.landing_velocities_BODY = Yf(idx_landing,4:6); struct_out.PRF.landing_velocities_NED = quatrotate(quatconj(Yf(idx_landing,10:13)),Yf(idx_landing,4:6)); % deployment - struct_out.PRF.deploy_altitude_set = settings.para(1).z_cut + settings.z0; % set altitude for deployment + % struct_out.PRF.deploy_altitude_set = settings.para(1).z_cut + environment.z0; % set altitude for deployment struct_out.PRF.deploy_position = Yf(lastDrogueIndex+1,1:3); % actual position of deployment struct_out.PRF.deploy_velocity = Yf(lastDrogueIndex+1,4:6); else diff --git a/simulator/src/std_run_parts/run_ARB_SIM.m b/simulator/src/std_run_parts/run_ARB_SIM.m index f47bbd819e8554e22e45866e2d7acab6973ba78d..94083aea9e4c3f9b2cb8473d97b20fd44b663429 100644 --- a/simulator/src/std_run_parts/run_ARB_SIM.m +++ b/simulator/src/std_run_parts/run_ARB_SIM.m @@ -1,4 +1,4 @@ -function [ap_ref_new,contSettings,varargout] = run_ARB_SIM(sensorData,settings,contSettings,ap_ref_old) +function [ap_ref_new,contSettings,varargout] = run_ARB_SIM(sensorData,settings,contSettings,ap_ref_old,environment) %% HELP: @@ -31,19 +31,19 @@ switch true % set this value in configControl.m case strcmp(contSettings.algorithm,'interp') || strcmp(contSettings.algorithm,'complete') % help in the function - [ap_ref_new,contSettings] = control_Interp(-sensorData.kalman.z-settings.z0,-sensorData.kalman.vz,settings,contSettings,ap_ref_old); % cambiare nome alla funzione tra le altre cose + [ap_ref_new,contSettings] = control_Interp(-sensorData.kalman.z-environment.z0,-sensorData.kalman.vz,settings,contSettings,ap_ref_old); % cambiare nome alla funzione tra le altre cose case strcmp (contSettings.algorithm,'shooting') % shooting algorithm: - [ap_ref_new] = control_Interp(-sensorData.kalman.z-settings.z0,-sensorData.kalman.vz,contSettings.reference.Z,contSettings.reference.Vz,'linear',contSettings.N_forward,settings); % cambiare nome alla funzione tra le altre cose + [ap_ref_new] = control_Interp(-sensorData.kalman.z-environment.z0,-sensorData.kalman.vz,contSettings.reference.Z,contSettings.reference.Vz,'linear',contSettings.N_forward,settings); % cambiare nome alla funzione tra le altre cose init.options = optimoptions("lsqnonlin","Display","off"); if not(contSettings.flagFilter) - [ap_ref_new] = control_Shooting([-sensorData.kalman.z-settings.z0,-sensorData.kalman.vz],ap_ref_new,settings,contSettings.coeff_Cd,settings.arb,init); + [ap_ref_new] = control_Shooting([-sensorData.kalman.z-environment.z0,-sensorData.kalman.vz],ap_ref_new,settings,contSettings.coeff_Cd,settings.arb,init); else - [ap_base_filter] = control_Shooting([-sensorData.kalman.z-settings.z0,-sensorData.kalman.vz],ap_ref_new,settings,contSettings.coeff_Cd,settings.arb,init); + [ap_base_filter] = control_Shooting([-sensorData.kalman.z-environment.z0,-sensorData.kalman.vz],ap_ref_new,settings,contSettings.coeff_Cd,settings.arb,init); % filter control action if contSettings.flagFirstControlABK == false % the first reference is given the fastest possible (unfiltered), then filter diff --git a/simulator/src/std_run_parts/run_MTR_SIM.m b/simulator/src/std_run_parts/run_MTR_SIM.m index da1c52a059c07135581b3d7595009d01b72b5fe3..0ff11e03ea5ed145ba8934e3577110d3c2ce8e5f 100644 --- a/simulator/src/std_run_parts/run_MTR_SIM.m +++ b/simulator/src/std_run_parts/run_MTR_SIM.m @@ -1,72 +1,91 @@ -function [sensorData,sensorTot,settings,contSettings] = run_MTR_SIM (sensorData,sensorTot,settings,contSettings,T1, engineT0,dt_ode) +function [sensorData,sensorTot,settings,contSettings,rocket] = run_MTR_SIM... + (sensorData,sensorTot,settings,contSettings,T1, engineT0,dt_ode,rocket,environment, mission) - % impose valve position - if T1 < settings.timeEngineCut - u = 1; - else - u = 0; - end - if ~settings.flagMEAInit - sensorTot.mea.time = T1-dt_ode; - settings.flagMEAInit = true; - end - - [sensorData,sensorTot] = run_MEA(sensorData,sensorTot,settings,contSettings,u,T1); - - if sensorTot.mea.prediction(end) >= settings.mea.z_shutdown - settings.mea.counter_shutdown = settings.mea.counter_shutdown + 1*floor(settings.frequencies.MEAFrequency/settings.frequencies.controlFrequency); % the last multiplication is to take into account the frequency difference - if ~settings.expShutdown - if settings.mea.counter_shutdown > contSettings.N_prediction_threshold %&& T1 > settings.mea.t_lower_shadowmode% threshold set in configControl - settings.expShutdown = true; - settings.t_shutdown = T1; - settings.timeEngineCut = settings.t_shutdown + settings.shutdownValveDelay; - settings.expTimeEngineCut = settings.t_shutdown; - end - if T1-engineT0 >= settings.mea.t_higher_shadowmode - settings.expShutdown = true; - settings.t_shutdown = T1; - settings.timeEngineCut = settings.t_shutdown + settings.shutdownValveDelay; - settings.expTimeEngineCut = settings.t_shutdown; - end - end - if T1-engineT0 < settings.tb - settings.IengineCut = interpLinear(settings.motor.expTime, settings.I, T1-engineT0); - else - settings.IengineCut = interpLinear(settings.motor.expTime, settings.I, settings.tb); - end - settings.expMengineCut = settings.parout.m(end) - settings.ms; - if T1 > settings.timeEngineCut - settings.shutdown = true; - settings = settingsEngineCut(settings, engineT0); - settings.quatCut = [sensorTot.nas.states(end, 10) sensorTot.nas.states(end, 7:9)]; - [~,settings.pitchCut,~] = quat2angle(settings.quatCut,'ZYX'); - end - - contSettings.valve_pos = 0; - % else - % settings.t_shutdown = nan; - % end - else - if ~settings.expShutdown && T1-engineT0 >= settings.mea.t_higher_shadowmode +% impose valve position +if T1 < rocket.motor.cutoffTime + u = 1; +else + u = 0; +end +if ~settings.flagMEAInit + sensorTot.mea.time = T1-dt_ode; + settings.flagMEAInit = true; +end +[sensorData,sensorTot] = run_MEA(sensorData,sensorTot,settings,contSettings,u,T1,engineT0,environment,rocket, mission); +if sensorTot.mea.prediction(end) >= settings.mea.z_shutdown + settings.mea.counter_shutdown = settings.mea.counter_shutdown + 1*floor(settings.frequencies.MEAFrequency/settings.frequencies.controlFrequency); % the last multiplication is to take into account the frequency difference + if ~settings.expShutdown + if settings.mea.counter_shutdown > contSettings.N_prediction_threshold %&& T1 > settings.mea.t_lower_shadowmode% threshold set in configControl settings.expShutdown = true; settings.t_shutdown = T1; - settings.timeEngineCut = settings.t_shutdown + settings.shutdownValveDelay; + rocket.motor.cutoffTime = settings.t_shutdown + settings.shutdownValveDelay; settings.expTimeEngineCut = settings.t_shutdown; + [settings, rocket] = settingsEngineCut(settings, engineT0, rocket); end - if T1-engineT0 < settings.tb - settings.IengineCut = interpLinear(settings.motor.expTime, settings.I, T1-engineT0); - else - settings.IengineCut = interpLinear(settings.motor.expTime, settings.I, settings.tb); - end - settings.expMengineCut = settings.parout.m(end) - settings.ms; - if T1 > settings.timeEngineCut - settings.shutdown = true; - settings = settingsEngineCut(settings, engineT0); - settings.quatCut = [sensorTot.nas.states(end, 10) sensorTot.nas.states(end, 7:9)]; - [~,settings.pitchCut,~] = quat2angle(settings.quatCut,'ZYX'); + if T1-engineT0 >= settings.mea.t_higher_shadowmode + settings.expShutdown = true; + settings.t_shutdown = T1; + rocket.motor.cutoffTime = settings.t_shutdown + settings.shutdownValveDelay; + settings.expTimeEngineCut = settings.t_shutdown; end - settings.counter_shutdown = 0; + + + end + + % if settings.expShutdown + % if T1-engineT0 < rocket.motor.time(end) + % % if rocket.motor.cutoffTime > rocket.motor.time(end) + % % rocket.motor.cutoffTime = rocket.motor.cutoffTime - engineT0; + % % end + % cutoff = rocket.motor.cutoffTime; + % rocket.motor.cutoffTime = T1 - engineT0; + % rocket.updateCutoff; + % rocket.motor.cutoffTime = cutoff; + % % settings.IengineCut = interpLinear(settings.motor.expTime, settings.I, T1-engineT0); + % else + % rocket.motor.cutoffTime = rocket.motor.time(end); + % rocket.updateCutoff; + % % settings.IengineCut = interpLinear(settings.motor.expTime, settings.I, settings.tb); + % end + % end + + settings.expMengineCut = settings.parout.m(end) - (rocket.massNoMotor + rocket.motor.mass(end)); + if T1 - engineT0 > rocket.motor.cutoffTime + settings.shutdown = true; + % rocket.updateCutoff; + % [settings, rocket] = settingsEngineCut(settings, engineT0, rocket); + % settings.quatCut = [sensorTot.nas.states(end, 10) sensorTot.nas.states(end, 7:9)]; + % [~,settings.pitchCut,~] = quat2angle(settings.quatCut,'ZYX'); + end + + contSettings.valve_pos = 0; + % else + % settings.t_shutdown = nan; + % end +else + if ~settings.expShutdown && T1-engineT0 >= settings.mea.t_higher_shadowmode + settings.expShutdown = true; + settings.t_shutdown = T1; + rocket.motor.cutoffTime = settings.t_shutdown + settings.shutdownValveDelay; + settings.expTimeEngineCut = settings.t_shutdown; end + % if T1-engineT0 < rocket.motor.time(end) + % rocket.updateCutoff; + % settings.IengineCut = interpLinear(rocket.motor.time, rocket.inertia, T1-engineT0); + % else + % rocket.updateCutoff; + % % settings.IengineCut = interpLinear(rocket.motor.time, rocket.inertia, rocket.motor.time(end)); + % end + settings.expMengineCut = settings.parout.m(end) - (rocket.massNoMotor + rocket.motor.mass(end)); + if T1 - engineT0 > rocket.motor.cutoffTime + settings.shutdown = true; + rocket.updateCutoff; + [settings,rocket] = settingsEngineCut(settings, engineT0, rocket); + settings.quatCut = [sensorTot.nas.states(end, 10) sensorTot.nas.states(end, 7:9)]; + [~,settings.pitchCut,~] = quat2angle(settings.quatCut,'ZYX'); + end + settings.counter_shutdown = 0; +end end diff --git a/simulator/src/std_run_parts/run_parafoilGuidance.m b/simulator/src/std_run_parts/run_parafoilGuidance.m index b6fbce65e6b929ab5a8caaeb5e509e626ce3ccb9..7d755d54d3fee1264bb46e5c88a2d5b42db80469 100644 --- a/simulator/src/std_run_parts/run_parafoilGuidance.m +++ b/simulator/src/std_run_parts/run_parafoilGuidance.m @@ -1,4 +1,4 @@ -function [deltaA_ref, contSettings] = run_parafoilGuidance(pos_est, vel_est, wind_est, target, contSettings) +function [deltaA_ref, contSettings] = run_parafoilGuidance(pos_est, vel_est, wind_est, target, contSettings, controlParams) % HELP: % % parafoil guidance algorithm @@ -43,16 +43,16 @@ else % compute heading difference error_psi = angdiff(psi,psi_ref); - P = contSettings.payload.Kp * error_psi; + P = controlParams.Kp * error_psi; if contSettings.payload.saturation == false - contSettings.payload.I = contSettings.payload.Ki * error_psi + contSettings.payload.I; + contSettings.payload.I = controlParams.Ki * error_psi + contSettings.payload.I; end deltaA_ref = P + contSettings.payload.I; - [deltaA_ref,contSettings.payload.saturation] = Saturation(deltaA_ref,contSettings.payload.uMin, contSettings.payload.uMax); + [deltaA_ref,contSettings.payload.saturation] = Saturation(deltaA_ref,controlParams.uMin, controlParams.uMax); % inserire WES conditions % storia dei 15 secondi di calibrazione etc diff --git a/simulator/src/std_run_parts/std_hardwareInTheLoop.m b/simulator/src/std_run_parts/std_hardwareInTheLoop.m index 1b679fab906b6c69b0a21d09ebaae6f8e5aa660b..c4e56199e94fbe92df3c3462820e32922e3cf3db 100644 --- a/simulator/src/std_run_parts/std_hardwareInTheLoop.m +++ b/simulator/src/std_run_parts/std_hardwareInTheLoop.m @@ -89,7 +89,7 @@ end %% Update Mass estimation data if ~settings.parafoil - if contains(settings.mission,'_2023') || contains(settings.mission,'_2024') + if contains(mission.name,'_2023') || contains(mission.name,'_2024') lastShutdown = settings.shutdown; settings.shutdown = not(flagBurning); @@ -109,7 +109,8 @@ if ~settings.parafoil if settings.shutdown && not(lastShutdown) && flagFlight % Need to check if this happens only once or the condition can be met multiple times t_shutdown = Tf(end); settings.expShutdown = 1; - settings.timeEngineCut = t_shutdown; + settings.shutdown = 1; + rocket.motor.cutoffTime = t_shutdown; settings.expTimeEngineCut = t_shutdown; settings.expMengineCut = m - settings.ms; settings.shutdown = 1; @@ -117,61 +118,58 @@ if ~settings.parafoil settings.quatCut = [sensorTot.nas.states(end,10) sensorTot.nas.states(end, 7:9)]; % why do we take the nas ones and not the simulation ones? [~,settings.pitchCut,~] = quat2angle(settings.quatCut,'ZYX'); sensorTot.mea.t_shutdown = t_shutdown; % to pass the value out of the std_run to the structOut - elseif ~settings.shutdown && Tf(end) >= settings.tb - t_shutdown = settings.tb; - settings.expShutdown = 1; - settings.timeEngineCut = t_shutdown; - settings.expTimeEngineCut = t_shutdown; - settings.expMengineCut = m - settings.ms; - settings.shutdown = 1; - settings = settingsEngineCut(settings); + elseif ~settings.shutdown && Tf(end)-engineT0 >= rocket.motor.time(end) + settings.expShutdown = true; + settings.shutdown = true; + settings.t_shutdown = rocket.motor.time(end); + rocket.motor.cutoffTime = settings.t_shutdown; + settings.expTimeEngineCut = settings.t_shutdown; + % settings.expMengineCut = settings.parout.m(end) - settings.ms; + % settings = settingsEngineCut(settings); settings.quatCut = [sensorTot.nas.states(end,10) sensorTot.nas.states(end, 7:9)]; % why do we take the nas ones and not the simulation ones? [~,settings.pitchCut,~] = quat2angle(settings.quatCut,'ZYX'); sensorTot.mea.t_shutdown = t_shutdown; % to pass the value out of the std_run to the structOut end else - if t0 > settings.motor.expTime(end) + if t0 > rocket.motor.time(end) settings.expShutdown = 1; end end else - if contains(settings.mission,'_2023') || contains(settings.mission,'_2024') - if Tf(end) <= settings.tb+0.5 &&... - (strcmp(contSettings.algorithm,'engine') || strcmp(contSettings.algorithm,'complete')) + if (contains(mission.name,'_2023') || contains(mission.name,'_2024')) && currentState ~= availableStates.on_ground + if (strcmp(contSettings.algorithm,'engine') || strcmp(contSettings.algorithm,'complete')) if isnan(sensorTot.comb_chamber.measures(end)) sensorTot.comb_chamber.measures(end) = 0; end if ~settings.shutdown - [t_shutdown,settings,contSettings,sensorData] =run_MTR_SIM (contSettings,sensorData,settings,sensorTot,Tf); - m = sensorData.mea.estimated_mass(end); - sensorTot.mea.pressure(iTimes) = sensorData.mea.estimated_pressure; - sensorTot.mea.mass(iTimes) = sensorData.mea.estimated_mass; - sensorTot.mea.prediction(iTimes) = sensorData.mea.predicted_apogee; - sensorTot.mea.t_shutdown = t_shutdown; - sensorTot.mea.time(iTimes) = t1; - end - if ~settings.shutdown && Tf(end) >= settings.tb - t_shutdown = settings.tb; - settings.expShutdown = 1; - settings.timeEngineCut = t_shutdown; - settings.expTimeEngineCut = t_shutdown; - settings.expMengineCut = m - settings.ms; - settings.shutdown = 1; - settings = settingsEngineCut(settings); - settings.quatCut = [sensorTot.nas.states(end,10) sensorTot.nas.states(end, 7:9)]; % why do we take the nas ones and not the simulation ones? - [~,settings.pitchCut,~] = quat2angle(settings.quatCut,'ZYX'); - sensorTot.mea.t_shutdown = t_shutdown; % to pass the value out of the std_run to the structOut + [sensorData,sensorTot,settings,contSettings] =run_MTR_SIM (sensorData,sensorTot,settings,contSettings,t1, engineT0,dt_ode); + sensorTot.mea.t_shutdown = settings.t_shutdown; + + if Tf(end)-engineT0 >= rocket.motor.time(end) + settings.expShutdown = true; + settings.shutdown = true; + settings.t_shutdown = rocket.motor.time(end); + rocket.motor.cutoffTime = settings.t_shutdown; + settings.expTimeEngineCut = settings.t_shutdown; + % settings.expMengineCut = settings.parout.m(end) - settings.ms; + % settings = settingsEngineCut(settings); + settings.quatCut = [sensorTot.nas.states(end,10) sensorTot.nas.states(end, 7:9)]; % why do we take the nas ones and not the simulation ones? + [~,settings.pitchCut,~] = quat2angle(settings.quatCut,'ZYX'); + sensorTot.mea.t_shutdown = settings.t_shutdown; % to pass the value out of the std_run to the structOut + end end - elseif ~(strcmp(contSettings.algorithm,'engine') || strcmp(contSettings.algorithm,'complete')) && Tf(end) > settings.tb + + + elseif ~(strcmp(contSettings.algorithm,'engine') || strcmp(contSettings.algorithm,'complete')) && Tf(end)-engineT0 > rocket.motor.time(end) settings.shutdown = 1; settings.expShutdown = 1; - settings.timeEngineCut = settings.tb; - settings.expTimeEngineCut = settings.tb; + rocket.motor.cutoffTime = rocket.motor.time(end); + settings.expTimeEngineCut = rocket.motor.time(end); end else - if t0 > settings.motor.expTime(end) + if t0-engineT0 > rocket.motor.time(end) settings.expShutdown = 1; end end @@ -199,7 +197,7 @@ else if flagAeroBrakes && settings.flagNAS && settings.control && ... ~( strcmp(contSettings.algorithm,'NoControl') || strcmp(contSettings.algorithm,'engine') ) - if (contains(settings.mission,'_2023') || contains(settings.mission,'_2024')) && contSettings.traj_choice == 1 && settings.expShutdown + if (contains(mission.name,'_2023') || contains(mission.name,'_2024')) && contSettings.traj_choice == 1 && settings.expShutdown if ~strcmp(contSettings.algorithm,'complete') m = settings.ms; else @@ -234,7 +232,7 @@ if ~settings.flagAscent && settings.parafoil contSettings.flagFirstControlPRF = false; if contSettings.payload.guidance_alg == "t-approach" pos_est = sensorData.nas.states(end,1:3); - pos_est(3) = -pos_est(3)-settings.z0; + pos_est(3) = -pos_est(3)-environment.z0; [contSettings.payload.EMC,contSettings.payload.M1,contSettings.payload.M2] = setEMCpoints(pos_est,settings.payload.target,contSettings.payload); end end @@ -255,7 +253,7 @@ if ~settings.flagAscent && settings.parafoil % deltaA_ref_old = deltaA_ref_new; % t_last_prf_control = t1; % pos_est = sensorData.nas.states(end,1:3); -% pos_est(3) = -pos_est(3)-settings.z0; +% pos_est(3) = -pos_est(3)-environment.z0; % % [deltaA_ref_new,contSettings] = run_parafoilGuidance(pos_est, sensorData.nas.states(end,4:5), wind_est, settings.payload.target, contSettings); % end diff --git a/simulator/src/std_run_parts/std_magneticField.m b/simulator/src/std_run_parts/std_magneticField.m index bb1ff613f9d31c7985c7917481fcf079f50b054f..6703b0f24f168dd585eed9f84e17b8ef0242f77d 100644 --- a/simulator/src/std_run_parts/std_magneticField.m +++ b/simulator/src/std_run_parts/std_magneticField.m @@ -8,8 +8,8 @@ hmax = settings.hmax; %Use this lines if your MATLAB version is up to 2020 dy = decyear(settings.launchDate); -XYZ0 = wrldmagm(0, settings.lat0, settings.lon0, dy, '2020'); % World magnetic map at h = 0 -XYZh = wrldmagm(hmax, settings.lat0, settings.lon0, dy, '2020'); % World magnetic map at h = 6000 +XYZ0 = wrldmagm(0, environment.lat0, environment.lon0, dy, '2020'); % World magnetic map at h = 0 +XYZh = wrldmagm(hmax, environment.lat0, environment.lon0, dy, '2020'); % World magnetic map at h = 6000 % %Use this next line if your MATLAB version is previous to 2020 % load('magn_field.mat'); diff --git a/simulator/src/std_run_parts/std_setInitialParams.m b/simulator/src/std_run_parts/std_setInitialParams.m index c20359c61438aa264a6c0dfed001d5bac415dcdd..1b999512e79b54955efca70366dc4823f982324d 100644 --- a/simulator/src/std_run_parts/std_setInitialParams.m +++ b/simulator/src/std_run_parts/std_setInitialParams.m @@ -8,7 +8,7 @@ integration initialization script- setting initial condition before control phas %% kalman initialization if not(settings.scenario == "descent") sensorData.kalman.vz = 0; % Vertical velocity - sensorData.kalman.z = -settings.z0; + sensorData.kalman.z = -environment.z0; else sensorData.kalman.vz = -settings.Vz_final; % Vertical velocity sensorData.kalman.z = -settings.z_final; @@ -51,7 +51,7 @@ sensorData.barometer_sens{3}.t0 = initSensorT0... sensorData.pitot.t0 = initSensorT0... (control_freq,settings.frequencies.pitotFrequency); -if contains(settings.mission,'_2023') || contains(settings.mission,'_2024') +if contains(mission.name,'2023') || contains(mission.name,'2024') sensorData.chamberPressure.t0 = initSensorT0... (control_freq,settings.frequencies.chamberPressureFrequency); end @@ -77,7 +77,7 @@ windMag = []; windAz = []; %% control angle (air brakes) initialization -ap_ref_new = 0; % air brakes closed until Mach < settings.MachControl +ap_ref_new = 0; % air brakes closed until Mach < rocket.airbrakes.maxMach ap_ref_old = 0; ap_ref = [ ap_ref_old ap_ref_new ]; @@ -89,7 +89,7 @@ deltaA_ref_new = 0; deltaA_ref_old = 0; deltaA_ref = [deltaA_ref_old,deltaA_ref_new]; % servo motor time delay - in ode it needs to be set to change reference value -t_change_ref_PRF = t0 + contSettings.payload.deltaA_delay; +t_change_ref_PRF = t0 + rocket.parachutes(2,2).controlParams.deltaA_delay; t_last_prf_control = 0; @@ -133,7 +133,7 @@ sfd_mean_p = []; %% ADA initial conditions (Apogee Detection Algorithm) if strcmp(settings.scenario, 'descent') - [~, ~, p_fin, ~] = atmosisa(settings.z_final+settings.z0); % Reference temperature in kelvin and pressure in Pa + [~, ~, p_fin, ~] = atmosisa(settings.z_final+environment.z0); % Reference temperature in kelvin and pressure in Pa settings.ada.v0 = -10; % Vertical velocity initial condition settings.ada.a0 = -100; % Acceleration velocity initial condition @@ -157,9 +157,9 @@ if settings.flagNAS || settings.electronics % initialize states of the NAS sensorData.nas.states = [X0; V0; Q0(2:4); Q0(1);0;0;0]'; if settings.scenario ~="descent" - sensorData.nas.states(3) = -settings.z0; + sensorData.nas.states(3) = -environment.z0; else - sensorData.nas.states(3) = -settings.z_final-settings.z0; + sensorData.nas.states(3) = -settings.z_final-environment.z0; end sensorData.nas.P = 0.01*eye(12); end @@ -168,12 +168,12 @@ sensorData.nas.time = 0; settings.nas.flagStopPitotCorrection = false; %% MEA PARAMETERS (mass estimation algorithm) -sensorData.mea.x = [0,0,settings.m0]; % initial state estimate -sensorData.mea.estimated_mass(1) = settings.m0; +sensorData.mea.x = [0,0,rocket.mass(1)]; % initial state estimate +sensorData.mea.estimated_mass(1) = rocket.mass(1); sensorData.mea.P = diag([0 0 0.36^2]); % initial value for P sensorData.mea.P_acc = diag([0 0 0.36^2]); sensorData.mea.time = 0; -sensorData.mea.estimated_mass = settings.m0; +sensorData.mea.estimated_mass = rocket.mass(1); sensorData.mea.estimated_pressure = 0; sensorData.mea.predicted_apogee = 0; settings.t_shutdown = Inf; @@ -185,20 +185,20 @@ para = 1; %% total sensors initialization % total measurements -[~,~,P0,~] = atmosisa(settings.z0); +[~,~,P0,~] = atmosisa(environment.z0); sensorTot.barometer_sens{1}.pressure_measures = P0; sensorTot.barometer_sens{2}.pressure_measures = P0; sensorTot.barometer_sens{3}.pressure_measures = P0; -sensorTot.barometer_sens{1}.altitude = -settings.z0; -sensorTot.barometer_sens{2}.altitude = -settings.z0; -sensorTot.barometer_sens{3}.altitude = -settings.z0; +sensorTot.barometer_sens{1}.altitude = -environment.z0; +sensorTot.barometer_sens{2}.altitude = -environment.z0; +sensorTot.barometer_sens{3}.altitude = -environment.z0; sensorTot.barometer.pressure_measures = P0; -sensorTot.barometer.altitude = -settings.z0; +sensorTot.barometer.altitude = -environment.z0; sensorTot.comb_chamber.measures = 0; sensorTot.imu.accelerometer_measures = [0, 0, 0]; sensorTot.imu.gyro_measures = [0, 0, 0]; sensorTot.imu.magnetometer_measures = [0, 0, 0]; -sensorTot.gps.position_measures = [settings.lat0, settings.lon0, settings.z0]; +sensorTot.gps.position_measures = [environment.lat0, environment.lon0, environment.z0]; sensorTot.gps.velocity_measures = [0, 0, 0]; sensorTot.pitot.total_pressure = P0; sensorTot.pitot.static_pressure = P0; @@ -207,7 +207,7 @@ sensorTot.pitot.airspeed = 0; sensorTot.nas.states = sensorData.nas.states; sensorTot.nas.timestampPitotCorrection = nan; sensorTot.mea.pressure = 0; %it's a differential pressure sensor -sensorTot.mea.mass = settings.m0; +sensorTot.mea.mass = rocket.motor.mass(1); sensorTot.mea.prediction = 0; sensorTot.mea.time = 0; diff --git a/simulator/src/std_run_parts/std_subsystems.m b/simulator/src/std_run_parts/std_subsystems.m index 960442fb9dd269c5283f833cc223978fa2768f67..d4b7ad382e463d2dc3440fa149f98363debeb152 100644 --- a/simulator/src/std_run_parts/std_subsystems.m +++ b/simulator/src/std_run_parts/std_subsystems.m @@ -13,7 +13,7 @@ end %% Navigation system (NAS) if settings.flagNAS && settings.dataNoise - [sensorData, sensorTot, settings.nas] = run_NAS(t1, XYZ0*0.01, sensorData, sensorTot, settings); + [sensorData, sensorTot, settings.nas] = run_NAS(t1, XYZ0*0.01, sensorData, sensorTot, settings, environment); @@ -27,7 +27,7 @@ if settings.flagNAS && settings.dataNoise end %% Engine Control algorithm -if (contains(settings.mission,'_2023') || contains(settings.mission,'_2024')) && currentState ~= availableStates.on_ground +if (contains(mission.name,'2023') || contains(mission.name,'2024')) && currentState ~= availableStates.on_ground if (strcmp(contSettings.algorithm,'engine') || strcmp(contSettings.algorithm,'complete')) if isnan(sensorTot.comb_chamber.measures(end)) @@ -35,14 +35,15 @@ if (contains(settings.mission,'_2023') || contains(settings.mission,'_2024')) && end if ~settings.shutdown - [sensorData,sensorTot,settings,contSettings] = run_MTR_SIM (sensorData,sensorTot,settings,contSettings,t1, engineT0,dt_ode); + [sensorData,sensorTot,settings,contSettings,rocket] = run_MTR_SIM ... + (sensorData,sensorTot,settings,contSettings,t1, engineT0,dt_ode,rocket,environment, mission); sensorTot.mea.t_shutdown = settings.t_shutdown; - if Tf(end)-engineT0 >= settings.tb + if Tf(end)-engineT0 >= rocket.motor.time(end) settings.expShutdown = true; settings.shutdown = true; - settings.t_shutdown = settings.tb; - settings.timeEngineCut = settings.t_shutdown; + settings.t_shutdown = rocket.motor.time(end); + rocket.motor.cutoffTime = settings.t_shutdown; settings.expTimeEngineCut = settings.t_shutdown; % settings.expMengineCut = settings.parout.m(end) - settings.ms; % settings = settingsEngineCut(settings); @@ -53,17 +54,17 @@ if (contains(settings.mission,'_2023') || contains(settings.mission,'_2024')) && end - elseif ~(strcmp(contSettings.algorithm,'engine') || strcmp(contSettings.algorithm,'complete')) && Tf(end)-engineT0 > settings.tb + elseif ~(strcmp(contSettings.algorithm,'engine') || strcmp(contSettings.algorithm,'complete')) && Tf(end)-engineT0 > rocket.motor.time(end) settings.shutdown = 1; settings.expShutdown = 1; - settings.timeEngineCut = settings.tb; - settings.expTimeEngineCut = settings.tb; + rocket.motor.cutoffTime = rocket.motor.time(end); + settings.expTimeEngineCut = rocket.motor.time(end); end else - if t0-engineT0 > settings.motor.expTime(end) && currentState ~= availableStates.on_ground + if t0-engineT0 > rocket.motor.time(end) && currentState ~= availableStates.on_ground settings.shutdown = 1; settings.expShutdown = 1; - settings.expTimeEngineCut = engineT0 + settings.tb; + settings.expTimeEngineCut = engineT0 + rocket.motor.time(end); end end @@ -72,11 +73,11 @@ end if flagAeroBrakes && settings.flagNAS && settings.control && ... ~( strcmp(contSettings.algorithm,'NoControl') || strcmp(contSettings.algorithm,'engine')) && ... - mach < settings.MachControl && Tf(end) > settings.expTimeEngineCut + contSettings.ABK_shutdown_delay + mach < rocket.airbrakes.maxMach && Tf(end) > settings.expTimeEngineCut + contSettings.ABK_shutdown_delay - if (contains(settings.mission,'_2023') || contains(settings.mission,'_2024')) && contSettings.traj_choice == 1 && settings.expShutdown + if (contains(mission.name,'2023') || contains(mission.name,'2024')) && contSettings.traj_choice == 1 && settings.expShutdown if ~strcmp(contSettings.algorithm,'complete') - m = settings.ms; + m = rocket.massNoMotor + rocket.motor.mass(end); else m = sensorData.mea.estimated_mass(end); end @@ -92,7 +93,7 @@ if flagAeroBrakes && settings.flagNAS && settings.control && ... ap_ref_old = ap_ref_new; settings.quat = [sensorTot.nas.states(end, [10,7:9])]; [~,settings.pitch,~] = quat2angle(settings.quat,'ZYX'); - [ap_ref_new,contSettings] = run_ARB_SIM(sensorData,settings,contSettings,ap_ref_old); % "simulated" airbrakes because otherwise are run by the HIL. + [ap_ref_new,contSettings] = run_ARB_SIM(sensorData,settings,contSettings,ap_ref_old,environment); % "simulated" airbrakes because otherwise are run by the HIL. end else ap_ref_new = 0; @@ -110,7 +111,7 @@ if ~settings.flagAscent && settings.parafoil contSettings.flagFirstControlPRF = false; if contSettings.payload.guidance_alg == "t-approach" pos_est = sensorData.nas.states(end,1:3); - pos_est(3) = -pos_est(3)-settings.z0; + pos_est(3) = -pos_est(3)-environment.z0; [contSettings.payload.EMC,contSettings.payload.M1,contSettings.payload.M2] = setEMCpoints(pos_est,settings.payload.target,contSettings.payload); end end @@ -126,6 +127,7 @@ if ~settings.flagAscent && settings.parafoil sensorTot.wes.measure(iTimes,:) = wind_est; sensorTot.wes.time(iTimes) = t1; else + contSettings.WES.state = 2; wind_est = [0,0]; end @@ -134,9 +136,10 @@ if ~settings.flagAscent && settings.parafoil deltaA_ref_old = deltaA_ref_new; t_last_prf_control = t1; pos_est = sensorData.nas.states(end,1:3); - pos_est(3) = -pos_est(3)-settings.z0; + pos_est(3) = -pos_est(3)-environment.z0; - [deltaA_ref_new,contSettings] = run_parafoilGuidance(pos_est, sensorData.nas.states(end,4:5), wind_est, settings.payload.target, contSettings); + [deltaA_ref_new,contSettings] = run_parafoilGuidance(pos_est, sensorData.nas.states(end,4:5), wind_est, ... + settings.payload.target, contSettings, rocket.parachutes(2,2).controlParams); end end diff --git a/trajectoryGeneration/configTrajectoryGeneration.m b/trajectoryGeneration/configTrajectoryGeneration.m index 697e8113112e235a2bdc15ac331e88a7af5986e3..4d1a59ed51fc471f0a214344681c40664deb7d6d 100644 --- a/trajectoryGeneration/configTrajectoryGeneration.m +++ b/trajectoryGeneration/configTrajectoryGeneration.m @@ -15,7 +15,7 @@ SPDX-License-Identifier: GPL-3.0-or-later %% LOAD DATA % Retrieve MSA-Toolkit rocket data -dataPath = strcat('../common/missions/', settings.missionMSA); +dataPath = strcat('../common/missions/', mission.nameMSA); addpath(dataPath); simulationsData @@ -23,9 +23,9 @@ commonFunctionsPath = '../common/functions'; addpath(genpath(commonFunctionsPath)) % Retrieve Control rocket data -ConDataPath = strcat('../data/', settings.mission); +ConDataPath = strcat('../data/', mission.name); addpath(ConDataPath); -run(strcat('config', settings.mission)); +run(strcat('config', mission.name)); % Control common functions commonFunctionsPath = '../commonFunctions'; diff --git a/trajectoryGeneration/mainTrajectoryGeneration.m b/trajectoryGeneration/mainTrajectoryGeneration.m index 1cf69a2bf6e73079ee0903a3846310edb7608b31..06ebcc91e30a8068821137fe2d3080a2fe17da22 100644 --- a/trajectoryGeneration/mainTrajectoryGeneration.m +++ b/trajectoryGeneration/mainTrajectoryGeneration.m @@ -27,6 +27,7 @@ else clearvars -except flagSubmodulesUpdated end +restoredefaultpath; filePath = fileparts(mfilename('fullpath')); currentPath = pwd; if not(strcmp(filePath, currentPath)) @@ -42,6 +43,10 @@ addpath(genpath(commonFunctionsPath)); % Config path addpath('../simulator/configs/'); +% add MSA data path +commonPath = strcat('../common'); +addpath(genpath(commonPath)); + %% CHECK IF MSA-TOOLKIT IS UPDATED % msaToolkitURL = 'https://github.com/skyward-er/msa-toolkit'; % localRepoPath = '../data/msa-toolkit'; @@ -56,7 +61,7 @@ configSimulator; %% AIRBRAKES RADIAL EXTENSION % Airbrakes extension vector delta_alpha_values = linspace(settings.servo.minAngle,settings.servo.maxAngle,2); -[deltaX_values] = extension_From_Angle(delta_alpha_values, settings); +[deltaX_values] = extension_From_Angle(delta_alpha_values, settings, mission); % I exclude the limits for robustness % deltaX_values = deltaX_values(2:end-1); @@ -73,7 +78,7 @@ y_final = settings.y_final; %% INITIAL VELOCITY %%% Attitude -Q0 = angleToQuat(settings.PHI, settings.OMEGA, 0*pi/180)'; % set initial quaternion to ramp angles +Q0 = angleToQuat(environment.phi, environment.omega, 0*pi/180)'; % set initial quaternion to ramp angles %%% State X0 = [0 0 0]'; @@ -81,19 +86,20 @@ V0 = [0 0 0]'; W0 = [0 0 0]'; %%% wind initialization -[uw, vw, ww, ~] = windConstGenerator(settings.wind); +wind = WindCustom(mission); +[uw, vw, ww] = wind.getVels(0); settings.constWind = [uw, vw, ww]; Z_initial = 0; %% INTERPOLATED CA -coeffsCA = load(strcat(dataPath, '/CAinterpCoeffs.mat')); +coeffsCA = load(strcat(commonPath, '/missions/', mission.name, '/data/CAinterpCoeffs.mat')); %% NEEDED PARAMETERS -settingsSim.g0 = settings.g0; -settingsSim.z0 = settings.z0; -settingsSim.C = settings.C; +settingsSim.g0 = environment.g0; +settingsSim.z0 = environment.z0; +settingsSim.C = rocket.diameter; settingsSim.CD_correction_ref = settings.CD_correction_ref; %% COMPUTE THE TRAJECTORIES BY BACK INTEGRATION @@ -141,7 +147,7 @@ for j = 1:N_mass end %% SAVING -% settings.save = false; +% settings.save = false; % load test if ~settings.save warning('save is set to false') diff --git a/trajectoryGeneration/src/Trajectory_generation.slx b/trajectoryGeneration/src/Trajectory_generation.slx index 3e027b2ba52a58dffb9d9400a8fe1b3dc58f7d98..3f98aa353c5a425432d00f3f7a354d2f0e2ac698 100644 Binary files a/trajectoryGeneration/src/Trajectory_generation.slx and b/trajectoryGeneration/src/Trajectory_generation.slx differ diff --git a/trajectoryGeneration/src/Trajectory_generation.slx.autosave b/trajectoryGeneration/src/Trajectory_generation.slx.r2022b similarity index 52% rename from trajectoryGeneration/src/Trajectory_generation.slx.autosave rename to trajectoryGeneration/src/Trajectory_generation.slx.r2022b index d39d5d46631218148b71e48dae2e7709719b836a..3e027b2ba52a58dffb9d9400a8fe1b3dc58f7d98 100644 Binary files a/trajectoryGeneration/src/Trajectory_generation.slx.autosave and b/trajectoryGeneration/src/Trajectory_generation.slx.r2022b differ diff --git a/trajectoryGeneration/src/eventAirBrake.m b/trajectoryGeneration/src/eventAirBrake.m index b5b842a060e3571dc787478e380423f3488b7a51..39bbe07f437130b3ecf6055cb4c3b5fd26842b29 100644 --- a/trajectoryGeneration/src/eventAirBrake.m +++ b/trajectoryGeneration/src/eventAirBrake.m @@ -30,7 +30,7 @@ SPDX-License-Identifier: GPL-3.0-or-later %} -if t > settings.tb +if t > rocket.motor.time(end) %% RECALL THE STATE z = -Y(3); @@ -57,9 +57,9 @@ if t > settings.tb wr = w - wind(3); V_norm = norm([ur vr wr]); - Mach = getMach(V_norm, z + settings.z0); + Mach = getMach(V_norm, z + environment.z0); - value = Mach - settings.MachControl; + value = Mach - rocket.airbrakes.maxMach; else value = 1; diff --git a/trajectoryGeneration/src/eventSpeed.m b/trajectoryGeneration/src/eventSpeed.m index 2d0a4571dfe4489b49ab9aa7162baaf6337d2a4b..814a08064801d00609ffd37cf5181c2973f5a573 100644 --- a/trajectoryGeneration/src/eventSpeed.m +++ b/trajectoryGeneration/src/eventSpeed.m @@ -1,6 +1,6 @@ function [value, isterminal, direction] = eventSpeed(t, Y,settings, varargin) - Mach = getMach(norm(Y(4:6)), -Y(3) + settings.z0); + Mach = getMach(norm(Y(4:6)), -Y(3) + environment.z0); value = Mach - 0.8;