mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-16 14:37:34 +08:00
EKF: replacement of covariance prediction autocode with sympy generated output (#870)
* added python script with ekf derivation (WIP) Signed-off-by: RomanBapst <bapstroman@gmail.com> * worked on c code auto-generation Signed-off-by: RomanBapst <bapstroman@gmail.com> * save before variable name change Signed-off-by: RomanBapst <bapstroman@gmail.com> * changed symbol names Signed-off-by: RomanBapst <bapstroman@gmail.com> * added codegeneration class Signed-off-by: RomanBapst <bapstroman@gmail.com> * improve 3D mag fusion derivation Signed-off-by: RomanBapst <bapstroman@gmail.com> * EKF: Extend ekf sympy derivation to include all observation types * EKF: Add custom ecl::powf function for integer powers * EKF: Convert ekf covariance prediction to use sympy output * EKF: Add test program to compare sympy and matlab covariance prediction Also tests ecl::powf(x,exp) function * EKF: simplify ecl::powf function * Generate code to subfolder generated/ * Add printouts for showing code generation progress * Move generated covariance code to generated folder * Upgrade code generation to python3 * main.py: Remove unused create_symbols function & making code more compact * main.py: move main part into function * Code generation: fix passing wrong rotation matrix to yaw_observation () * EKF: Amend generated code filename for consistency * Move ecl::powf function test to unit tests * EKF: Use updated ecl:powf functionality in test program * Move ecl::powf to utils.hpp * Update ecl::powf test * Update output change indication * test: update expected output for change indicator * test: update expected output for change indicator again Co-authored-by: RomanBapst <bapstroman@gmail.com> Co-authored-by: kamilritz <kritz@ethz.ch>
This commit is contained in:
+453
-271
@@ -35,12 +35,14 @@
|
||||
* @file covariance.cpp
|
||||
* Contains functions for initialising, predicting and updating the state
|
||||
* covariance matrix
|
||||
* equations generated using EKF/python/ekf_derivation/main.py
|
||||
*
|
||||
* @author Roman Bast <bastroman@gmail.com>
|
||||
*
|
||||
*/
|
||||
|
||||
#include "ekf.h"
|
||||
#include "utils.hpp"
|
||||
|
||||
#include <ecl.h>
|
||||
#include <math.h>
|
||||
@@ -114,26 +116,26 @@ Vector3f Ekf::getVelocityVariance() const
|
||||
void Ekf::predictCovariance()
|
||||
{
|
||||
// assign intermediate state variables
|
||||
const float q0 = _state.quat_nominal(0);
|
||||
const float q1 = _state.quat_nominal(1);
|
||||
const float q2 = _state.quat_nominal(2);
|
||||
const float q3 = _state.quat_nominal(3);
|
||||
const float &q0 = _state.quat_nominal(0);
|
||||
const float &q1 = _state.quat_nominal(1);
|
||||
const float &q2 = _state.quat_nominal(2);
|
||||
const float &q3 = _state.quat_nominal(3);
|
||||
|
||||
const float dax = _imu_sample_delayed.delta_ang(0);
|
||||
const float day = _imu_sample_delayed.delta_ang(1);
|
||||
const float daz = _imu_sample_delayed.delta_ang(2);
|
||||
const float &dax = _imu_sample_delayed.delta_ang(0);
|
||||
const float &day = _imu_sample_delayed.delta_ang(1);
|
||||
const float &daz = _imu_sample_delayed.delta_ang(2);
|
||||
|
||||
const float dvx = _imu_sample_delayed.delta_vel(0);
|
||||
const float dvy = _imu_sample_delayed.delta_vel(1);
|
||||
const float dvz = _imu_sample_delayed.delta_vel(2);
|
||||
const float &dvx = _imu_sample_delayed.delta_vel(0);
|
||||
const float &dvy = _imu_sample_delayed.delta_vel(1);
|
||||
const float &dvz = _imu_sample_delayed.delta_vel(2);
|
||||
|
||||
const float dax_b = _state.delta_ang_bias(0);
|
||||
const float day_b = _state.delta_ang_bias(1);
|
||||
const float daz_b = _state.delta_ang_bias(2);
|
||||
const float &dax_b = _state.delta_ang_bias(0);
|
||||
const float &day_b = _state.delta_ang_bias(1);
|
||||
const float &daz_b = _state.delta_ang_bias(2);
|
||||
|
||||
const float dvx_b = _state.delta_vel_bias(0);
|
||||
const float dvy_b = _state.delta_vel_bias(1);
|
||||
const float dvz_b = _state.delta_vel_bias(2);
|
||||
const float &dvx_b = _state.delta_vel_bias(0);
|
||||
const float &dvy_b = _state.delta_vel_bias(1);
|
||||
const float &dvz_b = _state.delta_vel_bias(2);
|
||||
|
||||
// Use average update interval to reduce accumulated covariance prediction errors due to small single frame dt values
|
||||
const float dt = FILTER_UPDATE_PERIOD_S;
|
||||
@@ -266,158 +268,290 @@ void Ekf::predictCovariance()
|
||||
dvzVar = sq(dt * BADACC_BIAS_PNOISE);
|
||||
}
|
||||
|
||||
// predict the covariance
|
||||
// equations generated using EKF/python/ekf_derivation/main.py
|
||||
|
||||
// intermediate calculations
|
||||
float SF[21];
|
||||
SF[0] = dvz - dvz_b;
|
||||
SF[1] = dvy - dvy_b;
|
||||
SF[2] = dvx - dvx_b;
|
||||
SF[3] = 2*q1*SF[2] + 2*q2*SF[1] + 2*q3*SF[0];
|
||||
SF[4] = 2*q0*SF[1] - 2*q1*SF[0] + 2*q3*SF[2];
|
||||
SF[5] = 2*q0*SF[2] + 2*q2*SF[0] - 2*q3*SF[1];
|
||||
SF[6] = day*0.5f - day_b*0.5f;
|
||||
SF[7] = daz*0.5f - daz_b*0.5f;
|
||||
SF[8] = dax*0.5f - dax_b*0.5f;
|
||||
SF[9] = dax_b*0.5f - dax*0.5f;
|
||||
SF[10] = daz_b*0.5f - daz*0.5f;
|
||||
SF[11] = day_b*0.5f - day*0.5f;
|
||||
SF[12] = 2*q1*SF[1];
|
||||
SF[13] = 2*q0*SF[0];
|
||||
SF[14] = q1*0.5f;
|
||||
SF[15] = q2*0.5f;
|
||||
SF[16] = q3*0.5f;
|
||||
SF[17] = sq(q3);
|
||||
SF[18] = sq(q2);
|
||||
SF[19] = sq(q1);
|
||||
SF[20] = sq(q0);
|
||||
|
||||
float SG[8];
|
||||
SG[0] = q0*0.5f;
|
||||
SG[1] = sq(q3);
|
||||
SG[2] = sq(q2);
|
||||
SG[3] = sq(q1);
|
||||
SG[4] = sq(q0);
|
||||
SG[5] = 2*q2*q3;
|
||||
SG[6] = 2*q1*q3;
|
||||
SG[7] = 2*q1*q2;
|
||||
|
||||
float SQ[11];
|
||||
SQ[0] = dvzVar*(SG[5] - 2*q0*q1)*(SG[1] - SG[2] - SG[3] + SG[4]) - dvyVar*(SG[5] + 2*q0*q1)*(SG[1] - SG[2] + SG[3] - SG[4]) + dvxVar*(SG[6] - 2*q0*q2)*(SG[7] + 2*q0*q3);
|
||||
SQ[1] = dvzVar*(SG[6] + 2*q0*q2)*(SG[1] - SG[2] - SG[3] + SG[4]) - dvxVar*(SG[6] - 2*q0*q2)*(SG[1] + SG[2] - SG[3] - SG[4]) + dvyVar*(SG[5] + 2*q0*q1)*(SG[7] - 2*q0*q3);
|
||||
SQ[2] = dvzVar*(SG[5] - 2*q0*q1)*(SG[6] + 2*q0*q2) - dvyVar*(SG[7] - 2*q0*q3)*(SG[1] - SG[2] + SG[3] - SG[4]) - dvxVar*(SG[7] + 2*q0*q3)*(SG[1] + SG[2] - SG[3] - SG[4]);
|
||||
SQ[3] = (dayVar*q1*SG[0])*0.5f - (dazVar*q1*SG[0])*0.5f - (daxVar*q2*q3)*0.25f;
|
||||
SQ[4] = (dazVar*q2*SG[0])*0.5f - (daxVar*q2*SG[0])*0.5f - (dayVar*q1*q3)*0.25f;
|
||||
SQ[5] = (daxVar*q3*SG[0])*0.5f - (dayVar*q3*SG[0])*0.5f - (dazVar*q1*q2)*0.25f;
|
||||
SQ[6] = (daxVar*q1*q2)*0.25f - (dazVar*q3*SG[0])*0.5f - (dayVar*q1*q2)*0.25f;
|
||||
SQ[7] = (dazVar*q1*q3)*0.25f - (daxVar*q1*q3)*0.25f - (dayVar*q2*SG[0])*0.5f;
|
||||
SQ[8] = (dayVar*q2*q3)*0.25f - (daxVar*q1*SG[0])*0.5f - (dazVar*q2*q3)*0.25f;
|
||||
SQ[9] = sq(SG[0]);
|
||||
SQ[10] = sq(q1);
|
||||
|
||||
float SPP[11];
|
||||
SPP[0] = SF[12] + SF[13] - 2*q2*SF[2];
|
||||
SPP[1] = SF[17] - SF[18] - SF[19] + SF[20];
|
||||
SPP[2] = SF[17] - SF[18] + SF[19] - SF[20];
|
||||
SPP[3] = SF[17] + SF[18] - SF[19] - SF[20];
|
||||
SPP[4] = 2*q0*q2 - 2*q1*q3;
|
||||
SPP[5] = 2*q0*q1 - 2*q2*q3;
|
||||
SPP[6] = 2*q0*q3 - 2*q1*q2;
|
||||
SPP[7] = 2*q0*q1 + 2*q2*q3;
|
||||
SPP[8] = 2*q0*q3 + 2*q1*q2;
|
||||
SPP[9] = 2*q0*q2 + 2*q1*q3;
|
||||
SPP[10] = SF[16];
|
||||
const float PS0 = ecl::powf(q1, 2);
|
||||
const float PS1 = 0.25F*daxVar;
|
||||
const float PS2 = ecl::powf(q2, 2);
|
||||
const float PS3 = 0.25F*dayVar;
|
||||
const float PS4 = ecl::powf(q3, 2);
|
||||
const float PS5 = 0.25F*dazVar;
|
||||
const float PS6 = 0.5F*q1;
|
||||
const float PS7 = 0.5F*q2;
|
||||
const float PS8 = P(10,11)*PS7;
|
||||
const float PS9 = 0.5F*q3;
|
||||
const float PS10 = P(10,12)*PS9;
|
||||
const float PS11 = 0.5F*dax - 0.5F*dax_b;
|
||||
const float PS12 = 0.5F*day - 0.5F*day_b;
|
||||
const float PS13 = 0.5F*daz - 0.5F*daz_b;
|
||||
const float PS14 = P(0,10) - P(1,10)*PS11 + P(10,10)*PS6 - P(2,10)*PS12 - P(3,10)*PS13 + PS10 + PS8;
|
||||
const float PS15 = P(10,11)*PS6;
|
||||
const float PS16 = P(11,12)*PS9;
|
||||
const float PS17 = P(0,11) - P(1,11)*PS11 + P(11,11)*PS7 - P(2,11)*PS12 - P(3,11)*PS13 + PS15 + PS16;
|
||||
const float PS18 = P(10,12)*PS6;
|
||||
const float PS19 = P(11,12)*PS7;
|
||||
const float PS20 = P(0,12) - P(1,12)*PS11 + P(12,12)*PS9 - P(2,12)*PS12 - P(3,12)*PS13 + PS18 + PS19;
|
||||
const float PS21 = P(1,2)*PS12;
|
||||
const float PS22 = -P(1,3)*PS13;
|
||||
const float PS23 = P(0,1) - P(1,1)*PS11 + P(1,10)*PS6 + P(1,11)*PS7 + P(1,12)*PS9 - PS21 + PS22;
|
||||
const float PS24 = -P(1,2)*PS11;
|
||||
const float PS25 = P(2,3)*PS13;
|
||||
const float PS26 = P(0,2) + P(2,10)*PS6 + P(2,11)*PS7 + P(2,12)*PS9 - P(2,2)*PS12 + PS24 - PS25;
|
||||
const float PS27 = P(1,3)*PS11;
|
||||
const float PS28 = -P(2,3)*PS12;
|
||||
const float PS29 = P(0,3) + P(3,10)*PS6 + P(3,11)*PS7 + P(3,12)*PS9 - P(3,3)*PS13 - PS27 + PS28;
|
||||
const float PS30 = P(0,1)*PS11;
|
||||
const float PS31 = P(0,2)*PS12;
|
||||
const float PS32 = P(0,3)*PS13;
|
||||
const float PS33 = P(0,0) + P(0,10)*PS6 + P(0,11)*PS7 + P(0,12)*PS9 - PS30 - PS31 - PS32;
|
||||
const float PS34 = 0.5F*q0;
|
||||
const float PS35 = q2*q3;
|
||||
const float PS36 = q0*q1;
|
||||
const float PS37 = q1*q3;
|
||||
const float PS38 = q0*q2;
|
||||
const float PS39 = q1*q2;
|
||||
const float PS40 = q0*q3;
|
||||
const float PS41 = -PS2;
|
||||
const float PS42 = ecl::powf(q0, 2);
|
||||
const float PS43 = -PS4 + PS42;
|
||||
const float PS44 = PS0 + PS41 + PS43;
|
||||
const float PS45 = P(0,13) - P(1,13)*PS11 + P(10,13)*PS6 + P(11,13)*PS7 + P(12,13)*PS9 - P(2,13)*PS12 - P(3,13)*PS13;
|
||||
const float PS46 = PS37 + PS38;
|
||||
const float PS47 = P(0,15) - P(1,15)*PS11 + P(10,15)*PS6 + P(11,15)*PS7 + P(12,15)*PS9 - P(2,15)*PS12 - P(3,15)*PS13;
|
||||
const float PS48 = 2*PS47;
|
||||
const float PS49 = dvy - dvy_b;
|
||||
const float PS50 = dvx - dvx_b;
|
||||
const float PS51 = dvz - dvz_b;
|
||||
const float PS52 = PS49*q0 + PS50*q3 - PS51*q1;
|
||||
const float PS53 = 2*PS29;
|
||||
const float PS54 = -PS39 + PS40;
|
||||
const float PS55 = P(0,14) - P(1,14)*PS11 + P(10,14)*PS6 + P(11,14)*PS7 + P(12,14)*PS9 - P(2,14)*PS12 - P(3,14)*PS13;
|
||||
const float PS56 = 2*PS55;
|
||||
const float PS57 = -PS49*q3 + PS50*q0 + PS51*q2;
|
||||
const float PS58 = 2*PS33;
|
||||
const float PS59 = PS49*q1 - PS50*q2 + PS51*q0;
|
||||
const float PS60 = 2*PS59;
|
||||
const float PS61 = PS49*q2 + PS50*q1 + PS51*q3;
|
||||
const float PS62 = 2*PS61;
|
||||
const float PS63 = P(0,4) - P(1,4)*PS11 - P(2,4)*PS12 - P(3,4)*PS13 + P(4,10)*PS6 + P(4,11)*PS7 + P(4,12)*PS9;
|
||||
const float PS64 = -PS0;
|
||||
const float PS65 = PS2 + PS43 + PS64;
|
||||
const float PS66 = PS39 + PS40;
|
||||
const float PS67 = 2*PS45;
|
||||
const float PS68 = -PS35 + PS36;
|
||||
const float PS69 = P(0,5) - P(1,5)*PS11 - P(2,5)*PS12 - P(3,5)*PS13 + P(5,10)*PS6 + P(5,11)*PS7 + P(5,12)*PS9;
|
||||
const float PS70 = PS4 + PS41 + PS42 + PS64;
|
||||
const float PS71 = PS35 + PS36;
|
||||
const float PS72 = 2*PS57;
|
||||
const float PS73 = -PS37 + PS38;
|
||||
const float PS74 = 2*PS52;
|
||||
const float PS75 = P(0,6) - P(1,6)*PS11 - P(2,6)*PS12 - P(3,6)*PS13 + P(6,10)*PS6 + P(6,11)*PS7 + P(6,12)*PS9;
|
||||
const float PS76 = -P(10,11)*PS34;
|
||||
const float PS77 = P(0,11)*PS11 + P(1,11) + P(11,11)*PS9 + P(2,11)*PS13 - P(3,11)*PS12 - PS19 + PS76;
|
||||
const float PS78 = P(0,2)*PS13;
|
||||
const float PS79 = P(0,3)*PS12;
|
||||
const float PS80 = P(0,0)*PS11 + P(0,1) - P(0,10)*PS34 + P(0,11)*PS9 - P(0,12)*PS7 + PS78 - PS79;
|
||||
const float PS81 = P(0,2)*PS11;
|
||||
const float PS82 = P(1,2) - P(2,10)*PS34 + P(2,11)*PS9 - P(2,12)*PS7 + P(2,2)*PS13 + PS28 + PS81;
|
||||
const float PS83 = P(10,11)*PS9;
|
||||
const float PS84 = P(10,12)*PS7;
|
||||
const float PS85 = P(0,10)*PS11 + P(1,10) - P(10,10)*PS34 + P(2,10)*PS13 - P(3,10)*PS12 + PS83 - PS84;
|
||||
const float PS86 = -P(10,12)*PS34;
|
||||
const float PS87 = P(0,12)*PS11 + P(1,12) - P(12,12)*PS7 + P(2,12)*PS13 - P(3,12)*PS12 + PS16 + PS86;
|
||||
const float PS88 = P(0,3)*PS11;
|
||||
const float PS89 = P(1,3) - P(3,10)*PS34 + P(3,11)*PS9 - P(3,12)*PS7 - P(3,3)*PS12 + PS25 + PS88;
|
||||
const float PS90 = P(1,2)*PS13;
|
||||
const float PS91 = P(1,3)*PS12;
|
||||
const float PS92 = P(1,1) - P(1,10)*PS34 + P(1,11)*PS9 - P(1,12)*PS7 + PS30 + PS90 - PS91;
|
||||
const float PS93 = P(0,13)*PS11 + P(1,13) - P(10,13)*PS34 + P(11,13)*PS9 - P(12,13)*PS7 + P(2,13)*PS13 - P(3,13)*PS12;
|
||||
const float PS94 = P(0,15)*PS11 + P(1,15) - P(10,15)*PS34 + P(11,15)*PS9 - P(12,15)*PS7 + P(2,15)*PS13 - P(3,15)*PS12;
|
||||
const float PS95 = 2*PS94;
|
||||
const float PS96 = P(0,14)*PS11 + P(1,14) - P(10,14)*PS34 + P(11,14)*PS9 - P(12,14)*PS7 + P(2,14)*PS13 - P(3,14)*PS12;
|
||||
const float PS97 = 2*PS96;
|
||||
const float PS98 = P(0,4)*PS11 + P(1,4) + P(2,4)*PS13 - P(3,4)*PS12 - P(4,10)*PS34 + P(4,11)*PS9 - P(4,12)*PS7;
|
||||
const float PS99 = 2*PS93;
|
||||
const float PS100 = P(0,5)*PS11 + P(1,5) + P(2,5)*PS13 - P(3,5)*PS12 - P(5,10)*PS34 + P(5,11)*PS9 - P(5,12)*PS7;
|
||||
const float PS101 = P(0,6)*PS11 + P(1,6) + P(2,6)*PS13 - P(3,6)*PS12 - P(6,10)*PS34 + P(6,11)*PS9 - P(6,12)*PS7;
|
||||
const float PS102 = -P(11,12)*PS34;
|
||||
const float PS103 = P(0,12)*PS12 - P(1,12)*PS13 + P(12,12)*PS6 + P(2,12) + P(3,12)*PS11 - PS10 + PS102;
|
||||
const float PS104 = P(2,3) - P(3,10)*PS9 - P(3,11)*PS34 + P(3,12)*PS6 + P(3,3)*PS11 + PS22 + PS79;
|
||||
const float PS105 = P(0,1)*PS13;
|
||||
const float PS106 = P(0,0)*PS12 - P(0,10)*PS9 - P(0,11)*PS34 + P(0,12)*PS6 + P(0,2) - PS105 + PS88;
|
||||
const float PS107 = P(11,12)*PS6;
|
||||
const float PS108 = P(0,11)*PS12 - P(1,11)*PS13 - P(11,11)*PS34 + P(2,11) + P(3,11)*PS11 + PS107 - PS83;
|
||||
const float PS109 = P(0,10)*PS12 - P(1,10)*PS13 - P(10,10)*PS9 + P(2,10) + P(3,10)*PS11 + PS18 + PS76;
|
||||
const float PS110 = P(0,1)*PS12;
|
||||
const float PS111 = -P(1,1)*PS13 - P(1,10)*PS9 - P(1,11)*PS34 + P(1,12)*PS6 + P(1,2) + PS110 + PS27;
|
||||
const float PS112 = P(2,3)*PS11;
|
||||
const float PS113 = -P(2,10)*PS9 - P(2,11)*PS34 + P(2,12)*PS6 + P(2,2) + PS112 + PS31 - PS90;
|
||||
const float PS114 = P(0,13)*PS12 - P(1,13)*PS13 - P(10,13)*PS9 - P(11,13)*PS34 + P(12,13)*PS6 + P(2,13) + P(3,13)*PS11;
|
||||
const float PS115 = P(0,15)*PS12 - P(1,15)*PS13 - P(10,15)*PS9 - P(11,15)*PS34 + P(12,15)*PS6 + P(2,15) + P(3,15)*PS11;
|
||||
const float PS116 = 2*PS115;
|
||||
const float PS117 = P(0,14)*PS12 - P(1,14)*PS13 - P(10,14)*PS9 - P(11,14)*PS34 + P(12,14)*PS6 + P(2,14) + P(3,14)*PS11;
|
||||
const float PS118 = 2*PS117;
|
||||
const float PS119 = P(0,4)*PS12 - P(1,4)*PS13 + P(2,4) + P(3,4)*PS11 - P(4,10)*PS9 - P(4,11)*PS34 + P(4,12)*PS6;
|
||||
const float PS120 = 2*PS114;
|
||||
const float PS121 = P(0,5)*PS12 - P(1,5)*PS13 + P(2,5) + P(3,5)*PS11 - P(5,10)*PS9 - P(5,11)*PS34 + P(5,12)*PS6;
|
||||
const float PS122 = P(0,6)*PS12 - P(1,6)*PS13 + P(2,6) + P(3,6)*PS11 - P(6,10)*PS9 - P(6,11)*PS34 + P(6,12)*PS6;
|
||||
const float PS123 = P(0,10)*PS13 + P(1,10)*PS12 + P(10,10)*PS7 - P(2,10)*PS11 + P(3,10) - PS15 + PS86;
|
||||
const float PS124 = P(1,1)*PS12 + P(1,10)*PS7 - P(1,11)*PS6 - P(1,12)*PS34 + P(1,3) + PS105 + PS24;
|
||||
const float PS125 = P(0,0)*PS13 + P(0,10)*PS7 - P(0,11)*PS6 - P(0,12)*PS34 + P(0,3) + PS110 - PS81;
|
||||
const float PS126 = P(0,12)*PS13 + P(1,12)*PS12 - P(12,12)*PS34 - P(2,12)*PS11 + P(3,12) - PS107 + PS84;
|
||||
const float PS127 = P(0,11)*PS13 + P(1,11)*PS12 - P(11,11)*PS6 - P(2,11)*PS11 + P(3,11) + PS102 + PS8;
|
||||
const float PS128 = P(2,10)*PS7 - P(2,11)*PS6 - P(2,12)*PS34 - P(2,2)*PS11 + P(2,3) + PS21 + PS78;
|
||||
const float PS129 = P(3,10)*PS7 - P(3,11)*PS6 - P(3,12)*PS34 + P(3,3) - PS112 + PS32 + PS91;
|
||||
const float PS130 = P(0,13)*PS13 + P(1,13)*PS12 + P(10,13)*PS7 - P(11,13)*PS6 - P(12,13)*PS34 - P(2,13)*PS11 + P(3,13);
|
||||
const float PS131 = P(0,15)*PS13 + P(1,15)*PS12 + P(10,15)*PS7 - P(11,15)*PS6 - P(12,15)*PS34 - P(2,15)*PS11 + P(3,15);
|
||||
const float PS132 = 2*PS131;
|
||||
const float PS133 = P(0,14)*PS13 + P(1,14)*PS12 + P(10,14)*PS7 - P(11,14)*PS6 - P(12,14)*PS34 - P(2,14)*PS11 + P(3,14);
|
||||
const float PS134 = 2*PS133;
|
||||
const float PS135 = P(0,4)*PS13 + P(1,4)*PS12 - P(2,4)*PS11 + P(3,4) + P(4,10)*PS7 - P(4,11)*PS6 - P(4,12)*PS34;
|
||||
const float PS136 = 2*PS130;
|
||||
const float PS137 = P(0,5)*PS13 + P(1,5)*PS12 - P(2,5)*PS11 + P(3,5) + P(5,10)*PS7 - P(5,11)*PS6 - P(5,12)*PS34;
|
||||
const float PS138 = P(0,6)*PS13 + P(1,6)*PS12 - P(2,6)*PS11 + P(3,6) + P(6,10)*PS7 - P(6,11)*PS6 - P(6,12)*PS34;
|
||||
const float PS139 = 2*PS46;
|
||||
const float PS140 = 2*PS54;
|
||||
const float PS141 = P(0,13)*PS72 + P(1,13)*PS62 - P(13,13)*PS44 + P(13,14)*PS140 - P(13,15)*PS139 + P(2,13)*PS60 - P(3,13)*PS74 + P(4,13);
|
||||
const float PS142 = P(0,15)*PS72 + P(1,15)*PS62 - P(13,15)*PS44 + P(14,15)*PS140 - P(15,15)*PS139 + P(2,15)*PS60 - P(3,15)*PS74 + P(4,15);
|
||||
const float PS143 = P(1,3)*PS62;
|
||||
const float PS144 = P(0,3)*PS72;
|
||||
const float PS145 = P(2,3)*PS60 - P(3,13)*PS44 + P(3,14)*PS140 - P(3,15)*PS139 - P(3,3)*PS74 + P(3,4) + PS143 + PS144;
|
||||
const float PS146 = P(0,14)*PS72 + P(1,14)*PS62 - P(13,14)*PS44 + P(14,14)*PS140 - P(14,15)*PS139 + P(2,14)*PS60 - P(3,14)*PS74 + P(4,14);
|
||||
const float PS147 = P(0,2)*PS60;
|
||||
const float PS148 = P(0,3)*PS74;
|
||||
const float PS149 = P(0,0)*PS72 + P(0,1)*PS62 - P(0,13)*PS44 + P(0,14)*PS140 - P(0,15)*PS139 + P(0,4) + PS147 - PS148;
|
||||
const float PS150 = P(1,2)*PS62;
|
||||
const float PS151 = P(0,2)*PS72;
|
||||
const float PS152 = -P(2,13)*PS44 + P(2,14)*PS140 - P(2,15)*PS139 + P(2,2)*PS60 - P(2,3)*PS74 + P(2,4) + PS150 + PS151;
|
||||
const float PS153 = P(1,2)*PS60;
|
||||
const float PS154 = P(1,3)*PS74;
|
||||
const float PS155 = P(0,1)*PS72 + P(1,1)*PS62 - P(1,13)*PS44 + P(1,14)*PS140 - P(1,15)*PS139 + P(1,4) + PS153 - PS154;
|
||||
const float PS156 = 4*dvyVar;
|
||||
const float PS157 = 4*dvzVar;
|
||||
const float PS158 = P(0,4)*PS72 + P(1,4)*PS62 + P(2,4)*PS60 - P(3,4)*PS74 - P(4,13)*PS44 + P(4,14)*PS140 - P(4,15)*PS139 + P(4,4);
|
||||
const float PS159 = 2*PS141;
|
||||
const float PS160 = 2*PS68;
|
||||
const float PS161 = PS65*dvyVar;
|
||||
const float PS162 = 2*PS66;
|
||||
const float PS163 = PS44*dvxVar;
|
||||
const float PS164 = P(0,5)*PS72 + P(1,5)*PS62 + P(2,5)*PS60 - P(3,5)*PS74 + P(4,5) - P(5,13)*PS44 + P(5,14)*PS140 - P(5,15)*PS139;
|
||||
const float PS165 = 2*PS71;
|
||||
const float PS166 = 2*PS73;
|
||||
const float PS167 = PS70*dvzVar;
|
||||
const float PS168 = P(0,6)*PS72 + P(1,6)*PS62 + P(2,6)*PS60 - P(3,6)*PS74 + P(4,6) - P(6,13)*PS44 + P(6,14)*PS140 - P(6,15)*PS139;
|
||||
const float PS169 = P(0,14)*PS74 - P(1,14)*PS60 - P(13,14)*PS162 - P(14,14)*PS65 + P(14,15)*PS160 + P(2,14)*PS62 + P(3,14)*PS72 + P(5,14);
|
||||
const float PS170 = P(0,13)*PS74 - P(1,13)*PS60 - P(13,13)*PS162 - P(13,14)*PS65 + P(13,15)*PS160 + P(2,13)*PS62 + P(3,13)*PS72 + P(5,13);
|
||||
const float PS171 = P(0,1)*PS74;
|
||||
const float PS172 = -P(1,1)*PS60 - P(1,13)*PS162 - P(1,14)*PS65 + P(1,15)*PS160 + P(1,3)*PS72 + P(1,5) + PS150 + PS171;
|
||||
const float PS173 = P(0,15)*PS74 - P(1,15)*PS60 - P(13,15)*PS162 - P(14,15)*PS65 + P(15,15)*PS160 + P(2,15)*PS62 + P(3,15)*PS72 + P(5,15);
|
||||
const float PS174 = P(2,3)*PS62;
|
||||
const float PS175 = -P(1,3)*PS60 - P(3,13)*PS162 - P(3,14)*PS65 + P(3,15)*PS160 + P(3,3)*PS72 + P(3,5) + PS148 + PS174;
|
||||
const float PS176 = P(0,1)*PS60;
|
||||
const float PS177 = P(0,0)*PS74 - P(0,13)*PS162 - P(0,14)*PS65 + P(0,15)*PS160 + P(0,2)*PS62 + P(0,5) + PS144 - PS176;
|
||||
const float PS178 = P(2,3)*PS72;
|
||||
const float PS179 = P(0,2)*PS74 - P(2,13)*PS162 - P(2,14)*PS65 + P(2,15)*PS160 + P(2,2)*PS62 + P(2,5) - PS153 + PS178;
|
||||
const float PS180 = 4*dvxVar;
|
||||
const float PS181 = P(0,5)*PS74 - P(1,5)*PS60 + P(2,5)*PS62 + P(3,5)*PS72 - P(5,13)*PS162 - P(5,14)*PS65 + P(5,15)*PS160 + P(5,5);
|
||||
const float PS182 = P(0,6)*PS74 - P(1,6)*PS60 + P(2,6)*PS62 + P(3,6)*PS72 + P(5,6) - P(6,13)*PS162 - P(6,14)*PS65 + P(6,15)*PS160;
|
||||
const float PS183 = P(0,15)*PS60 + P(1,15)*PS74 + P(13,15)*PS166 - P(14,15)*PS165 - P(15,15)*PS70 - P(2,15)*PS72 + P(3,15)*PS62 + P(6,15);
|
||||
const float PS184 = P(0,14)*PS60 + P(1,14)*PS74 + P(13,14)*PS166 - P(14,14)*PS165 - P(14,15)*PS70 - P(2,14)*PS72 + P(3,14)*PS62 + P(6,14);
|
||||
const float PS185 = P(0,13)*PS60 + P(1,13)*PS74 + P(13,13)*PS166 - P(13,14)*PS165 - P(13,15)*PS70 - P(2,13)*PS72 + P(3,13)*PS62 + P(6,13);
|
||||
const float PS186 = P(0,6)*PS60 + P(1,6)*PS74 - P(2,6)*PS72 + P(3,6)*PS62 + P(6,13)*PS166 - P(6,14)*PS165 - P(6,15)*PS70 + P(6,6);
|
||||
|
||||
// covariance update
|
||||
SquareMatrix24f nextP;
|
||||
|
||||
// calculate variances and upper diagonal covariances for quaternion, velocity, position and gyro bias states
|
||||
nextP(0,0) = P(0,0) + P(1,0)*SF[9] + P(2,0)*SF[11] + P(3,0)*SF[10] + P(10,0)*SF[14] + P(11,0)*SF[15] + P(12,0)*SPP[10] + (daxVar*SQ[10])*0.25f + SF[9]*(P(0,1) + P(1,1)*SF[9] + P(2,1)*SF[11] + P(3,1)*SF[10] + P(10,1)*SF[14] + P(11,1)*SF[15] + P(12,1)*SPP[10]) + SF[11]*(P(0,2) + P(1,2)*SF[9] + P(2,2)*SF[11] + P(3,2)*SF[10] + P(10,2)*SF[14] + P(11,2)*SF[15] + P(12,2)*SPP[10]) + SF[10]*(P(0,3) + P(1,3)*SF[9] + P(2,3)*SF[11] + P(3,3)*SF[10] + P(10,3)*SF[14] + P(11,3)*SF[15] + P(12,3)*SPP[10]) + SF[14]*(P(0,10) + P(1,10)*SF[9] + P(2,10)*SF[11] + P(3,10)*SF[10] + P(10,10)*SF[14] + P(11,10)*SF[15] + P(12,10)*SPP[10]) + SF[15]*(P(0,11) + P(1,11)*SF[9] + P(2,11)*SF[11] + P(3,11)*SF[10] + P(10,11)*SF[14] + P(11,11)*SF[15] + P(12,11)*SPP[10]) + SPP[10]*(P(0,12) + P(1,12)*SF[9] + P(2,12)*SF[11] + P(3,12)*SF[10] + P(10,12)*SF[14] + P(11,12)*SF[15] + P(12,12)*SPP[10]) + (dayVar*sq(q2))*0.25f + (dazVar*sq(q3))*0.25f;
|
||||
nextP(0,1) = P(0,1) + SQ[8] + P(1,1)*SF[9] + P(2,1)*SF[11] + P(3,1)*SF[10] + P(10,1)*SF[14] + P(11,1)*SF[15] + P(12,1)*SPP[10] + SF[8]*(P(0,0) + P(1,0)*SF[9] + P(2,0)*SF[11] + P(3,0)*SF[10] + P(10,0)*SF[14] + P(11,0)*SF[15] + P(12,0)*SPP[10]) + SF[7]*(P(0,2) + P(1,2)*SF[9] + P(2,2)*SF[11] + P(3,2)*SF[10] + P(10,2)*SF[14] + P(11,2)*SF[15] + P(12,2)*SPP[10]) + SF[11]*(P(0,3) + P(1,3)*SF[9] + P(2,3)*SF[11] + P(3,3)*SF[10] + P(10,3)*SF[14] + P(11,3)*SF[15] + P(12,3)*SPP[10]) - SF[15]*(P(0,12) + P(1,12)*SF[9] + P(2,12)*SF[11] + P(3,12)*SF[10] + P(10,12)*SF[14] + P(11,12)*SF[15] + P(12,12)*SPP[10]) + SPP[10]*(P(0,11) + P(1,11)*SF[9] + P(2,11)*SF[11] + P(3,11)*SF[10] + P(10,11)*SF[14] + P(11,11)*SF[15] + P(12,11)*SPP[10]) - (q0*(P(0,10) + P(1,10)*SF[9] + P(2,10)*SF[11] + P(3,10)*SF[10] + P(10,10)*SF[14] + P(11,10)*SF[15] + P(12,10)*SPP[10]))*0.5f;
|
||||
nextP(1,1) = P(1,1) + P(0,1)*SF[8] + P(2,1)*SF[7] + P(3,1)*SF[11] - P(12,1)*SF[15] + P(11,1)*SPP[10] + daxVar*SQ[9] - (P(10,1)*q0)*0.5f + SF[8]*(P(1,0) + P(0,0)*SF[8] + P(2,0)*SF[7] + P(3,0)*SF[11] - P(12,0)*SF[15] + P(11,0)*SPP[10] - (P(10,0)*q0)*0.5f) + SF[7]*(P(1,2) + P(0,2)*SF[8] + P(2,2)*SF[7] + P(3,2)*SF[11] - P(12,2)*SF[15] + P(11,2)*SPP[10] - (P(10,2)*q0)*0.5f) + SF[11]*(P(1,3) + P(0,3)*SF[8] + P(2,3)*SF[7] + P(3,3)*SF[11] - P(12,3)*SF[15] + P(11,3)*SPP[10] - (P(10,3)*q0)*0.5f) - SF[15]*(P(1,12) + P(0,12)*SF[8] + P(2,12)*SF[7] + P(3,12)*SF[11] - P(12,12)*SF[15] + P(11,12)*SPP[10] - (P(10,12)*q0)*0.5f) + SPP[10]*(P(1,11) + P(0,11)*SF[8] + P(2,11)*SF[7] + P(3,11)*SF[11] - P(12,11)*SF[15] + P(11,11)*SPP[10] - (P(10,11)*q0)*0.5f) + (dayVar*sq(q3))*0.25f + (dazVar*sq(q2))*0.25f - (q0*(P(1,10) + P(0,10)*SF[8] + P(2,10)*SF[7] + P(3,10)*SF[11] - P(12,10)*SF[15] + P(11,10)*SPP[10] - (P(10,10)*q0)*0.5f))*0.5f;
|
||||
nextP(0,2) = P(0,2) + SQ[7] + P(1,2)*SF[9] + P(2,2)*SF[11] + P(3,2)*SF[10] + P(10,2)*SF[14] + P(11,2)*SF[15] + P(12,2)*SPP[10] + SF[6]*(P(0,0) + P(1,0)*SF[9] + P(2,0)*SF[11] + P(3,0)*SF[10] + P(10,0)*SF[14] + P(11,0)*SF[15] + P(12,0)*SPP[10]) + SF[10]*(P(0,1) + P(1,1)*SF[9] + P(2,1)*SF[11] + P(3,1)*SF[10] + P(10,1)*SF[14] + P(11,1)*SF[15] + P(12,1)*SPP[10]) + SF[8]*(P(0,3) + P(1,3)*SF[9] + P(2,3)*SF[11] + P(3,3)*SF[10] + P(10,3)*SF[14] + P(11,3)*SF[15] + P(12,3)*SPP[10]) + SF[14]*(P(0,12) + P(1,12)*SF[9] + P(2,12)*SF[11] + P(3,12)*SF[10] + P(10,12)*SF[14] + P(11,12)*SF[15] + P(12,12)*SPP[10]) - SPP[10]*(P(0,10) + P(1,10)*SF[9] + P(2,10)*SF[11] + P(3,10)*SF[10] + P(10,10)*SF[14] + P(11,10)*SF[15] + P(12,10)*SPP[10]) - (q0*(P(0,11) + P(1,11)*SF[9] + P(2,11)*SF[11] + P(3,11)*SF[10] + P(10,11)*SF[14] + P(11,11)*SF[15] + P(12,11)*SPP[10]))*0.5f;
|
||||
nextP(1,2) = P(1,2) + SQ[5] + P(0,2)*SF[8] + P(2,2)*SF[7] + P(3,2)*SF[11] - P(12,2)*SF[15] + P(11,2)*SPP[10] - (P(10,2)*q0)*0.5f + SF[6]*(P(1,0) + P(0,0)*SF[8] + P(2,0)*SF[7] + P(3,0)*SF[11] - P(12,0)*SF[15] + P(11,0)*SPP[10] - (P(10,0)*q0)*0.5f) + SF[10]*(P(1,1) + P(0,1)*SF[8] + P(2,1)*SF[7] + P(3,1)*SF[11] - P(12,1)*SF[15] + P(11,1)*SPP[10] - (P(10,1)*q0)*0.5f) + SF[8]*(P(1,3) + P(0,3)*SF[8] + P(2,3)*SF[7] + P(3,3)*SF[11] - P(12,3)*SF[15] + P(11,3)*SPP[10] - (P(10,3)*q0)*0.5f) + SF[14]*(P(1,12) + P(0,12)*SF[8] + P(2,12)*SF[7] + P(3,12)*SF[11] - P(12,12)*SF[15] + P(11,12)*SPP[10] - (P(10,12)*q0)*0.5f) - SPP[10]*(P(1,10) + P(0,10)*SF[8] + P(2,10)*SF[7] + P(3,10)*SF[11] - P(12,10)*SF[15] + P(11,10)*SPP[10] - (P(10,10)*q0)*0.5f) - (q0*(P(1,11) + P(0,11)*SF[8] + P(2,11)*SF[7] + P(3,11)*SF[11] - P(12,11)*SF[15] + P(11,11)*SPP[10] - (P(10,11)*q0)*0.5f))*0.5f;
|
||||
nextP(2,2) = P(2,2) + P(0,2)*SF[6] + P(1,2)*SF[10] + P(3,2)*SF[8] + P(12,2)*SF[14] - P(10,2)*SPP[10] + dayVar*SQ[9] + (dazVar*SQ[10])*0.25f - (P(11,2)*q0)*0.5f + SF[6]*(P(2,0) + P(0,0)*SF[6] + P(1,0)*SF[10] + P(3,0)*SF[8] + P(12,0)*SF[14] - P(10,0)*SPP[10] - (P(11,0)*q0)*0.5f) + SF[10]*(P(2,1) + P(0,1)*SF[6] + P(1,1)*SF[10] + P(3,1)*SF[8] + P(12,1)*SF[14] - P(10,1)*SPP[10] - (P(11,1)*q0)*0.5f) + SF[8]*(P(2,3) + P(0,3)*SF[6] + P(1,3)*SF[10] + P(3,3)*SF[8] + P(12,3)*SF[14] - P(10,3)*SPP[10] - (P(11,3)*q0)*0.5f) + SF[14]*(P(2,12) + P(0,12)*SF[6] + P(1,12)*SF[10] + P(3,12)*SF[8] + P(12,12)*SF[14] - P(10,12)*SPP[10] - (P(11,12)*q0)*0.5f) - SPP[10]*(P(2,10) + P(0,10)*SF[6] + P(1,10)*SF[10] + P(3,10)*SF[8] + P(12,10)*SF[14] - P(10,10)*SPP[10] - (P(11,10)*q0)*0.5f) + (daxVar*sq(q3))*0.25f - (q0*(P(2,11) + P(0,11)*SF[6] + P(1,11)*SF[10] + P(3,11)*SF[8] + P(12,11)*SF[14] - P(10,11)*SPP[10] - (P(11,11)*q0)*0.5f))*0.5f;
|
||||
nextP(0,3) = P(0,3) + SQ[6] + P(1,3)*SF[9] + P(2,3)*SF[11] + P(3,3)*SF[10] + P(10,3)*SF[14] + P(11,3)*SF[15] + P(12,3)*SPP[10] + SF[7]*(P(0,0) + P(1,0)*SF[9] + P(2,0)*SF[11] + P(3,0)*SF[10] + P(10,0)*SF[14] + P(11,0)*SF[15] + P(12,0)*SPP[10]) + SF[6]*(P(0,1) + P(1,1)*SF[9] + P(2,1)*SF[11] + P(3,1)*SF[10] + P(10,1)*SF[14] + P(11,1)*SF[15] + P(12,1)*SPP[10]) + SF[9]*(P(0,2) + P(1,2)*SF[9] + P(2,2)*SF[11] + P(3,2)*SF[10] + P(10,2)*SF[14] + P(11,2)*SF[15] + P(12,2)*SPP[10]) + SF[15]*(P(0,10) + P(1,10)*SF[9] + P(2,10)*SF[11] + P(3,10)*SF[10] + P(10,10)*SF[14] + P(11,10)*SF[15] + P(12,10)*SPP[10]) - SF[14]*(P(0,11) + P(1,11)*SF[9] + P(2,11)*SF[11] + P(3,11)*SF[10] + P(10,11)*SF[14] + P(11,11)*SF[15] + P(12,11)*SPP[10]) - (q0*(P(0,12) + P(1,12)*SF[9] + P(2,12)*SF[11] + P(3,12)*SF[10] + P(10,12)*SF[14] + P(11,12)*SF[15] + P(12,12)*SPP[10]))*0.5f;
|
||||
nextP(1,3) = P(1,3) + SQ[4] + P(0,3)*SF[8] + P(2,3)*SF[7] + P(3,3)*SF[11] - P(12,3)*SF[15] + P(11,3)*SPP[10] - (P(10,3)*q0)*0.5f + SF[7]*(P(1,0) + P(0,0)*SF[8] + P(2,0)*SF[7] + P(3,0)*SF[11] - P(12,0)*SF[15] + P(11,0)*SPP[10] - (P(10,0)*q0)*0.5f) + SF[6]*(P(1,1) + P(0,1)*SF[8] + P(2,1)*SF[7] + P(3,1)*SF[11] - P(12,1)*SF[15] + P(11,1)*SPP[10] - (P(10,1)*q0)*0.5f) + SF[9]*(P(1,2) + P(0,2)*SF[8] + P(2,2)*SF[7] + P(3,2)*SF[11] - P(12,2)*SF[15] + P(11,2)*SPP[10] - (P(10,2)*q0)*0.5f) + SF[15]*(P(1,10) + P(0,10)*SF[8] + P(2,10)*SF[7] + P(3,10)*SF[11] - P(12,10)*SF[15] + P(11,10)*SPP[10] - (P(10,10)*q0)*0.5f) - SF[14]*(P(1,11) + P(0,11)*SF[8] + P(2,11)*SF[7] + P(3,11)*SF[11] - P(12,11)*SF[15] + P(11,11)*SPP[10] - (P(10,11)*q0)*0.5f) - (q0*(P(1,12) + P(0,12)*SF[8] + P(2,12)*SF[7] + P(3,12)*SF[11] - P(12,12)*SF[15] + P(11,12)*SPP[10] - (P(10,12)*q0)*0.5f))*0.5f;
|
||||
nextP(2,3) = P(2,3) + SQ[3] + P(0,3)*SF[6] + P(1,3)*SF[10] + P(3,3)*SF[8] + P(12,3)*SF[14] - P(10,3)*SPP[10] - (P(11,3)*q0)*0.5f + SF[7]*(P(2,0) + P(0,0)*SF[6] + P(1,0)*SF[10] + P(3,0)*SF[8] + P(12,0)*SF[14] - P(10,0)*SPP[10] - (P(11,0)*q0)*0.5f) + SF[6]*(P(2,1) + P(0,1)*SF[6] + P(1,1)*SF[10] + P(3,1)*SF[8] + P(12,1)*SF[14] - P(10,1)*SPP[10] - (P(11,1)*q0)*0.5f) + SF[9]*(P(2,2) + P(0,2)*SF[6] + P(1,2)*SF[10] + P(3,2)*SF[8] + P(12,2)*SF[14] - P(10,2)*SPP[10] - (P(11,2)*q0)*0.5f) + SF[15]*(P(2,10) + P(0,10)*SF[6] + P(1,10)*SF[10] + P(3,10)*SF[8] + P(12,10)*SF[14] - P(10,10)*SPP[10] - (P(11,10)*q0)*0.5f) - SF[14]*(P(2,11) + P(0,11)*SF[6] + P(1,11)*SF[10] + P(3,11)*SF[8] + P(12,11)*SF[14] - P(10,11)*SPP[10] - (P(11,11)*q0)*0.5f) - (q0*(P(2,12) + P(0,12)*SF[6] + P(1,12)*SF[10] + P(3,12)*SF[8] + P(12,12)*SF[14] - P(10,12)*SPP[10] - (P(11,12)*q0)*0.5f))*0.5f;
|
||||
nextP(3,3) = P(3,3) + P(0,3)*SF[7] + P(1,3)*SF[6] + P(2,3)*SF[9] + P(10,3)*SF[15] - P(11,3)*SF[14] + (dayVar*SQ[10])*0.25f + dazVar*SQ[9] - (P(12,3)*q0)*0.5f + SF[7]*(P(3,0) + P(0,0)*SF[7] + P(1,0)*SF[6] + P(2,0)*SF[9] + P(10,0)*SF[15] - P(11,0)*SF[14] - (P(12,0)*q0)*0.5f) + SF[6]*(P(3,1) + P(0,1)*SF[7] + P(1,1)*SF[6] + P(2,1)*SF[9] + P(10,1)*SF[15] - P(11,1)*SF[14] - (P(12,1)*q0)*0.5f) + SF[9]*(P(3,2) + P(0,2)*SF[7] + P(1,2)*SF[6] + P(2,2)*SF[9] + P(10,2)*SF[15] - P(11,2)*SF[14] - (P(12,2)*q0)*0.5f) + SF[15]*(P(3,10) + P(0,10)*SF[7] + P(1,10)*SF[6] + P(2,10)*SF[9] + P(10,10)*SF[15] - P(11,10)*SF[14] - (P(12,10)*q0)*0.5f) - SF[14]*(P(3,11) + P(0,11)*SF[7] + P(1,11)*SF[6] + P(2,11)*SF[9] + P(10,11)*SF[15] - P(11,11)*SF[14] - (P(12,11)*q0)*0.5f) + (daxVar*sq(q2))*0.25f - (q0*(P(3,12) + P(0,12)*SF[7] + P(1,12)*SF[6] + P(2,12)*SF[9] + P(10,12)*SF[15] - P(11,12)*SF[14] - (P(12,12)*q0)*0.5f))*0.5f;
|
||||
nextP(0,4) = P(0,4) + P(1,4)*SF[9] + P(2,4)*SF[11] + P(3,4)*SF[10] + P(10,4)*SF[14] + P(11,4)*SF[15] + P(12,4)*SPP[10] + SF[5]*(P(0,0) + P(1,0)*SF[9] + P(2,0)*SF[11] + P(3,0)*SF[10] + P(10,0)*SF[14] + P(11,0)*SF[15] + P(12,0)*SPP[10]) + SF[3]*(P(0,1) + P(1,1)*SF[9] + P(2,1)*SF[11] + P(3,1)*SF[10] + P(10,1)*SF[14] + P(11,1)*SF[15] + P(12,1)*SPP[10]) - SF[4]*(P(0,3) + P(1,3)*SF[9] + P(2,3)*SF[11] + P(3,3)*SF[10] + P(10,3)*SF[14] + P(11,3)*SF[15] + P(12,3)*SPP[10]) + SPP[0]*(P(0,2) + P(1,2)*SF[9] + P(2,2)*SF[11] + P(3,2)*SF[10] + P(10,2)*SF[14] + P(11,2)*SF[15] + P(12,2)*SPP[10]) + SPP[3]*(P(0,13) + P(1,13)*SF[9] + P(2,13)*SF[11] + P(3,13)*SF[10] + P(10,13)*SF[14] + P(11,13)*SF[15] + P(12,13)*SPP[10]) + SPP[6]*(P(0,14) + P(1,14)*SF[9] + P(2,14)*SF[11] + P(3,14)*SF[10] + P(10,14)*SF[14] + P(11,14)*SF[15] + P(12,14)*SPP[10]) - SPP[9]*(P(0,15) + P(1,15)*SF[9] + P(2,15)*SF[11] + P(3,15)*SF[10] + P(10,15)*SF[14] + P(11,15)*SF[15] + P(12,15)*SPP[10]);
|
||||
nextP(1,4) = P(1,4) + P(0,4)*SF[8] + P(2,4)*SF[7] + P(3,4)*SF[11] - P(12,4)*SF[15] + P(11,4)*SPP[10] - (P(10,4)*q0)*0.5f + SF[5]*(P(1,0) + P(0,0)*SF[8] + P(2,0)*SF[7] + P(3,0)*SF[11] - P(12,0)*SF[15] + P(11,0)*SPP[10] - (P(10,0)*q0)*0.5f) + SF[3]*(P(1,1) + P(0,1)*SF[8] + P(2,1)*SF[7] + P(3,1)*SF[11] - P(12,1)*SF[15] + P(11,1)*SPP[10] - (P(10,1)*q0)*0.5f) - SF[4]*(P(1,3) + P(0,3)*SF[8] + P(2,3)*SF[7] + P(3,3)*SF[11] - P(12,3)*SF[15] + P(11,3)*SPP[10] - (P(10,3)*q0)*0.5f) + SPP[0]*(P(1,2) + P(0,2)*SF[8] + P(2,2)*SF[7] + P(3,2)*SF[11] - P(12,2)*SF[15] + P(11,2)*SPP[10] - (P(10,2)*q0)*0.5f) + SPP[3]*(P(1,13) + P(0,13)*SF[8] + P(2,13)*SF[7] + P(3,13)*SF[11] - P(12,13)*SF[15] + P(11,13)*SPP[10] - (P(10,13)*q0)*0.5f) + SPP[6]*(P(1,14) + P(0,14)*SF[8] + P(2,14)*SF[7] + P(3,14)*SF[11] - P(12,14)*SF[15] + P(11,14)*SPP[10] - (P(10,14)*q0)*0.5f) - SPP[9]*(P(1,15) + P(0,15)*SF[8] + P(2,15)*SF[7] + P(3,15)*SF[11] - P(12,15)*SF[15] + P(11,15)*SPP[10] - (P(10,15)*q0)*0.5f);
|
||||
nextP(2,4) = P(2,4) + P(0,4)*SF[6] + P(1,4)*SF[10] + P(3,4)*SF[8] + P(12,4)*SF[14] - P(10,4)*SPP[10] - (P(11,4)*q0)*0.5f + SF[5]*(P(2,0) + P(0,0)*SF[6] + P(1,0)*SF[10] + P(3,0)*SF[8] + P(12,0)*SF[14] - P(10,0)*SPP[10] - (P(11,0)*q0)*0.5f) + SF[3]*(P(2,1) + P(0,1)*SF[6] + P(1,1)*SF[10] + P(3,1)*SF[8] + P(12,1)*SF[14] - P(10,1)*SPP[10] - (P(11,1)*q0)*0.5f) - SF[4]*(P(2,3) + P(0,3)*SF[6] + P(1,3)*SF[10] + P(3,3)*SF[8] + P(12,3)*SF[14] - P(10,3)*SPP[10] - (P(11,3)*q0)*0.5f) + SPP[0]*(P(2,2) + P(0,2)*SF[6] + P(1,2)*SF[10] + P(3,2)*SF[8] + P(12,2)*SF[14] - P(10,2)*SPP[10] - (P(11,2)*q0)*0.5f) + SPP[3]*(P(2,13) + P(0,13)*SF[6] + P(1,13)*SF[10] + P(3,13)*SF[8] + P(12,13)*SF[14] - P(10,13)*SPP[10] - (P(11,13)*q0)*0.5f) + SPP[6]*(P(2,14) + P(0,14)*SF[6] + P(1,14)*SF[10] + P(3,14)*SF[8] + P(12,14)*SF[14] - P(10,14)*SPP[10] - (P(11,14)*q0)*0.5f) - SPP[9]*(P(2,15) + P(0,15)*SF[6] + P(1,15)*SF[10] + P(3,15)*SF[8] + P(12,15)*SF[14] - P(10,15)*SPP[10] - (P(11,15)*q0)*0.5f);
|
||||
nextP(3,4) = P(3,4) + P(0,4)*SF[7] + P(1,4)*SF[6] + P(2,4)*SF[9] + P(10,4)*SF[15] - P(11,4)*SF[14] - (P(12,4)*q0)*0.5f + SF[5]*(P(3,0) + P(0,0)*SF[7] + P(1,0)*SF[6] + P(2,0)*SF[9] + P(10,0)*SF[15] - P(11,0)*SF[14] - (P(12,0)*q0)*0.5f) + SF[3]*(P(3,1) + P(0,1)*SF[7] + P(1,1)*SF[6] + P(2,1)*SF[9] + P(10,1)*SF[15] - P(11,1)*SF[14] - (P(12,1)*q0)*0.5f) - SF[4]*(P(3,3) + P(0,3)*SF[7] + P(1,3)*SF[6] + P(2,3)*SF[9] + P(10,3)*SF[15] - P(11,3)*SF[14] - (P(12,3)*q0)*0.5f) + SPP[0]*(P(3,2) + P(0,2)*SF[7] + P(1,2)*SF[6] + P(2,2)*SF[9] + P(10,2)*SF[15] - P(11,2)*SF[14] - (P(12,2)*q0)*0.5f) + SPP[3]*(P(3,13) + P(0,13)*SF[7] + P(1,13)*SF[6] + P(2,13)*SF[9] + P(10,13)*SF[15] - P(11,13)*SF[14] - (P(12,13)*q0)*0.5f) + SPP[6]*(P(3,14) + P(0,14)*SF[7] + P(1,14)*SF[6] + P(2,14)*SF[9] + P(10,14)*SF[15] - P(11,14)*SF[14] - (P(12,14)*q0)*0.5f) - SPP[9]*(P(3,15) + P(0,15)*SF[7] + P(1,15)*SF[6] + P(2,15)*SF[9] + P(10,15)*SF[15] - P(11,15)*SF[14] - (P(12,15)*q0)*0.5f);
|
||||
nextP(4,4) = P(4,4) + P(0,4)*SF[5] + P(1,4)*SF[3] - P(3,4)*SF[4] + P(2,4)*SPP[0] + P(13,4)*SPP[3] + P(14,4)*SPP[6] - P(15,4)*SPP[9] + dvyVar*sq(SG[7] - 2*q0*q3) + dvzVar*sq(SG[6] + 2*q0*q2) + SF[5]*(P(4,0) + P(0,0)*SF[5] + P(1,0)*SF[3] - P(3,0)*SF[4] + P(2,0)*SPP[0] + P(13,0)*SPP[3] + P(14,0)*SPP[6] - P(15,0)*SPP[9]) + SF[3]*(P(4,1) + P(0,1)*SF[5] + P(1,1)*SF[3] - P(3,1)*SF[4] + P(2,1)*SPP[0] + P(13,1)*SPP[3] + P(14,1)*SPP[6] - P(15,1)*SPP[9]) - SF[4]*(P(4,3) + P(0,3)*SF[5] + P(1,3)*SF[3] - P(3,3)*SF[4] + P(2,3)*SPP[0] + P(13,3)*SPP[3] + P(14,3)*SPP[6] - P(15,3)*SPP[9]) + SPP[0]*(P(4,2) + P(0,2)*SF[5] + P(1,2)*SF[3] - P(3,2)*SF[4] + P(2,2)*SPP[0] + P(13,2)*SPP[3] + P(14,2)*SPP[6] - P(15,2)*SPP[9]) + SPP[3]*(P(4,13) + P(0,13)*SF[5] + P(1,13)*SF[3] - P(3,13)*SF[4] + P(2,13)*SPP[0] + P(13,13)*SPP[3] + P(14,13)*SPP[6] - P(15,13)*SPP[9]) + SPP[6]*(P(4,14) + P(0,14)*SF[5] + P(1,14)*SF[3] - P(3,14)*SF[4] + P(2,14)*SPP[0] + P(13,14)*SPP[3] + P(14,14)*SPP[6] - P(15,14)*SPP[9]) - SPP[9]*(P(4,15) + P(0,15)*SF[5] + P(1,15)*SF[3] - P(3,15)*SF[4] + P(2,15)*SPP[0] + P(13,15)*SPP[3] + P(14,15)*SPP[6] - P(15,15)*SPP[9]) + dvxVar*sq(SG[1] + SG[2] - SG[3] - SG[4]);
|
||||
nextP(0,5) = P(0,5) + P(1,5)*SF[9] + P(2,5)*SF[11] + P(3,5)*SF[10] + P(10,5)*SF[14] + P(11,5)*SF[15] + P(12,5)*SPP[10] + SF[4]*(P(0,0) + P(1,0)*SF[9] + P(2,0)*SF[11] + P(3,0)*SF[10] + P(10,0)*SF[14] + P(11,0)*SF[15] + P(12,0)*SPP[10]) + SF[3]*(P(0,2) + P(1,2)*SF[9] + P(2,2)*SF[11] + P(3,2)*SF[10] + P(10,2)*SF[14] + P(11,2)*SF[15] + P(12,2)*SPP[10]) + SF[5]*(P(0,3) + P(1,3)*SF[9] + P(2,3)*SF[11] + P(3,3)*SF[10] + P(10,3)*SF[14] + P(11,3)*SF[15] + P(12,3)*SPP[10]) - SPP[0]*(P(0,1) + P(1,1)*SF[9] + P(2,1)*SF[11] + P(3,1)*SF[10] + P(10,1)*SF[14] + P(11,1)*SF[15] + P(12,1)*SPP[10]) - SPP[8]*(P(0,13) + P(1,13)*SF[9] + P(2,13)*SF[11] + P(3,13)*SF[10] + P(10,13)*SF[14] + P(11,13)*SF[15] + P(12,13)*SPP[10]) + SPP[2]*(P(0,14) + P(1,14)*SF[9] + P(2,14)*SF[11] + P(3,14)*SF[10] + P(10,14)*SF[14] + P(11,14)*SF[15] + P(12,14)*SPP[10]) + SPP[5]*(P(0,15) + P(1,15)*SF[9] + P(2,15)*SF[11] + P(3,15)*SF[10] + P(10,15)*SF[14] + P(11,15)*SF[15] + P(12,15)*SPP[10]);
|
||||
nextP(1,5) = P(1,5) + P(0,5)*SF[8] + P(2,5)*SF[7] + P(3,5)*SF[11] - P(12,5)*SF[15] + P(11,5)*SPP[10] - (P(10,5)*q0)*0.5f + SF[4]*(P(1,0) + P(0,0)*SF[8] + P(2,0)*SF[7] + P(3,0)*SF[11] - P(12,0)*SF[15] + P(11,0)*SPP[10] - (P(10,0)*q0)*0.5f) + SF[3]*(P(1,2) + P(0,2)*SF[8] + P(2,2)*SF[7] + P(3,2)*SF[11] - P(12,2)*SF[15] + P(11,2)*SPP[10] - (P(10,2)*q0)*0.5f) + SF[5]*(P(1,3) + P(0,3)*SF[8] + P(2,3)*SF[7] + P(3,3)*SF[11] - P(12,3)*SF[15] + P(11,3)*SPP[10] - (P(10,3)*q0)*0.5f) - SPP[0]*(P(1,1) + P(0,1)*SF[8] + P(2,1)*SF[7] + P(3,1)*SF[11] - P(12,1)*SF[15] + P(11,1)*SPP[10] - (P(10,1)*q0)*0.5f) - SPP[8]*(P(1,13) + P(0,13)*SF[8] + P(2,13)*SF[7] + P(3,13)*SF[11] - P(12,13)*SF[15] + P(11,13)*SPP[10] - (P(10,13)*q0)*0.5f) + SPP[2]*(P(1,14) + P(0,14)*SF[8] + P(2,14)*SF[7] + P(3,14)*SF[11] - P(12,14)*SF[15] + P(11,14)*SPP[10] - (P(10,14)*q0)*0.5f) + SPP[5]*(P(1,15) + P(0,15)*SF[8] + P(2,15)*SF[7] + P(3,15)*SF[11] - P(12,15)*SF[15] + P(11,15)*SPP[10] - (P(10,15)*q0)*0.5f);
|
||||
nextP(2,5) = P(2,5) + P(0,5)*SF[6] + P(1,5)*SF[10] + P(3,5)*SF[8] + P(12,5)*SF[14] - P(10,5)*SPP[10] - (P(11,5)*q0)*0.5f + SF[4]*(P(2,0) + P(0,0)*SF[6] + P(1,0)*SF[10] + P(3,0)*SF[8] + P(12,0)*SF[14] - P(10,0)*SPP[10] - (P(11,0)*q0)*0.5f) + SF[3]*(P(2,2) + P(0,2)*SF[6] + P(1,2)*SF[10] + P(3,2)*SF[8] + P(12,2)*SF[14] - P(10,2)*SPP[10] - (P(11,2)*q0)*0.5f) + SF[5]*(P(2,3) + P(0,3)*SF[6] + P(1,3)*SF[10] + P(3,3)*SF[8] + P(12,3)*SF[14] - P(10,3)*SPP[10] - (P(11,3)*q0)*0.5f) - SPP[0]*(P(2,1) + P(0,1)*SF[6] + P(1,1)*SF[10] + P(3,1)*SF[8] + P(12,1)*SF[14] - P(10,1)*SPP[10] - (P(11,1)*q0)*0.5f) - SPP[8]*(P(2,13) + P(0,13)*SF[6] + P(1,13)*SF[10] + P(3,13)*SF[8] + P(12,13)*SF[14] - P(10,13)*SPP[10] - (P(11,13)*q0)*0.5f) + SPP[2]*(P(2,14) + P(0,14)*SF[6] + P(1,14)*SF[10] + P(3,14)*SF[8] + P(12,14)*SF[14] - P(10,14)*SPP[10] - (P(11,14)*q0)*0.5f) + SPP[5]*(P(2,15) + P(0,15)*SF[6] + P(1,15)*SF[10] + P(3,15)*SF[8] + P(12,15)*SF[14] - P(10,15)*SPP[10] - (P(11,15)*q0)*0.5f);
|
||||
nextP(3,5) = P(3,5) + P(0,5)*SF[7] + P(1,5)*SF[6] + P(2,5)*SF[9] + P(10,5)*SF[15] - P(11,5)*SF[14] - (P(12,5)*q0)*0.5f + SF[4]*(P(3,0) + P(0,0)*SF[7] + P(1,0)*SF[6] + P(2,0)*SF[9] + P(10,0)*SF[15] - P(11,0)*SF[14] - (P(12,0)*q0)*0.5f) + SF[3]*(P(3,2) + P(0,2)*SF[7] + P(1,2)*SF[6] + P(2,2)*SF[9] + P(10,2)*SF[15] - P(11,2)*SF[14] - (P(12,2)*q0)*0.5f) + SF[5]*(P(3,3) + P(0,3)*SF[7] + P(1,3)*SF[6] + P(2,3)*SF[9] + P(10,3)*SF[15] - P(11,3)*SF[14] - (P(12,3)*q0)*0.5f) - SPP[0]*(P(3,1) + P(0,1)*SF[7] + P(1,1)*SF[6] + P(2,1)*SF[9] + P(10,1)*SF[15] - P(11,1)*SF[14] - (P(12,1)*q0)*0.5f) - SPP[8]*(P(3,13) + P(0,13)*SF[7] + P(1,13)*SF[6] + P(2,13)*SF[9] + P(10,13)*SF[15] - P(11,13)*SF[14] - (P(12,13)*q0)*0.5f) + SPP[2]*(P(3,14) + P(0,14)*SF[7] + P(1,14)*SF[6] + P(2,14)*SF[9] + P(10,14)*SF[15] - P(11,14)*SF[14] - (P(12,14)*q0)*0.5f) + SPP[5]*(P(3,15) + P(0,15)*SF[7] + P(1,15)*SF[6] + P(2,15)*SF[9] + P(10,15)*SF[15] - P(11,15)*SF[14] - (P(12,15)*q0)*0.5f);
|
||||
nextP(4,5) = P(4,5) + SQ[2] + P(0,5)*SF[5] + P(1,5)*SF[3] - P(3,5)*SF[4] + P(2,5)*SPP[0] + P(13,5)*SPP[3] + P(14,5)*SPP[6] - P(15,5)*SPP[9] + SF[4]*(P(4,0) + P(0,0)*SF[5] + P(1,0)*SF[3] - P(3,0)*SF[4] + P(2,0)*SPP[0] + P(13,0)*SPP[3] + P(14,0)*SPP[6] - P(15,0)*SPP[9]) + SF[3]*(P(4,2) + P(0,2)*SF[5] + P(1,2)*SF[3] - P(3,2)*SF[4] + P(2,2)*SPP[0] + P(13,2)*SPP[3] + P(14,2)*SPP[6] - P(15,2)*SPP[9]) + SF[5]*(P(4,3) + P(0,3)*SF[5] + P(1,3)*SF[3] - P(3,3)*SF[4] + P(2,3)*SPP[0] + P(13,3)*SPP[3] + P(14,3)*SPP[6] - P(15,3)*SPP[9]) - SPP[0]*(P(4,1) + P(0,1)*SF[5] + P(1,1)*SF[3] - P(3,1)*SF[4] + P(2,1)*SPP[0] + P(13,1)*SPP[3] + P(14,1)*SPP[6] - P(15,1)*SPP[9]) - SPP[8]*(P(4,13) + P(0,13)*SF[5] + P(1,13)*SF[3] - P(3,13)*SF[4] + P(2,13)*SPP[0] + P(13,13)*SPP[3] + P(14,13)*SPP[6] - P(15,13)*SPP[9]) + SPP[2]*(P(4,14) + P(0,14)*SF[5] + P(1,14)*SF[3] - P(3,14)*SF[4] + P(2,14)*SPP[0] + P(13,14)*SPP[3] + P(14,14)*SPP[6] - P(15,14)*SPP[9]) + SPP[5]*(P(4,15) + P(0,15)*SF[5] + P(1,15)*SF[3] - P(3,15)*SF[4] + P(2,15)*SPP[0] + P(13,15)*SPP[3] + P(14,15)*SPP[6] - P(15,15)*SPP[9]);
|
||||
nextP(5,5) = P(5,5) + P(0,5)*SF[4] + P(2,5)*SF[3] + P(3,5)*SF[5] - P(1,5)*SPP[0] - P(13,5)*SPP[8] + P(14,5)*SPP[2] + P(15,5)*SPP[5] + dvxVar*sq(SG[7] + 2*q0*q3) + dvzVar*sq(SG[5] - 2*q0*q1) + SF[4]*(P(5,0) + P(0,0)*SF[4] + P(2,0)*SF[3] + P(3,0)*SF[5] - P(1,0)*SPP[0] - P(13,0)*SPP[8] + P(14,0)*SPP[2] + P(15,0)*SPP[5]) + SF[3]*(P(5,2) + P(0,2)*SF[4] + P(2,2)*SF[3] + P(3,2)*SF[5] - P(1,2)*SPP[0] - P(13,2)*SPP[8] + P(14,2)*SPP[2] + P(15,2)*SPP[5]) + SF[5]*(P(5,3) + P(0,3)*SF[4] + P(2,3)*SF[3] + P(3,3)*SF[5] - P(1,3)*SPP[0] - P(13,3)*SPP[8] + P(14,3)*SPP[2] + P(15,3)*SPP[5]) - SPP[0]*(P(5,1) + P(0,1)*SF[4] + P(2,1)*SF[3] + P(3,1)*SF[5] - P(1,1)*SPP[0] - P(13,1)*SPP[8] + P(14,1)*SPP[2] + P(15,1)*SPP[5]) - SPP[8]*(P(5,13) + P(0,13)*SF[4] + P(2,13)*SF[3] + P(3,13)*SF[5] - P(1,13)*SPP[0] - P(13,13)*SPP[8] + P(14,13)*SPP[2] + P(15,13)*SPP[5]) + SPP[2]*(P(5,14) + P(0,14)*SF[4] + P(2,14)*SF[3] + P(3,14)*SF[5] - P(1,14)*SPP[0] - P(13,14)*SPP[8] + P(14,14)*SPP[2] + P(15,14)*SPP[5]) + SPP[5]*(P(5,15) + P(0,15)*SF[4] + P(2,15)*SF[3] + P(3,15)*SF[5] - P(1,15)*SPP[0] - P(13,15)*SPP[8] + P(14,15)*SPP[2] + P(15,15)*SPP[5]) + dvyVar*sq(SG[1] - SG[2] + SG[3] - SG[4]);
|
||||
nextP(0,6) = P(0,6) + P(1,6)*SF[9] + P(2,6)*SF[11] + P(3,6)*SF[10] + P(10,6)*SF[14] + P(11,6)*SF[15] + P(12,6)*SPP[10] + SF[4]*(P(0,1) + P(1,1)*SF[9] + P(2,1)*SF[11] + P(3,1)*SF[10] + P(10,1)*SF[14] + P(11,1)*SF[15] + P(12,1)*SPP[10]) - SF[5]*(P(0,2) + P(1,2)*SF[9] + P(2,2)*SF[11] + P(3,2)*SF[10] + P(10,2)*SF[14] + P(11,2)*SF[15] + P(12,2)*SPP[10]) + SF[3]*(P(0,3) + P(1,3)*SF[9] + P(2,3)*SF[11] + P(3,3)*SF[10] + P(10,3)*SF[14] + P(11,3)*SF[15] + P(12,3)*SPP[10]) + SPP[0]*(P(0,0) + P(1,0)*SF[9] + P(2,0)*SF[11] + P(3,0)*SF[10] + P(10,0)*SF[14] + P(11,0)*SF[15] + P(12,0)*SPP[10]) + SPP[4]*(P(0,13) + P(1,13)*SF[9] + P(2,13)*SF[11] + P(3,13)*SF[10] + P(10,13)*SF[14] + P(11,13)*SF[15] + P(12,13)*SPP[10]) - SPP[7]*(P(0,14) + P(1,14)*SF[9] + P(2,14)*SF[11] + P(3,14)*SF[10] + P(10,14)*SF[14] + P(11,14)*SF[15] + P(12,14)*SPP[10]) - SPP[1]*(P(0,15) + P(1,15)*SF[9] + P(2,15)*SF[11] + P(3,15)*SF[10] + P(10,15)*SF[14] + P(11,15)*SF[15] + P(12,15)*SPP[10]);
|
||||
nextP(1,6) = P(1,6) + P(0,6)*SF[8] + P(2,6)*SF[7] + P(3,6)*SF[11] - P(12,6)*SF[15] + P(11,6)*SPP[10] - (P(10,6)*q0)*0.5f + SF[4]*(P(1,1) + P(0,1)*SF[8] + P(2,1)*SF[7] + P(3,1)*SF[11] - P(12,1)*SF[15] + P(11,1)*SPP[10] - (P(10,1)*q0)*0.5f) - SF[5]*(P(1,2) + P(0,2)*SF[8] + P(2,2)*SF[7] + P(3,2)*SF[11] - P(12,2)*SF[15] + P(11,2)*SPP[10] - (P(10,2)*q0)*0.5f) + SF[3]*(P(1,3) + P(0,3)*SF[8] + P(2,3)*SF[7] + P(3,3)*SF[11] - P(12,3)*SF[15] + P(11,3)*SPP[10] - (P(10,3)*q0)*0.5f) + SPP[0]*(P(1,0) + P(0,0)*SF[8] + P(2,0)*SF[7] + P(3,0)*SF[11] - P(12,0)*SF[15] + P(11,0)*SPP[10] - (P(10,0)*q0)*0.5f) + SPP[4]*(P(1,13) + P(0,13)*SF[8] + P(2,13)*SF[7] + P(3,13)*SF[11] - P(12,13)*SF[15] + P(11,13)*SPP[10] - (P(10,13)*q0)*0.5f) - SPP[7]*(P(1,14) + P(0,14)*SF[8] + P(2,14)*SF[7] + P(3,14)*SF[11] - P(12,14)*SF[15] + P(11,14)*SPP[10] - (P(10,14)*q0)*0.5f) - SPP[1]*(P(1,15) + P(0,15)*SF[8] + P(2,15)*SF[7] + P(3,15)*SF[11] - P(12,15)*SF[15] + P(11,15)*SPP[10] - (P(10,15)*q0)*0.5f);
|
||||
nextP(2,6) = P(2,6) + P(0,6)*SF[6] + P(1,6)*SF[10] + P(3,6)*SF[8] + P(12,6)*SF[14] - P(10,6)*SPP[10] - (P(11,6)*q0)*0.5f + SF[4]*(P(2,1) + P(0,1)*SF[6] + P(1,1)*SF[10] + P(3,1)*SF[8] + P(12,1)*SF[14] - P(10,1)*SPP[10] - (P(11,1)*q0)*0.5f) - SF[5]*(P(2,2) + P(0,2)*SF[6] + P(1,2)*SF[10] + P(3,2)*SF[8] + P(12,2)*SF[14] - P(10,2)*SPP[10] - (P(11,2)*q0)*0.5f) + SF[3]*(P(2,3) + P(0,3)*SF[6] + P(1,3)*SF[10] + P(3,3)*SF[8] + P(12,3)*SF[14] - P(10,3)*SPP[10] - (P(11,3)*q0)*0.5f) + SPP[0]*(P(2,0) + P(0,0)*SF[6] + P(1,0)*SF[10] + P(3,0)*SF[8] + P(12,0)*SF[14] - P(10,0)*SPP[10] - (P(11,0)*q0)*0.5f) + SPP[4]*(P(2,13) + P(0,13)*SF[6] + P(1,13)*SF[10] + P(3,13)*SF[8] + P(12,13)*SF[14] - P(10,13)*SPP[10] - (P(11,13)*q0)*0.5f) - SPP[7]*(P(2,14) + P(0,14)*SF[6] + P(1,14)*SF[10] + P(3,14)*SF[8] + P(12,14)*SF[14] - P(10,14)*SPP[10] - (P(11,14)*q0)*0.5f) - SPP[1]*(P(2,15) + P(0,15)*SF[6] + P(1,15)*SF[10] + P(3,15)*SF[8] + P(12,15)*SF[14] - P(10,15)*SPP[10] - (P(11,15)*q0)*0.5f);
|
||||
nextP(3,6) = P(3,6) + P(0,6)*SF[7] + P(1,6)*SF[6] + P(2,6)*SF[9] + P(10,6)*SF[15] - P(11,6)*SF[14] - (P(12,6)*q0)*0.5f + SF[4]*(P(3,1) + P(0,1)*SF[7] + P(1,1)*SF[6] + P(2,1)*SF[9] + P(10,1)*SF[15] - P(11,1)*SF[14] - (P(12,1)*q0)*0.5f) - SF[5]*(P(3,2) + P(0,2)*SF[7] + P(1,2)*SF[6] + P(2,2)*SF[9] + P(10,2)*SF[15] - P(11,2)*SF[14] - (P(12,2)*q0)*0.5f) + SF[3]*(P(3,3) + P(0,3)*SF[7] + P(1,3)*SF[6] + P(2,3)*SF[9] + P(10,3)*SF[15] - P(11,3)*SF[14] - (P(12,3)*q0)*0.5f) + SPP[0]*(P(3,0) + P(0,0)*SF[7] + P(1,0)*SF[6] + P(2,0)*SF[9] + P(10,0)*SF[15] - P(11,0)*SF[14] - (P(12,0)*q0)*0.5f) + SPP[4]*(P(3,13) + P(0,13)*SF[7] + P(1,13)*SF[6] + P(2,13)*SF[9] + P(10,13)*SF[15] - P(11,13)*SF[14] - (P(12,13)*q0)*0.5f) - SPP[7]*(P(3,14) + P(0,14)*SF[7] + P(1,14)*SF[6] + P(2,14)*SF[9] + P(10,14)*SF[15] - P(11,14)*SF[14] - (P(12,14)*q0)*0.5f) - SPP[1]*(P(3,15) + P(0,15)*SF[7] + P(1,15)*SF[6] + P(2,15)*SF[9] + P(10,15)*SF[15] - P(11,15)*SF[14] - (P(12,15)*q0)*0.5f);
|
||||
nextP(4,6) = P(4,6) + SQ[1] + P(0,6)*SF[5] + P(1,6)*SF[3] - P(3,6)*SF[4] + P(2,6)*SPP[0] + P(13,6)*SPP[3] + P(14,6)*SPP[6] - P(15,6)*SPP[9] + SF[4]*(P(4,1) + P(0,1)*SF[5] + P(1,1)*SF[3] - P(3,1)*SF[4] + P(2,1)*SPP[0] + P(13,1)*SPP[3] + P(14,1)*SPP[6] - P(15,1)*SPP[9]) - SF[5]*(P(4,2) + P(0,2)*SF[5] + P(1,2)*SF[3] - P(3,2)*SF[4] + P(2,2)*SPP[0] + P(13,2)*SPP[3] + P(14,2)*SPP[6] - P(15,2)*SPP[9]) + SF[3]*(P(4,3) + P(0,3)*SF[5] + P(1,3)*SF[3] - P(3,3)*SF[4] + P(2,3)*SPP[0] + P(13,3)*SPP[3] + P(14,3)*SPP[6] - P(15,3)*SPP[9]) + SPP[0]*(P(4,0) + P(0,0)*SF[5] + P(1,0)*SF[3] - P(3,0)*SF[4] + P(2,0)*SPP[0] + P(13,0)*SPP[3] + P(14,0)*SPP[6] - P(15,0)*SPP[9]) + SPP[4]*(P(4,13) + P(0,13)*SF[5] + P(1,13)*SF[3] - P(3,13)*SF[4] + P(2,13)*SPP[0] + P(13,13)*SPP[3] + P(14,13)*SPP[6] - P(15,13)*SPP[9]) - SPP[7]*(P(4,14) + P(0,14)*SF[5] + P(1,14)*SF[3] - P(3,14)*SF[4] + P(2,14)*SPP[0] + P(13,14)*SPP[3] + P(14,14)*SPP[6] - P(15,14)*SPP[9]) - SPP[1]*(P(4,15) + P(0,15)*SF[5] + P(1,15)*SF[3] - P(3,15)*SF[4] + P(2,15)*SPP[0] + P(13,15)*SPP[3] + P(14,15)*SPP[6] - P(15,15)*SPP[9]);
|
||||
nextP(5,6) = P(5,6) + SQ[0] + P(0,6)*SF[4] + P(2,6)*SF[3] + P(3,6)*SF[5] - P(1,6)*SPP[0] - P(13,6)*SPP[8] + P(14,6)*SPP[2] + P(15,6)*SPP[5] + SF[4]*(P(5,1) + P(0,1)*SF[4] + P(2,1)*SF[3] + P(3,1)*SF[5] - P(1,1)*SPP[0] - P(13,1)*SPP[8] + P(14,1)*SPP[2] + P(15,1)*SPP[5]) - SF[5]*(P(5,2) + P(0,2)*SF[4] + P(2,2)*SF[3] + P(3,2)*SF[5] - P(1,2)*SPP[0] - P(13,2)*SPP[8] + P(14,2)*SPP[2] + P(15,2)*SPP[5]) + SF[3]*(P(5,3) + P(0,3)*SF[4] + P(2,3)*SF[3] + P(3,3)*SF[5] - P(1,3)*SPP[0] - P(13,3)*SPP[8] + P(14,3)*SPP[2] + P(15,3)*SPP[5]) + SPP[0]*(P(5,0) + P(0,0)*SF[4] + P(2,0)*SF[3] + P(3,0)*SF[5] - P(1,0)*SPP[0] - P(13,0)*SPP[8] + P(14,0)*SPP[2] + P(15,0)*SPP[5]) + SPP[4]*(P(5,13) + P(0,13)*SF[4] + P(2,13)*SF[3] + P(3,13)*SF[5] - P(1,13)*SPP[0] - P(13,13)*SPP[8] + P(14,13)*SPP[2] + P(15,13)*SPP[5]) - SPP[7]*(P(5,14) + P(0,14)*SF[4] + P(2,14)*SF[3] + P(3,14)*SF[5] - P(1,14)*SPP[0] - P(13,14)*SPP[8] + P(14,14)*SPP[2] + P(15,14)*SPP[5]) - SPP[1]*(P(5,15) + P(0,15)*SF[4] + P(2,15)*SF[3] + P(3,15)*SF[5] - P(1,15)*SPP[0] - P(13,15)*SPP[8] + P(14,15)*SPP[2] + P(15,15)*SPP[5]);
|
||||
nextP(6,6) = P(6,6) + P(1,6)*SF[4] - P(2,6)*SF[5] + P(3,6)*SF[3] + P(0,6)*SPP[0] + P(13,6)*SPP[4] - P(14,6)*SPP[7] - P(15,6)*SPP[1] + dvxVar*sq(SG[6] - 2*q0*q2) + dvyVar*sq(SG[5] + 2*q0*q1) + SF[4]*(P(6,1) + P(1,1)*SF[4] - P(2,1)*SF[5] + P(3,1)*SF[3] + P(0,1)*SPP[0] + P(13,1)*SPP[4] - P(14,1)*SPP[7] - P(15,1)*SPP[1]) - SF[5]*(P(6,2) + P(1,2)*SF[4] - P(2,2)*SF[5] + P(3,2)*SF[3] + P(0,2)*SPP[0] + P(13,2)*SPP[4] - P(14,2)*SPP[7] - P(15,2)*SPP[1]) + SF[3]*(P(6,3) + P(1,3)*SF[4] - P(2,3)*SF[5] + P(3,3)*SF[3] + P(0,3)*SPP[0] + P(13,3)*SPP[4] - P(14,3)*SPP[7] - P(15,3)*SPP[1]) + SPP[0]*(P(6,0) + P(1,0)*SF[4] - P(2,0)*SF[5] + P(3,0)*SF[3] + P(0,0)*SPP[0] + P(13,0)*SPP[4] - P(14,0)*SPP[7] - P(15,0)*SPP[1]) + SPP[4]*(P(6,13) + P(1,13)*SF[4] - P(2,13)*SF[5] + P(3,13)*SF[3] + P(0,13)*SPP[0] + P(13,13)*SPP[4] - P(14,13)*SPP[7] - P(15,13)*SPP[1]) - SPP[7]*(P(6,14) + P(1,14)*SF[4] - P(2,14)*SF[5] + P(3,14)*SF[3] + P(0,14)*SPP[0] + P(13,14)*SPP[4] - P(14,14)*SPP[7] - P(15,14)*SPP[1]) - SPP[1]*(P(6,15) + P(1,15)*SF[4] - P(2,15)*SF[5] + P(3,15)*SF[3] + P(0,15)*SPP[0] + P(13,15)*SPP[4] - P(14,15)*SPP[7] - P(15,15)*SPP[1]) + dvzVar*sq(SG[1] - SG[2] - SG[3] + SG[4]);
|
||||
nextP(0,7) = P(0,7) + P(1,7)*SF[9] + P(2,7)*SF[11] + P(3,7)*SF[10] + P(10,7)*SF[14] + P(11,7)*SF[15] + P(12,7)*SPP[10] + dt*(P(0,4) + P(1,4)*SF[9] + P(2,4)*SF[11] + P(3,4)*SF[10] + P(10,4)*SF[14] + P(11,4)*SF[15] + P(12,4)*SPP[10]);
|
||||
nextP(1,7) = P(1,7) + P(0,7)*SF[8] + P(2,7)*SF[7] + P(3,7)*SF[11] - P(12,7)*SF[15] + P(11,7)*SPP[10] - (P(10,7)*q0)*0.5f + dt*(P(1,4) + P(0,4)*SF[8] + P(2,4)*SF[7] + P(3,4)*SF[11] - P(12,4)*SF[15] + P(11,4)*SPP[10] - (P(10,4)*q0)*0.5f);
|
||||
nextP(2,7) = P(2,7) + P(0,7)*SF[6] + P(1,7)*SF[10] + P(3,7)*SF[8] + P(12,7)*SF[14] - P(10,7)*SPP[10] - (P(11,7)*q0)*0.5f + dt*(P(2,4) + P(0,4)*SF[6] + P(1,4)*SF[10] + P(3,4)*SF[8] + P(12,4)*SF[14] - P(10,4)*SPP[10] - (P(11,4)*q0)*0.5f);
|
||||
nextP(3,7) = P(3,7) + P(0,7)*SF[7] + P(1,7)*SF[6] + P(2,7)*SF[9] + P(10,7)*SF[15] - P(11,7)*SF[14] - (P(12,7)*q0)*0.5f + dt*(P(3,4) + P(0,4)*SF[7] + P(1,4)*SF[6] + P(2,4)*SF[9] + P(10,4)*SF[15] - P(11,4)*SF[14] - (P(12,4)*q0)*0.5f);
|
||||
nextP(4,7) = P(4,7) + P(0,7)*SF[5] + P(1,7)*SF[3] - P(3,7)*SF[4] + P(2,7)*SPP[0] + P(13,7)*SPP[3] + P(14,7)*SPP[6] - P(15,7)*SPP[9] + dt*(P(4,4) + P(0,4)*SF[5] + P(1,4)*SF[3] - P(3,4)*SF[4] + P(2,4)*SPP[0] + P(13,4)*SPP[3] + P(14,4)*SPP[6] - P(15,4)*SPP[9]);
|
||||
nextP(5,7) = P(5,7) + P(0,7)*SF[4] + P(2,7)*SF[3] + P(3,7)*SF[5] - P(1,7)*SPP[0] - P(13,7)*SPP[8] + P(14,7)*SPP[2] + P(15,7)*SPP[5] + dt*(P(5,4) + P(0,4)*SF[4] + P(2,4)*SF[3] + P(3,4)*SF[5] - P(1,4)*SPP[0] - P(13,4)*SPP[8] + P(14,4)*SPP[2] + P(15,4)*SPP[5]);
|
||||
nextP(6,7) = P(6,7) + P(1,7)*SF[4] - P(2,7)*SF[5] + P(3,7)*SF[3] + P(0,7)*SPP[0] + P(13,7)*SPP[4] - P(14,7)*SPP[7] - P(15,7)*SPP[1] + dt*(P(6,4) + P(1,4)*SF[4] - P(2,4)*SF[5] + P(3,4)*SF[3] + P(0,4)*SPP[0] + P(13,4)*SPP[4] - P(14,4)*SPP[7] - P(15,4)*SPP[1]);
|
||||
nextP(7,7) = P(7,7) + P(4,7)*dt + dt*(P(7,4) + P(4,4)*dt);
|
||||
nextP(0,8) = P(0,8) + P(1,8)*SF[9] + P(2,8)*SF[11] + P(3,8)*SF[10] + P(10,8)*SF[14] + P(11,8)*SF[15] + P(12,8)*SPP[10] + dt*(P(0,5) + P(1,5)*SF[9] + P(2,5)*SF[11] + P(3,5)*SF[10] + P(10,5)*SF[14] + P(11,5)*SF[15] + P(12,5)*SPP[10]);
|
||||
nextP(1,8) = P(1,8) + P(0,8)*SF[8] + P(2,8)*SF[7] + P(3,8)*SF[11] - P(12,8)*SF[15] + P(11,8)*SPP[10] - (P(10,8)*q0)*0.5f + dt*(P(1,5) + P(0,5)*SF[8] + P(2,5)*SF[7] + P(3,5)*SF[11] - P(12,5)*SF[15] + P(11,5)*SPP[10] - (P(10,5)*q0)*0.5f);
|
||||
nextP(2,8) = P(2,8) + P(0,8)*SF[6] + P(1,8)*SF[10] + P(3,8)*SF[8] + P(12,8)*SF[14] - P(10,8)*SPP[10] - (P(11,8)*q0)*0.5f + dt*(P(2,5) + P(0,5)*SF[6] + P(1,5)*SF[10] + P(3,5)*SF[8] + P(12,5)*SF[14] - P(10,5)*SPP[10] - (P(11,5)*q0)*0.5f);
|
||||
nextP(3,8) = P(3,8) + P(0,8)*SF[7] + P(1,8)*SF[6] + P(2,8)*SF[9] + P(10,8)*SF[15] - P(11,8)*SF[14] - (P(12,8)*q0)*0.5f + dt*(P(3,5) + P(0,5)*SF[7] + P(1,5)*SF[6] + P(2,5)*SF[9] + P(10,5)*SF[15] - P(11,5)*SF[14] - (P(12,5)*q0)*0.5f);
|
||||
nextP(4,8) = P(4,8) + P(0,8)*SF[5] + P(1,8)*SF[3] - P(3,8)*SF[4] + P(2,8)*SPP[0] + P(13,8)*SPP[3] + P(14,8)*SPP[6] - P(15,8)*SPP[9] + dt*(P(4,5) + P(0,5)*SF[5] + P(1,5)*SF[3] - P(3,5)*SF[4] + P(2,5)*SPP[0] + P(13,5)*SPP[3] + P(14,5)*SPP[6] - P(15,5)*SPP[9]);
|
||||
nextP(5,8) = P(5,8) + P(0,8)*SF[4] + P(2,8)*SF[3] + P(3,8)*SF[5] - P(1,8)*SPP[0] - P(13,8)*SPP[8] + P(14,8)*SPP[2] + P(15,8)*SPP[5] + dt*(P(5,5) + P(0,5)*SF[4] + P(2,5)*SF[3] + P(3,5)*SF[5] - P(1,5)*SPP[0] - P(13,5)*SPP[8] + P(14,5)*SPP[2] + P(15,5)*SPP[5]);
|
||||
nextP(6,8) = P(6,8) + P(1,8)*SF[4] - P(2,8)*SF[5] + P(3,8)*SF[3] + P(0,8)*SPP[0] + P(13,8)*SPP[4] - P(14,8)*SPP[7] - P(15,8)*SPP[1] + dt*(P(6,5) + P(1,5)*SF[4] - P(2,5)*SF[5] + P(3,5)*SF[3] + P(0,5)*SPP[0] + P(13,5)*SPP[4] - P(14,5)*SPP[7] - P(15,5)*SPP[1]);
|
||||
nextP(7,8) = P(7,8) + P(4,8)*dt + dt*(P(7,5) + P(4,5)*dt);
|
||||
nextP(8,8) = P(8,8) + P(5,8)*dt + dt*(P(8,5) + P(5,5)*dt);
|
||||
nextP(0,9) = P(0,9) + P(1,9)*SF[9] + P(2,9)*SF[11] + P(3,9)*SF[10] + P(10,9)*SF[14] + P(11,9)*SF[15] + P(12,9)*SPP[10] + dt*(P(0,6) + P(1,6)*SF[9] + P(2,6)*SF[11] + P(3,6)*SF[10] + P(10,6)*SF[14] + P(11,6)*SF[15] + P(12,6)*SPP[10]);
|
||||
nextP(1,9) = P(1,9) + P(0,9)*SF[8] + P(2,9)*SF[7] + P(3,9)*SF[11] - P(12,9)*SF[15] + P(11,9)*SPP[10] - (P(10,9)*q0)*0.5f + dt*(P(1,6) + P(0,6)*SF[8] + P(2,6)*SF[7] + P(3,6)*SF[11] - P(12,6)*SF[15] + P(11,6)*SPP[10] - (P(10,6)*q0)*0.5f);
|
||||
nextP(2,9) = P(2,9) + P(0,9)*SF[6] + P(1,9)*SF[10] + P(3,9)*SF[8] + P(12,9)*SF[14] - P(10,9)*SPP[10] - (P(11,9)*q0)*0.5f + dt*(P(2,6) + P(0,6)*SF[6] + P(1,6)*SF[10] + P(3,6)*SF[8] + P(12,6)*SF[14] - P(10,6)*SPP[10] - (P(11,6)*q0)*0.5f);
|
||||
nextP(3,9) = P(3,9) + P(0,9)*SF[7] + P(1,9)*SF[6] + P(2,9)*SF[9] + P(10,9)*SF[15] - P(11,9)*SF[14] - (P(12,9)*q0)*0.5f + dt*(P(3,6) + P(0,6)*SF[7] + P(1,6)*SF[6] + P(2,6)*SF[9] + P(10,6)*SF[15] - P(11,6)*SF[14] - (P(12,6)*q0)*0.5f);
|
||||
nextP(4,9) = P(4,9) + P(0,9)*SF[5] + P(1,9)*SF[3] - P(3,9)*SF[4] + P(2,9)*SPP[0] + P(13,9)*SPP[3] + P(14,9)*SPP[6] - P(15,9)*SPP[9] + dt*(P(4,6) + P(0,6)*SF[5] + P(1,6)*SF[3] - P(3,6)*SF[4] + P(2,6)*SPP[0] + P(13,6)*SPP[3] + P(14,6)*SPP[6] - P(15,6)*SPP[9]);
|
||||
nextP(5,9) = P(5,9) + P(0,9)*SF[4] + P(2,9)*SF[3] + P(3,9)*SF[5] - P(1,9)*SPP[0] - P(13,9)*SPP[8] + P(14,9)*SPP[2] + P(15,9)*SPP[5] + dt*(P(5,6) + P(0,6)*SF[4] + P(2,6)*SF[3] + P(3,6)*SF[5] - P(1,6)*SPP[0] - P(13,6)*SPP[8] + P(14,6)*SPP[2] + P(15,6)*SPP[5]);
|
||||
nextP(6,9) = P(6,9) + P(1,9)*SF[4] - P(2,9)*SF[5] + P(3,9)*SF[3] + P(0,9)*SPP[0] + P(13,9)*SPP[4] - P(14,9)*SPP[7] - P(15,9)*SPP[1] + dt*(P(6,6) + P(1,6)*SF[4] - P(2,6)*SF[5] + P(3,6)*SF[3] + P(0,6)*SPP[0] + P(13,6)*SPP[4] - P(14,6)*SPP[7] - P(15,6)*SPP[1]);
|
||||
nextP(7,9) = P(7,9) + P(4,9)*dt + dt*(P(7,6) + P(4,6)*dt);
|
||||
nextP(8,9) = P(8,9) + P(5,9)*dt + dt*(P(8,6) + P(5,6)*dt);
|
||||
nextP(9,9) = P(9,9) + P(6,9)*dt + dt*(P(9,6) + P(6,6)*dt);
|
||||
nextP(0,10) = P(0,10) + P(1,10)*SF[9] + P(2,10)*SF[11] + P(3,10)*SF[10] + P(10,10)*SF[14] + P(11,10)*SF[15] + P(12,10)*SPP[10];
|
||||
nextP(1,10) = P(1,10) + P(0,10)*SF[8] + P(2,10)*SF[7] + P(3,10)*SF[11] - P(12,10)*SF[15] + P(11,10)*SPP[10] - (P(10,10)*q0)*0.5f;
|
||||
nextP(2,10) = P(2,10) + P(0,10)*SF[6] + P(1,10)*SF[10] + P(3,10)*SF[8] + P(12,10)*SF[14] - P(10,10)*SPP[10] - (P(11,10)*q0)*0.5f;
|
||||
nextP(3,10) = P(3,10) + P(0,10)*SF[7] + P(1,10)*SF[6] + P(2,10)*SF[9] + P(10,10)*SF[15] - P(11,10)*SF[14] - (P(12,10)*q0)*0.5f;
|
||||
nextP(4,10) = P(4,10) + P(0,10)*SF[5] + P(1,10)*SF[3] - P(3,10)*SF[4] + P(2,10)*SPP[0] + P(13,10)*SPP[3] + P(14,10)*SPP[6] - P(15,10)*SPP[9];
|
||||
nextP(5,10) = P(5,10) + P(0,10)*SF[4] + P(2,10)*SF[3] + P(3,10)*SF[5] - P(1,10)*SPP[0] - P(13,10)*SPP[8] + P(14,10)*SPP[2] + P(15,10)*SPP[5];
|
||||
nextP(6,10) = P(6,10) + P(1,10)*SF[4] - P(2,10)*SF[5] + P(3,10)*SF[3] + P(0,10)*SPP[0] + P(13,10)*SPP[4] - P(14,10)*SPP[7] - P(15,10)*SPP[1];
|
||||
nextP(7,10) = P(7,10) + P(4,10)*dt;
|
||||
nextP(8,10) = P(8,10) + P(5,10)*dt;
|
||||
nextP(9,10) = P(9,10) + P(6,10)*dt;
|
||||
nextP(0,0) = PS0*PS1 - PS11*PS23 - PS12*PS26 - PS13*PS29 + PS14*PS6 + PS17*PS7 + PS2*PS3 + PS20*PS9 + PS33 + PS4*PS5;
|
||||
nextP(0,1) = -PS1*PS36 + PS11*PS33 - PS12*PS29 + PS13*PS26 - PS14*PS34 + PS17*PS9 - PS20*PS7 + PS23 + PS3*PS35 - PS35*PS5;
|
||||
nextP(1,1) = PS1*PS42 + PS11*PS80 - PS12*PS89 + PS13*PS82 + PS2*PS5 + PS3*PS4 - PS34*PS85 - PS7*PS87 + PS77*PS9 + PS92;
|
||||
nextP(0,2) = -PS1*PS37 + PS11*PS29 + PS12*PS33 - PS13*PS23 - PS14*PS9 - PS17*PS34 + PS20*PS6 + PS26 - PS3*PS38 + PS37*PS5;
|
||||
nextP(1,2) = PS1*PS40 + PS11*PS89 + PS12*PS80 - PS13*PS92 - PS3*PS40 - PS34*PS77 - PS39*PS5 + PS6*PS87 + PS82 - PS85*PS9;
|
||||
nextP(2,2) = PS0*PS5 + PS1*PS4 + PS103*PS6 + PS104*PS11 + PS106*PS12 - PS108*PS34 - PS109*PS9 - PS111*PS13 + PS113 + PS3*PS42;
|
||||
nextP(0,3) = PS1*PS39 - PS11*PS26 + PS12*PS23 + PS13*PS33 + PS14*PS7 - PS17*PS6 - PS20*PS34 + PS29 - PS3*PS39 - PS40*PS5;
|
||||
nextP(1,3) = -PS1*PS38 - PS11*PS82 + PS12*PS92 + PS13*PS80 - PS3*PS37 - PS34*PS87 + PS38*PS5 - PS6*PS77 + PS7*PS85 + PS89;
|
||||
nextP(2,3) = -PS1*PS35 - PS103*PS34 + PS104 + PS106*PS13 - PS108*PS6 + PS109*PS7 - PS11*PS113 + PS111*PS12 + PS3*PS36 - PS36*PS5;
|
||||
nextP(3,3) = PS0*PS3 + PS1*PS2 - PS11*PS128 + PS12*PS124 + PS123*PS7 + PS125*PS13 - PS126*PS34 - PS127*PS6 + PS129 + PS42*PS5;
|
||||
nextP(0,4) = PS23*PS62 + PS26*PS60 - PS44*PS45 - PS46*PS48 - PS52*PS53 + PS54*PS56 + PS57*PS58 + PS63;
|
||||
nextP(1,4) = -PS44*PS93 - PS46*PS95 + PS54*PS97 + PS60*PS82 + PS62*PS92 + PS72*PS80 - PS74*PS89 + PS98;
|
||||
nextP(2,4) = -PS104*PS74 + PS106*PS72 + PS111*PS62 + PS113*PS60 - PS114*PS44 - PS116*PS46 + PS118*PS54 + PS119;
|
||||
nextP(3,4) = PS124*PS62 + PS125*PS72 + PS128*PS60 - PS129*PS74 - PS130*PS44 - PS132*PS46 + PS134*PS54 + PS135;
|
||||
nextP(4,4) = -PS139*PS142 + PS140*PS146 - PS141*PS44 - PS145*PS74 + PS149*PS72 + PS152*PS60 + PS155*PS62 + PS156*ecl::powf(PS54, 2) + PS157*ecl::powf(PS46, 2) + PS158 + ecl::powf(PS44, 2)*dvxVar;
|
||||
nextP(0,5) = -PS23*PS60 + PS26*PS62 + PS48*PS68 + PS52*PS58 + PS53*PS57 - PS55*PS65 - PS66*PS67 + PS69;
|
||||
nextP(1,5) = PS100 - PS60*PS92 + PS62*PS82 - PS65*PS96 - PS66*PS99 + PS68*PS95 + PS72*PS89 + PS74*PS80;
|
||||
nextP(2,5) = PS104*PS72 + PS106*PS74 - PS111*PS60 + PS113*PS62 + PS116*PS68 - PS117*PS65 - PS120*PS66 + PS121;
|
||||
nextP(3,5) = -PS124*PS60 + PS125*PS74 + PS128*PS62 + PS129*PS72 + PS132*PS68 - PS133*PS65 - PS136*PS66 + PS137;
|
||||
nextP(4,5) = -PS140*PS161 + PS142*PS160 + PS145*PS72 - PS146*PS65 + PS149*PS74 + PS152*PS62 - PS155*PS60 - PS157*PS46*PS68 - PS159*PS66 + PS162*PS163 + PS164;
|
||||
nextP(5,5) = PS157*ecl::powf(PS68, 2) + PS160*PS173 - PS162*PS170 - PS169*PS65 - PS172*PS60 + PS175*PS72 + PS177*PS74 + PS179*PS62 + PS180*ecl::powf(PS66, 2) + PS181 + ecl::powf(PS65, 2)*dvyVar;
|
||||
nextP(0,6) = PS23*PS74 - PS26*PS72 - PS47*PS70 + PS53*PS61 - PS56*PS71 + PS58*PS59 + PS67*PS73 + PS75;
|
||||
nextP(1,6) = PS101 + PS60*PS80 + PS62*PS89 - PS70*PS94 - PS71*PS97 - PS72*PS82 + PS73*PS99 + PS74*PS92;
|
||||
nextP(2,6) = PS104*PS62 + PS106*PS60 + PS111*PS74 - PS113*PS72 - PS115*PS70 - PS118*PS71 + PS120*PS73 + PS122;
|
||||
nextP(3,6) = PS124*PS74 + PS125*PS60 - PS128*PS72 + PS129*PS62 - PS131*PS70 - PS134*PS71 + PS136*PS73 + PS138;
|
||||
nextP(4,6) = PS139*PS167 - PS142*PS70 + PS145*PS62 - PS146*PS165 + PS149*PS60 - PS152*PS72 + PS155*PS74 - PS156*PS54*PS71 + PS159*PS73 - PS163*PS166 + PS168;
|
||||
nextP(5,6) = -PS160*PS167 + PS161*PS165 - PS165*PS169 + PS166*PS170 + PS172*PS74 - PS173*PS70 + PS175*PS62 + PS177*PS60 - PS179*PS72 - PS180*PS66*PS73 + PS182;
|
||||
nextP(6,6) = PS156*ecl::powf(PS71, 2) - PS165*PS184 + PS166*PS185 + PS180*ecl::powf(PS73, 2) - PS183*PS70 + PS186 + PS60*(P(0,0)*PS60 + P(0,13)*PS166 - P(0,14)*PS165 - P(0,15)*PS70 + P(0,3)*PS62 + P(0,6) - PS151 + PS171) + PS62*(P(0,3)*PS60 + P(3,13)*PS166 - P(3,14)*PS165 - P(3,15)*PS70 + P(3,3)*PS62 + P(3,6) + PS154 - PS178) + ecl::powf(PS70, 2)*dvzVar - PS72*(P(1,2)*PS74 + P(2,13)*PS166 - P(2,14)*PS165 - P(2,15)*PS70 - P(2,2)*PS72 + P(2,6) + PS147 + PS174) + PS74*(P(1,1)*PS74 + P(1,13)*PS166 - P(1,14)*PS165 - P(1,15)*PS70 - P(1,2)*PS72 + P(1,6) + PS143 + PS176);
|
||||
nextP(0,7) = P(0,7) - P(1,7)*PS11 - P(2,7)*PS12 - P(3,7)*PS13 + P(7,10)*PS6 + P(7,11)*PS7 + P(7,12)*PS9 + PS63*dt;
|
||||
nextP(1,7) = P(0,7)*PS11 + P(1,7) + P(2,7)*PS13 - P(3,7)*PS12 - P(7,10)*PS34 + P(7,11)*PS9 - P(7,12)*PS7 + PS98*dt;
|
||||
nextP(2,7) = P(0,7)*PS12 - P(1,7)*PS13 + P(2,7) + P(3,7)*PS11 - P(7,10)*PS9 - P(7,11)*PS34 + P(7,12)*PS6 + PS119*dt;
|
||||
nextP(3,7) = P(0,7)*PS13 + P(1,7)*PS12 - P(2,7)*PS11 + P(3,7) + P(7,10)*PS7 - P(7,11)*PS6 - P(7,12)*PS34 + PS135*dt;
|
||||
nextP(4,7) = P(0,7)*PS72 + P(1,7)*PS62 + P(2,7)*PS60 - P(3,7)*PS74 + P(4,7) - P(7,13)*PS44 + P(7,14)*PS140 - P(7,15)*PS139 + PS158*dt;
|
||||
nextP(5,7) = P(0,7)*PS74 - P(1,7)*PS60 + P(2,7)*PS62 + P(3,7)*PS72 + P(5,7) - P(7,13)*PS162 - P(7,14)*PS65 + P(7,15)*PS160 + dt*(P(0,4)*PS74 - P(1,4)*PS60 + P(2,4)*PS62 + P(3,4)*PS72 - P(4,13)*PS162 - P(4,14)*PS65 + P(4,15)*PS160 + P(4,5));
|
||||
nextP(6,7) = P(0,7)*PS60 + P(1,7)*PS74 - P(2,7)*PS72 + P(3,7)*PS62 + P(6,7) + P(7,13)*PS166 - P(7,14)*PS165 - P(7,15)*PS70 + dt*(P(0,4)*PS60 + P(1,4)*PS74 - P(2,4)*PS72 + P(3,4)*PS62 + P(4,13)*PS166 - P(4,14)*PS165 - P(4,15)*PS70 + P(4,6));
|
||||
nextP(7,7) = P(4,7)*dt + P(7,7) + dt*(P(4,4)*dt + P(4,7));
|
||||
nextP(0,8) = P(0,8) - P(1,8)*PS11 - P(2,8)*PS12 - P(3,8)*PS13 + P(8,10)*PS6 + P(8,11)*PS7 + P(8,12)*PS9 + PS69*dt;
|
||||
nextP(1,8) = P(0,8)*PS11 + P(1,8) + P(2,8)*PS13 - P(3,8)*PS12 - P(8,10)*PS34 + P(8,11)*PS9 - P(8,12)*PS7 + PS100*dt;
|
||||
nextP(2,8) = P(0,8)*PS12 - P(1,8)*PS13 + P(2,8) + P(3,8)*PS11 - P(8,10)*PS9 - P(8,11)*PS34 + P(8,12)*PS6 + PS121*dt;
|
||||
nextP(3,8) = P(0,8)*PS13 + P(1,8)*PS12 - P(2,8)*PS11 + P(3,8) + P(8,10)*PS7 - P(8,11)*PS6 - P(8,12)*PS34 + PS137*dt;
|
||||
nextP(4,8) = P(0,8)*PS72 + P(1,8)*PS62 + P(2,8)*PS60 - P(3,8)*PS74 + P(4,8) - P(8,13)*PS44 + P(8,14)*PS140 - P(8,15)*PS139 + PS164*dt;
|
||||
nextP(5,8) = P(0,8)*PS74 - P(1,8)*PS60 + P(2,8)*PS62 + P(3,8)*PS72 + P(5,8) - P(8,13)*PS162 - P(8,14)*PS65 + P(8,15)*PS160 + PS181*dt;
|
||||
nextP(6,8) = P(0,8)*PS60 + P(1,8)*PS74 - P(2,8)*PS72 + P(3,8)*PS62 + P(6,8) + P(8,13)*PS166 - P(8,14)*PS165 - P(8,15)*PS70 + dt*(P(0,5)*PS60 + P(1,5)*PS74 - P(2,5)*PS72 + P(3,5)*PS62 + P(5,13)*PS166 - P(5,14)*PS165 - P(5,15)*PS70 + P(5,6));
|
||||
nextP(7,8) = P(4,8)*dt + P(7,8) + dt*(P(4,5)*dt + P(5,7));
|
||||
nextP(8,8) = P(5,8)*dt + P(8,8) + dt*(P(5,5)*dt + P(5,8));
|
||||
nextP(0,9) = P(0,9) - P(1,9)*PS11 - P(2,9)*PS12 - P(3,9)*PS13 + P(9,10)*PS6 + P(9,11)*PS7 + P(9,12)*PS9 + PS75*dt;
|
||||
nextP(1,9) = P(0,9)*PS11 + P(1,9) + P(2,9)*PS13 - P(3,9)*PS12 - P(9,10)*PS34 + P(9,11)*PS9 - P(9,12)*PS7 + PS101*dt;
|
||||
nextP(2,9) = P(0,9)*PS12 - P(1,9)*PS13 + P(2,9) + P(3,9)*PS11 - P(9,10)*PS9 - P(9,11)*PS34 + P(9,12)*PS6 + PS122*dt;
|
||||
nextP(3,9) = P(0,9)*PS13 + P(1,9)*PS12 - P(2,9)*PS11 + P(3,9) + P(9,10)*PS7 - P(9,11)*PS6 - P(9,12)*PS34 + PS138*dt;
|
||||
nextP(4,9) = P(0,9)*PS72 + P(1,9)*PS62 + P(2,9)*PS60 - P(3,9)*PS74 + P(4,9) - P(9,13)*PS44 + P(9,14)*PS140 - P(9,15)*PS139 + PS168*dt;
|
||||
nextP(5,9) = P(0,9)*PS74 - P(1,9)*PS60 + P(2,9)*PS62 + P(3,9)*PS72 + P(5,9) - P(9,13)*PS162 - P(9,14)*PS65 + P(9,15)*PS160 + PS182*dt;
|
||||
nextP(6,9) = P(0,9)*PS60 + P(1,9)*PS74 - P(2,9)*PS72 + P(3,9)*PS62 + P(6,9) + P(9,13)*PS166 - P(9,14)*PS165 - P(9,15)*PS70 + PS186*dt;
|
||||
nextP(7,9) = P(4,9)*dt + P(7,9) + dt*(P(4,6)*dt + P(6,7));
|
||||
nextP(8,9) = P(5,9)*dt + P(8,9) + dt*(P(5,6)*dt + P(6,8));
|
||||
nextP(9,9) = P(6,9)*dt + P(9,9) + dt*(P(6,6)*dt + P(6,9));
|
||||
nextP(0,10) = PS14;
|
||||
nextP(1,10) = PS85;
|
||||
nextP(2,10) = PS109;
|
||||
nextP(3,10) = PS123;
|
||||
nextP(4,10) = P(0,10)*PS72 + P(1,10)*PS62 - P(10,13)*PS44 + P(10,14)*PS140 - P(10,15)*PS139 + P(2,10)*PS60 - P(3,10)*PS74 + P(4,10);
|
||||
nextP(5,10) = P(0,10)*PS74 - P(1,10)*PS60 - P(10,13)*PS162 - P(10,14)*PS65 + P(10,15)*PS160 + P(2,10)*PS62 + P(3,10)*PS72 + P(5,10);
|
||||
nextP(6,10) = P(0,10)*PS60 + P(1,10)*PS74 + P(10,13)*PS166 - P(10,14)*PS165 - P(10,15)*PS70 - P(2,10)*PS72 + P(3,10)*PS62 + P(6,10);
|
||||
nextP(7,10) = P(4,10)*dt + P(7,10);
|
||||
nextP(8,10) = P(5,10)*dt + P(8,10);
|
||||
nextP(9,10) = P(6,10)*dt + P(9,10);
|
||||
nextP(10,10) = P(10,10);
|
||||
nextP(0,11) = P(0,11) + P(1,11)*SF[9] + P(2,11)*SF[11] + P(3,11)*SF[10] + P(10,11)*SF[14] + P(11,11)*SF[15] + P(12,11)*SPP[10];
|
||||
nextP(1,11) = P(1,11) + P(0,11)*SF[8] + P(2,11)*SF[7] + P(3,11)*SF[11] - P(12,11)*SF[15] + P(11,11)*SPP[10] - (P(10,11)*q0)*0.5f;
|
||||
nextP(2,11) = P(2,11) + P(0,11)*SF[6] + P(1,11)*SF[10] + P(3,11)*SF[8] + P(12,11)*SF[14] - P(10,11)*SPP[10] - (P(11,11)*q0)*0.5f;
|
||||
nextP(3,11) = P(3,11) + P(0,11)*SF[7] + P(1,11)*SF[6] + P(2,11)*SF[9] + P(10,11)*SF[15] - P(11,11)*SF[14] - (P(12,11)*q0)*0.5f;
|
||||
nextP(4,11) = P(4,11) + P(0,11)*SF[5] + P(1,11)*SF[3] - P(3,11)*SF[4] + P(2,11)*SPP[0] + P(13,11)*SPP[3] + P(14,11)*SPP[6] - P(15,11)*SPP[9];
|
||||
nextP(5,11) = P(5,11) + P(0,11)*SF[4] + P(2,11)*SF[3] + P(3,11)*SF[5] - P(1,11)*SPP[0] - P(13,11)*SPP[8] + P(14,11)*SPP[2] + P(15,11)*SPP[5];
|
||||
nextP(6,11) = P(6,11) + P(1,11)*SF[4] - P(2,11)*SF[5] + P(3,11)*SF[3] + P(0,11)*SPP[0] + P(13,11)*SPP[4] - P(14,11)*SPP[7] - P(15,11)*SPP[1];
|
||||
nextP(7,11) = P(7,11) + P(4,11)*dt;
|
||||
nextP(8,11) = P(8,11) + P(5,11)*dt;
|
||||
nextP(9,11) = P(9,11) + P(6,11)*dt;
|
||||
nextP(0,11) = PS17;
|
||||
nextP(1,11) = PS77;
|
||||
nextP(2,11) = PS108;
|
||||
nextP(3,11) = PS127;
|
||||
nextP(4,11) = P(0,11)*PS72 + P(1,11)*PS62 - P(11,13)*PS44 + P(11,14)*PS140 - P(11,15)*PS139 + P(2,11)*PS60 - P(3,11)*PS74 + P(4,11);
|
||||
nextP(5,11) = P(0,11)*PS74 - P(1,11)*PS60 - P(11,13)*PS162 - P(11,14)*PS65 + P(11,15)*PS160 + P(2,11)*PS62 + P(3,11)*PS72 + P(5,11);
|
||||
nextP(6,11) = P(0,11)*PS60 + P(1,11)*PS74 + P(11,13)*PS166 - P(11,14)*PS165 - P(11,15)*PS70 - P(2,11)*PS72 + P(3,11)*PS62 + P(6,11);
|
||||
nextP(7,11) = P(4,11)*dt + P(7,11);
|
||||
nextP(8,11) = P(5,11)*dt + P(8,11);
|
||||
nextP(9,11) = P(6,11)*dt + P(9,11);
|
||||
nextP(10,11) = P(10,11);
|
||||
nextP(11,11) = P(11,11);
|
||||
nextP(0,12) = P(0,12) + P(1,12)*SF[9] + P(2,12)*SF[11] + P(3,12)*SF[10] + P(10,12)*SF[14] + P(11,12)*SF[15] + P(12,12)*SPP[10];
|
||||
nextP(1,12) = P(1,12) + P(0,12)*SF[8] + P(2,12)*SF[7] + P(3,12)*SF[11] - P(12,12)*SF[15] + P(11,12)*SPP[10] - (P(10,12)*q0)*0.5f;
|
||||
nextP(2,12) = P(2,12) + P(0,12)*SF[6] + P(1,12)*SF[10] + P(3,12)*SF[8] + P(12,12)*SF[14] - P(10,12)*SPP[10] - (P(11,12)*q0)*0.5f;
|
||||
nextP(3,12) = P(3,12) + P(0,12)*SF[7] + P(1,12)*SF[6] + P(2,12)*SF[9] + P(10,12)*SF[15] - P(11,12)*SF[14] - (P(12,12)*q0)*0.5f;
|
||||
nextP(4,12) = P(4,12) + P(0,12)*SF[5] + P(1,12)*SF[3] - P(3,12)*SF[4] + P(2,12)*SPP[0] + P(13,12)*SPP[3] + P(14,12)*SPP[6] - P(15,12)*SPP[9];
|
||||
nextP(5,12) = P(5,12) + P(0,12)*SF[4] + P(2,12)*SF[3] + P(3,12)*SF[5] - P(1,12)*SPP[0] - P(13,12)*SPP[8] + P(14,12)*SPP[2] + P(15,12)*SPP[5];
|
||||
nextP(6,12) = P(6,12) + P(1,12)*SF[4] - P(2,12)*SF[5] + P(3,12)*SF[3] + P(0,12)*SPP[0] + P(13,12)*SPP[4] - P(14,12)*SPP[7] - P(15,12)*SPP[1];
|
||||
nextP(7,12) = P(7,12) + P(4,12)*dt;
|
||||
nextP(8,12) = P(8,12) + P(5,12)*dt;
|
||||
nextP(9,12) = P(9,12) + P(6,12)*dt;
|
||||
nextP(0,12) = PS20;
|
||||
nextP(1,12) = PS87;
|
||||
nextP(2,12) = PS103;
|
||||
nextP(3,12) = PS126;
|
||||
nextP(4,12) = P(0,12)*PS72 + P(1,12)*PS62 - P(12,13)*PS44 + P(12,14)*PS140 - P(12,15)*PS139 + P(2,12)*PS60 - P(3,12)*PS74 + P(4,12);
|
||||
nextP(5,12) = P(0,12)*PS74 - P(1,12)*PS60 - P(12,13)*PS162 - P(12,14)*PS65 + P(12,15)*PS160 + P(2,12)*PS62 + P(3,12)*PS72 + P(5,12);
|
||||
nextP(6,12) = P(0,12)*PS60 + P(1,12)*PS74 + P(12,13)*PS166 - P(12,14)*PS165 - P(12,15)*PS70 - P(2,12)*PS72 + P(3,12)*PS62 + P(6,12);
|
||||
nextP(7,12) = P(4,12)*dt + P(7,12);
|
||||
nextP(8,12) = P(5,12)*dt + P(8,12);
|
||||
nextP(9,12) = P(6,12)*dt + P(9,12);
|
||||
nextP(10,12) = P(10,12);
|
||||
nextP(11,12) = P(11,12);
|
||||
nextP(12,12) = P(12,12);
|
||||
@@ -429,58 +563,106 @@ void Ekf::predictCovariance()
|
||||
nextP(i,i) = kahanSummation(nextP(i,i), process_noise(i), _delta_angle_bias_var_accum(index));
|
||||
}
|
||||
|
||||
for (unsigned i = 13; i <= 15; i++) {
|
||||
const unsigned index = i - 13;
|
||||
if (!_accel_bias_inhibit[0]) {
|
||||
// calculate variances and upper diagonal covariances for IMU X axis delta velocity bias state
|
||||
nextP(0,13) = PS45;
|
||||
nextP(1,13) = PS93;
|
||||
nextP(2,13) = PS114;
|
||||
nextP(3,13) = PS130;
|
||||
nextP(4,13) = PS141;
|
||||
nextP(5,13) = PS170;
|
||||
nextP(6,13) = PS185;
|
||||
nextP(7,13) = P(4,13)*dt + P(7,13);
|
||||
nextP(8,13) = P(5,13)*dt + P(8,13);
|
||||
nextP(9,13) = P(6,13)*dt + P(9,13);
|
||||
nextP(10,13) = P(10,13);
|
||||
nextP(11,13) = P(11,13);
|
||||
nextP(12,13) = P(12,13);
|
||||
nextP(13,13) = P(13,13);
|
||||
|
||||
if (!_accel_bias_inhibit[index]) {
|
||||
// calculate variances and upper diagonal covariances for IMU delta velocity bias states
|
||||
nextP(0,i) = P(0,i) + P(1,i)*SF[9] + P(2,i)*SF[11] + P(3,i)*SF[10] + P(10,i)*SF[14] + P(11,i)*SF[15] + P(12,i)*SPP[10];
|
||||
nextP(1,i) = P(1,i) + P(0,i)*SF[8] + P(2,i)*SF[7] + P(3,i)*SF[11] - P(12,i)*SF[15] + P(11,i)*SPP[10] - (P(10,i)*q0)*0.5f;
|
||||
nextP(2,i) = P(2,i) + P(0,i)*SF[6] + P(1,i)*SF[10] + P(3,i)*SF[8] + P(12,i)*SF[14] - P(10,i)*SPP[10] - (P(11,i)*q0)*0.5f;
|
||||
nextP(3,i) = P(3,i) + P(0,i)*SF[7] + P(1,i)*SF[6] + P(2,i)*SF[9] + P(10,i)*SF[15] - P(11,i)*SF[14] - (P(12,i)*q0)*0.5f;
|
||||
nextP(4,i) = P(4,i) + P(0,i)*SF[5] + P(1,i)*SF[3] - P(3,i)*SF[4] + P(2,i)*SPP[0] + P(13,i)*SPP[3] + P(14,i)*SPP[6] - P(15,i)*SPP[9];
|
||||
nextP(5,i) = P(5,i) + P(0,i)*SF[4] + P(2,i)*SF[3] + P(3,i)*SF[5] - P(1,i)*SPP[0] - P(13,i)*SPP[8] + P(14,i)*SPP[2] + P(15,i)*SPP[5];
|
||||
nextP(6,i) = P(6,i) + P(1,i)*SF[4] - P(2,i)*SF[5] + P(3,i)*SF[3] + P(0,i)*SPP[0] + P(13,i)*SPP[4] - P(14,i)*SPP[7] - P(15,i)*SPP[1];
|
||||
nextP(7,i) = P(7,i) + P(4,i)*dt;
|
||||
nextP(8,i) = P(8,i) + P(5,i)*dt;
|
||||
nextP(9,i) = P(9,i) + P(6,i)*dt;
|
||||
nextP(10,i) = P(10,i);
|
||||
nextP(11,i) = P(11,i);
|
||||
nextP(12,i) = P(12,i);
|
||||
nextP(13,i) = P(13,i);
|
||||
// add process noise that is not from the IMU
|
||||
// process noise contribution for delta velocity states can be very small compared to
|
||||
// the variances, therefore use algorithm to minimise numerical error
|
||||
nextP(13,13) = kahanSummation(nextP(13,13), process_noise(13), _delta_vel_bias_var_accum(0));
|
||||
|
||||
if (i > 13) {
|
||||
nextP(14,i) = P(14,i);
|
||||
}
|
||||
} else {
|
||||
nextP.uncorrelateCovarianceSetVariance<1>(13, 0.f);
|
||||
_delta_vel_bias_var_accum(0) = 0.f;
|
||||
|
||||
if (i > 14) {
|
||||
nextP(15,i) = P(15,i);
|
||||
}
|
||||
}
|
||||
|
||||
// add process noise that is not from the IMU
|
||||
// process noise contributiton for delta velocity states can be very small compared to
|
||||
// the variances, therefore use algorithm to minimise numerical error
|
||||
nextP(i,i) = kahanSummation(nextP(i,i), process_noise(i), _delta_vel_bias_var_accum(index));
|
||||
if (!_accel_bias_inhibit[1]) {
|
||||
// calculate variances and upper diagonal covariances for IMU Y axis delta velocity bias state
|
||||
nextP(0,14) = PS55;
|
||||
nextP(1,14) = PS96;
|
||||
nextP(2,14) = PS117;
|
||||
nextP(3,14) = PS133;
|
||||
nextP(4,14) = PS146;
|
||||
nextP(5,14) = PS169;
|
||||
nextP(6,14) = PS184;
|
||||
nextP(7,14) = P(4,14)*dt + P(7,14);
|
||||
nextP(8,14) = P(5,14)*dt + P(8,14);
|
||||
nextP(9,14) = P(6,14)*dt + P(9,14);
|
||||
nextP(10,14) = P(10,14);
|
||||
nextP(11,14) = P(11,14);
|
||||
nextP(12,14) = P(12,14);
|
||||
nextP(13,14) = P(13,14);
|
||||
nextP(14,14) = P(14,14);
|
||||
|
||||
// add process noise that is not from the IMU
|
||||
// process noise contribution for delta velocity states can be very small compared to
|
||||
// the variances, therefore use algorithm to minimise numerical error
|
||||
nextP(14,14) = kahanSummation(nextP(14,14), process_noise(14), _delta_vel_bias_var_accum(1));
|
||||
|
||||
} else {
|
||||
nextP.uncorrelateCovarianceSetVariance<1>(14, 0.f);
|
||||
_delta_vel_bias_var_accum(1) = 0.f;
|
||||
|
||||
}
|
||||
|
||||
if (!_accel_bias_inhibit[2]) {
|
||||
// calculate variances and upper diagonal covariances for IMU Z axis delta velocity bias state
|
||||
nextP(0,15) = PS47;
|
||||
nextP(1,15) = PS94;
|
||||
nextP(2,15) = PS115;
|
||||
nextP(3,15) = PS131;
|
||||
nextP(4,15) = PS142;
|
||||
nextP(5,15) = PS173;
|
||||
nextP(6,15) = PS183;
|
||||
nextP(7,15) = P(4,15)*dt + P(7,15);
|
||||
nextP(8,15) = P(5,15)*dt + P(8,15);
|
||||
nextP(9,15) = P(6,15)*dt + P(9,15);
|
||||
nextP(10,15) = P(10,15);
|
||||
nextP(11,15) = P(11,15);
|
||||
nextP(12,15) = P(12,15);
|
||||
nextP(13,15) = P(13,15);
|
||||
nextP(14,15) = P(14,15);
|
||||
nextP(15,15) = P(15,15);
|
||||
|
||||
// add process noise that is not from the IMU
|
||||
// process noise contribution for delta velocity states can be very small compared to
|
||||
// the variances, therefore use algorithm to minimise numerical error
|
||||
nextP(15,15) = kahanSummation(nextP(15,15), process_noise(15), _delta_vel_bias_var_accum(2));
|
||||
|
||||
} else {
|
||||
nextP.uncorrelateCovarianceSetVariance<1>(15, 0.f);
|
||||
_delta_vel_bias_var_accum(2) = 0.f;
|
||||
|
||||
} else {
|
||||
nextP.uncorrelateCovarianceSetVariance<1>(i, 0.f);
|
||||
_delta_vel_bias_var_accum(index) = 0.f;
|
||||
}
|
||||
}
|
||||
|
||||
// Don't do covariance prediction on magnetic field states unless we are using 3-axis fusion
|
||||
if (_control_status.flags.mag_3D) {
|
||||
// calculate variances and upper diagonal covariances for earth and body magnetic field states
|
||||
nextP(0,16) = P(0,16) + P(1,16)*SF[9] + P(2,16)*SF[11] + P(3,16)*SF[10] + P(10,16)*SF[14] + P(11,16)*SF[15] + P(12,16)*SPP[10];
|
||||
nextP(1,16) = P(1,16) + P(0,16)*SF[8] + P(2,16)*SF[7] + P(3,16)*SF[11] - P(12,16)*SF[15] + P(11,16)*SPP[10] - (P(10,16)*q0)*0.5f;
|
||||
nextP(2,16) = P(2,16) + P(0,16)*SF[6] + P(1,16)*SF[10] + P(3,16)*SF[8] + P(12,16)*SF[14] - P(10,16)*SPP[10] - (P(11,16)*q0)*0.5f;
|
||||
nextP(3,16) = P(3,16) + P(0,16)*SF[7] + P(1,16)*SF[6] + P(2,16)*SF[9] + P(10,16)*SF[15] - P(11,16)*SF[14] - (P(12,16)*q0)*0.5f;
|
||||
nextP(4,16) = P(4,16) + P(0,16)*SF[5] + P(1,16)*SF[3] - P(3,16)*SF[4] + P(2,16)*SPP[0] + P(13,16)*SPP[3] + P(14,16)*SPP[6] - P(15,16)*SPP[9];
|
||||
nextP(5,16) = P(5,16) + P(0,16)*SF[4] + P(2,16)*SF[3] + P(3,16)*SF[5] - P(1,16)*SPP[0] - P(13,16)*SPP[8] + P(14,16)*SPP[2] + P(15,16)*SPP[5];
|
||||
nextP(6,16) = P(6,16) + P(1,16)*SF[4] - P(2,16)*SF[5] + P(3,16)*SF[3] + P(0,16)*SPP[0] + P(13,16)*SPP[4] - P(14,16)*SPP[7] - P(15,16)*SPP[1];
|
||||
nextP(7,16) = P(7,16) + P(4,16)*dt;
|
||||
nextP(8,16) = P(8,16) + P(5,16)*dt;
|
||||
nextP(9,16) = P(9,16) + P(6,16)*dt;
|
||||
nextP(0,16) = P(0,16) - P(1,16)*PS11 + P(10,16)*PS6 + P(11,16)*PS7 + P(12,16)*PS9 - P(2,16)*PS12 - P(3,16)*PS13;
|
||||
nextP(1,16) = P(0,16)*PS11 + P(1,16) - P(10,16)*PS34 + P(11,16)*PS9 - P(12,16)*PS7 + P(2,16)*PS13 - P(3,16)*PS12;
|
||||
nextP(2,16) = P(0,16)*PS12 - P(1,16)*PS13 - P(10,16)*PS9 - P(11,16)*PS34 + P(12,16)*PS6 + P(2,16) + P(3,16)*PS11;
|
||||
nextP(3,16) = P(0,16)*PS13 + P(1,16)*PS12 + P(10,16)*PS7 - P(11,16)*PS6 - P(12,16)*PS34 - P(2,16)*PS11 + P(3,16);
|
||||
nextP(4,16) = P(0,16)*PS72 + P(1,16)*PS62 - P(13,16)*PS44 + P(14,16)*PS140 - P(15,16)*PS139 + P(2,16)*PS60 - P(3,16)*PS74 + P(4,16);
|
||||
nextP(5,16) = P(0,16)*PS74 - P(1,16)*PS60 - P(13,16)*PS162 - P(14,16)*PS65 + P(15,16)*PS160 + P(2,16)*PS62 + P(3,16)*PS72 + P(5,16);
|
||||
nextP(6,16) = P(0,16)*PS60 + P(1,16)*PS74 + P(13,16)*PS166 - P(14,16)*PS165 - P(15,16)*PS70 - P(2,16)*PS72 + P(3,16)*PS62 + P(6,16);
|
||||
nextP(7,16) = P(4,16)*dt + P(7,16);
|
||||
nextP(8,16) = P(5,16)*dt + P(8,16);
|
||||
nextP(9,16) = P(6,16)*dt + P(9,16);
|
||||
nextP(10,16) = P(10,16);
|
||||
nextP(11,16) = P(11,16);
|
||||
nextP(12,16) = P(12,16);
|
||||
@@ -488,16 +670,16 @@ void Ekf::predictCovariance()
|
||||
nextP(14,16) = P(14,16);
|
||||
nextP(15,16) = P(15,16);
|
||||
nextP(16,16) = P(16,16);
|
||||
nextP(0,17) = P(0,17) + P(1,17)*SF[9] + P(2,17)*SF[11] + P(3,17)*SF[10] + P(10,17)*SF[14] + P(11,17)*SF[15] + P(12,17)*SPP[10];
|
||||
nextP(1,17) = P(1,17) + P(0,17)*SF[8] + P(2,17)*SF[7] + P(3,17)*SF[11] - P(12,17)*SF[15] + P(11,17)*SPP[10] - (P(10,17)*q0)*0.5f;
|
||||
nextP(2,17) = P(2,17) + P(0,17)*SF[6] + P(1,17)*SF[10] + P(3,17)*SF[8] + P(12,17)*SF[14] - P(10,17)*SPP[10] - (P(11,17)*q0)*0.5f;
|
||||
nextP(3,17) = P(3,17) + P(0,17)*SF[7] + P(1,17)*SF[6] + P(2,17)*SF[9] + P(10,17)*SF[15] - P(11,17)*SF[14] - (P(12,17)*q0)*0.5f;
|
||||
nextP(4,17) = P(4,17) + P(0,17)*SF[5] + P(1,17)*SF[3] - P(3,17)*SF[4] + P(2,17)*SPP[0] + P(13,17)*SPP[3] + P(14,17)*SPP[6] - P(15,17)*SPP[9];
|
||||
nextP(5,17) = P(5,17) + P(0,17)*SF[4] + P(2,17)*SF[3] + P(3,17)*SF[5] - P(1,17)*SPP[0] - P(13,17)*SPP[8] + P(14,17)*SPP[2] + P(15,17)*SPP[5];
|
||||
nextP(6,17) = P(6,17) + P(1,17)*SF[4] - P(2,17)*SF[5] + P(3,17)*SF[3] + P(0,17)*SPP[0] + P(13,17)*SPP[4] - P(14,17)*SPP[7] - P(15,17)*SPP[1];
|
||||
nextP(7,17) = P(7,17) + P(4,17)*dt;
|
||||
nextP(8,17) = P(8,17) + P(5,17)*dt;
|
||||
nextP(9,17) = P(9,17) + P(6,17)*dt;
|
||||
nextP(0,17) = P(0,17) - P(1,17)*PS11 + P(10,17)*PS6 + P(11,17)*PS7 + P(12,17)*PS9 - P(2,17)*PS12 - P(3,17)*PS13;
|
||||
nextP(1,17) = P(0,17)*PS11 + P(1,17) - P(10,17)*PS34 + P(11,17)*PS9 - P(12,17)*PS7 + P(2,17)*PS13 - P(3,17)*PS12;
|
||||
nextP(2,17) = P(0,17)*PS12 - P(1,17)*PS13 - P(10,17)*PS9 - P(11,17)*PS34 + P(12,17)*PS6 + P(2,17) + P(3,17)*PS11;
|
||||
nextP(3,17) = P(0,17)*PS13 + P(1,17)*PS12 + P(10,17)*PS7 - P(11,17)*PS6 - P(12,17)*PS34 - P(2,17)*PS11 + P(3,17);
|
||||
nextP(4,17) = P(0,17)*PS72 + P(1,17)*PS62 - P(13,17)*PS44 + P(14,17)*PS140 - P(15,17)*PS139 + P(2,17)*PS60 - P(3,17)*PS74 + P(4,17);
|
||||
nextP(5,17) = P(0,17)*PS74 - P(1,17)*PS60 - P(13,17)*PS162 - P(14,17)*PS65 + P(15,17)*PS160 + P(2,17)*PS62 + P(3,17)*PS72 + P(5,17);
|
||||
nextP(6,17) = P(0,17)*PS60 + P(1,17)*PS74 + P(13,17)*PS166 - P(14,17)*PS165 - P(15,17)*PS70 - P(2,17)*PS72 + P(3,17)*PS62 + P(6,17);
|
||||
nextP(7,17) = P(4,17)*dt + P(7,17);
|
||||
nextP(8,17) = P(5,17)*dt + P(8,17);
|
||||
nextP(9,17) = P(6,17)*dt + P(9,17);
|
||||
nextP(10,17) = P(10,17);
|
||||
nextP(11,17) = P(11,17);
|
||||
nextP(12,17) = P(12,17);
|
||||
@@ -506,16 +688,16 @@ void Ekf::predictCovariance()
|
||||
nextP(15,17) = P(15,17);
|
||||
nextP(16,17) = P(16,17);
|
||||
nextP(17,17) = P(17,17);
|
||||
nextP(0,18) = P(0,18) + P(1,18)*SF[9] + P(2,18)*SF[11] + P(3,18)*SF[10] + P(10,18)*SF[14] + P(11,18)*SF[15] + P(12,18)*SPP[10];
|
||||
nextP(1,18) = P(1,18) + P(0,18)*SF[8] + P(2,18)*SF[7] + P(3,18)*SF[11] - P(12,18)*SF[15] + P(11,18)*SPP[10] - (P(10,18)*q0)*0.5f;
|
||||
nextP(2,18) = P(2,18) + P(0,18)*SF[6] + P(1,18)*SF[10] + P(3,18)*SF[8] + P(12,18)*SF[14] - P(10,18)*SPP[10] - (P(11,18)*q0)*0.5f;
|
||||
nextP(3,18) = P(3,18) + P(0,18)*SF[7] + P(1,18)*SF[6] + P(2,18)*SF[9] + P(10,18)*SF[15] - P(11,18)*SF[14] - (P(12,18)*q0)*0.5f;
|
||||
nextP(4,18) = P(4,18) + P(0,18)*SF[5] + P(1,18)*SF[3] - P(3,18)*SF[4] + P(2,18)*SPP[0] + P(13,18)*SPP[3] + P(14,18)*SPP[6] - P(15,18)*SPP[9];
|
||||
nextP(5,18) = P(5,18) + P(0,18)*SF[4] + P(2,18)*SF[3] + P(3,18)*SF[5] - P(1,18)*SPP[0] - P(13,18)*SPP[8] + P(14,18)*SPP[2] + P(15,18)*SPP[5];
|
||||
nextP(6,18) = P(6,18) + P(1,18)*SF[4] - P(2,18)*SF[5] + P(3,18)*SF[3] + P(0,18)*SPP[0] + P(13,18)*SPP[4] - P(14,18)*SPP[7] - P(15,18)*SPP[1];
|
||||
nextP(7,18) = P(7,18) + P(4,18)*dt;
|
||||
nextP(8,18) = P(8,18) + P(5,18)*dt;
|
||||
nextP(9,18) = P(9,18) + P(6,18)*dt;
|
||||
nextP(0,18) = P(0,18) - P(1,18)*PS11 + P(10,18)*PS6 + P(11,18)*PS7 + P(12,18)*PS9 - P(2,18)*PS12 - P(3,18)*PS13;
|
||||
nextP(1,18) = P(0,18)*PS11 + P(1,18) - P(10,18)*PS34 + P(11,18)*PS9 - P(12,18)*PS7 + P(2,18)*PS13 - P(3,18)*PS12;
|
||||
nextP(2,18) = P(0,18)*PS12 - P(1,18)*PS13 - P(10,18)*PS9 - P(11,18)*PS34 + P(12,18)*PS6 + P(2,18) + P(3,18)*PS11;
|
||||
nextP(3,18) = P(0,18)*PS13 + P(1,18)*PS12 + P(10,18)*PS7 - P(11,18)*PS6 - P(12,18)*PS34 - P(2,18)*PS11 + P(3,18);
|
||||
nextP(4,18) = P(0,18)*PS72 + P(1,18)*PS62 - P(13,18)*PS44 + P(14,18)*PS140 - P(15,18)*PS139 + P(2,18)*PS60 - P(3,18)*PS74 + P(4,18);
|
||||
nextP(5,18) = P(0,18)*PS74 - P(1,18)*PS60 - P(13,18)*PS162 - P(14,18)*PS65 + P(15,18)*PS160 + P(2,18)*PS62 + P(3,18)*PS72 + P(5,18);
|
||||
nextP(6,18) = P(0,18)*PS60 + P(1,18)*PS74 + P(13,18)*PS166 - P(14,18)*PS165 - P(15,18)*PS70 - P(2,18)*PS72 + P(3,18)*PS62 + P(6,18);
|
||||
nextP(7,18) = P(4,18)*dt + P(7,18);
|
||||
nextP(8,18) = P(5,18)*dt + P(8,18);
|
||||
nextP(9,18) = P(6,18)*dt + P(9,18);
|
||||
nextP(10,18) = P(10,18);
|
||||
nextP(11,18) = P(11,18);
|
||||
nextP(12,18) = P(12,18);
|
||||
@@ -525,16 +707,16 @@ void Ekf::predictCovariance()
|
||||
nextP(16,18) = P(16,18);
|
||||
nextP(17,18) = P(17,18);
|
||||
nextP(18,18) = P(18,18);
|
||||
nextP(0,19) = P(0,19) + P(1,19)*SF[9] + P(2,19)*SF[11] + P(3,19)*SF[10] + P(10,19)*SF[14] + P(11,19)*SF[15] + P(12,19)*SPP[10];
|
||||
nextP(1,19) = P(1,19) + P(0,19)*SF[8] + P(2,19)*SF[7] + P(3,19)*SF[11] - P(12,19)*SF[15] + P(11,19)*SPP[10] - (P(10,19)*q0)*0.5f;
|
||||
nextP(2,19) = P(2,19) + P(0,19)*SF[6] + P(1,19)*SF[10] + P(3,19)*SF[8] + P(12,19)*SF[14] - P(10,19)*SPP[10] - (P(11,19)*q0)*0.5f;
|
||||
nextP(3,19) = P(3,19) + P(0,19)*SF[7] + P(1,19)*SF[6] + P(2,19)*SF[9] + P(10,19)*SF[15] - P(11,19)*SF[14] - (P(12,19)*q0)*0.5f;
|
||||
nextP(4,19) = P(4,19) + P(0,19)*SF[5] + P(1,19)*SF[3] - P(3,19)*SF[4] + P(2,19)*SPP[0] + P(13,19)*SPP[3] + P(14,19)*SPP[6] - P(15,19)*SPP[9];
|
||||
nextP(5,19) = P(5,19) + P(0,19)*SF[4] + P(2,19)*SF[3] + P(3,19)*SF[5] - P(1,19)*SPP[0] - P(13,19)*SPP[8] + P(14,19)*SPP[2] + P(15,19)*SPP[5];
|
||||
nextP(6,19) = P(6,19) + P(1,19)*SF[4] - P(2,19)*SF[5] + P(3,19)*SF[3] + P(0,19)*SPP[0] + P(13,19)*SPP[4] - P(14,19)*SPP[7] - P(15,19)*SPP[1];
|
||||
nextP(7,19) = P(7,19) + P(4,19)*dt;
|
||||
nextP(8,19) = P(8,19) + P(5,19)*dt;
|
||||
nextP(9,19) = P(9,19) + P(6,19)*dt;
|
||||
nextP(0,19) = P(0,19) - P(1,19)*PS11 + P(10,19)*PS6 + P(11,19)*PS7 + P(12,19)*PS9 - P(2,19)*PS12 - P(3,19)*PS13;
|
||||
nextP(1,19) = P(0,19)*PS11 + P(1,19) - P(10,19)*PS34 + P(11,19)*PS9 - P(12,19)*PS7 + P(2,19)*PS13 - P(3,19)*PS12;
|
||||
nextP(2,19) = P(0,19)*PS12 - P(1,19)*PS13 - P(10,19)*PS9 - P(11,19)*PS34 + P(12,19)*PS6 + P(2,19) + P(3,19)*PS11;
|
||||
nextP(3,19) = P(0,19)*PS13 + P(1,19)*PS12 + P(10,19)*PS7 - P(11,19)*PS6 - P(12,19)*PS34 - P(2,19)*PS11 + P(3,19);
|
||||
nextP(4,19) = P(0,19)*PS72 + P(1,19)*PS62 - P(13,19)*PS44 + P(14,19)*PS140 - P(15,19)*PS139 + P(2,19)*PS60 - P(3,19)*PS74 + P(4,19);
|
||||
nextP(5,19) = P(0,19)*PS74 - P(1,19)*PS60 - P(13,19)*PS162 - P(14,19)*PS65 + P(15,19)*PS160 + P(2,19)*PS62 + P(3,19)*PS72 + P(5,19);
|
||||
nextP(6,19) = P(0,19)*PS60 + P(1,19)*PS74 + P(13,19)*PS166 - P(14,19)*PS165 - P(15,19)*PS70 - P(2,19)*PS72 + P(3,19)*PS62 + P(6,19);
|
||||
nextP(7,19) = P(4,19)*dt + P(7,19);
|
||||
nextP(8,19) = P(5,19)*dt + P(8,19);
|
||||
nextP(9,19) = P(6,19)*dt + P(9,19);
|
||||
nextP(10,19) = P(10,19);
|
||||
nextP(11,19) = P(11,19);
|
||||
nextP(12,19) = P(12,19);
|
||||
@@ -545,16 +727,16 @@ void Ekf::predictCovariance()
|
||||
nextP(17,19) = P(17,19);
|
||||
nextP(18,19) = P(18,19);
|
||||
nextP(19,19) = P(19,19);
|
||||
nextP(0,20) = P(0,20) + P(1,20)*SF[9] + P(2,20)*SF[11] + P(3,20)*SF[10] + P(10,20)*SF[14] + P(11,20)*SF[15] + P(12,20)*SPP[10];
|
||||
nextP(1,20) = P(1,20) + P(0,20)*SF[8] + P(2,20)*SF[7] + P(3,20)*SF[11] - P(12,20)*SF[15] + P(11,20)*SPP[10] - (P(10,20)*q0)*0.5f;
|
||||
nextP(2,20) = P(2,20) + P(0,20)*SF[6] + P(1,20)*SF[10] + P(3,20)*SF[8] + P(12,20)*SF[14] - P(10,20)*SPP[10] - (P(11,20)*q0)*0.5f;
|
||||
nextP(3,20) = P(3,20) + P(0,20)*SF[7] + P(1,20)*SF[6] + P(2,20)*SF[9] + P(10,20)*SF[15] - P(11,20)*SF[14] - (P(12,20)*q0)*0.5f;
|
||||
nextP(4,20) = P(4,20) + P(0,20)*SF[5] + P(1,20)*SF[3] - P(3,20)*SF[4] + P(2,20)*SPP[0] + P(13,20)*SPP[3] + P(14,20)*SPP[6] - P(15,20)*SPP[9];
|
||||
nextP(5,20) = P(5,20) + P(0,20)*SF[4] + P(2,20)*SF[3] + P(3,20)*SF[5] - P(1,20)*SPP[0] - P(13,20)*SPP[8] + P(14,20)*SPP[2] + P(15,20)*SPP[5];
|
||||
nextP(6,20) = P(6,20) + P(1,20)*SF[4] - P(2,20)*SF[5] + P(3,20)*SF[3] + P(0,20)*SPP[0] + P(13,20)*SPP[4] - P(14,20)*SPP[7] - P(15,20)*SPP[1];
|
||||
nextP(7,20) = P(7,20) + P(4,20)*dt;
|
||||
nextP(8,20) = P(8,20) + P(5,20)*dt;
|
||||
nextP(9,20) = P(9,20) + P(6,20)*dt;
|
||||
nextP(0,20) = P(0,20) - P(1,20)*PS11 + P(10,20)*PS6 + P(11,20)*PS7 + P(12,20)*PS9 - P(2,20)*PS12 - P(3,20)*PS13;
|
||||
nextP(1,20) = P(0,20)*PS11 + P(1,20) - P(10,20)*PS34 + P(11,20)*PS9 - P(12,20)*PS7 + P(2,20)*PS13 - P(3,20)*PS12;
|
||||
nextP(2,20) = P(0,20)*PS12 - P(1,20)*PS13 - P(10,20)*PS9 - P(11,20)*PS34 + P(12,20)*PS6 + P(2,20) + P(3,20)*PS11;
|
||||
nextP(3,20) = P(0,20)*PS13 + P(1,20)*PS12 + P(10,20)*PS7 - P(11,20)*PS6 - P(12,20)*PS34 - P(2,20)*PS11 + P(3,20);
|
||||
nextP(4,20) = P(0,20)*PS72 + P(1,20)*PS62 - P(13,20)*PS44 + P(14,20)*PS140 - P(15,20)*PS139 + P(2,20)*PS60 - P(3,20)*PS74 + P(4,20);
|
||||
nextP(5,20) = P(0,20)*PS74 - P(1,20)*PS60 - P(13,20)*PS162 - P(14,20)*PS65 + P(15,20)*PS160 + P(2,20)*PS62 + P(3,20)*PS72 + P(5,20);
|
||||
nextP(6,20) = P(0,20)*PS60 + P(1,20)*PS74 + P(13,20)*PS166 - P(14,20)*PS165 - P(15,20)*PS70 - P(2,20)*PS72 + P(3,20)*PS62 + P(6,20);
|
||||
nextP(7,20) = P(4,20)*dt + P(7,20);
|
||||
nextP(8,20) = P(5,20)*dt + P(8,20);
|
||||
nextP(9,20) = P(6,20)*dt + P(9,20);
|
||||
nextP(10,20) = P(10,20);
|
||||
nextP(11,20) = P(11,20);
|
||||
nextP(12,20) = P(12,20);
|
||||
@@ -566,16 +748,16 @@ void Ekf::predictCovariance()
|
||||
nextP(18,20) = P(18,20);
|
||||
nextP(19,20) = P(19,20);
|
||||
nextP(20,20) = P(20,20);
|
||||
nextP(0,21) = P(0,21) + P(1,21)*SF[9] + P(2,21)*SF[11] + P(3,21)*SF[10] + P(10,21)*SF[14] + P(11,21)*SF[15] + P(12,21)*SPP[10];
|
||||
nextP(1,21) = P(1,21) + P(0,21)*SF[8] + P(2,21)*SF[7] + P(3,21)*SF[11] - P(12,21)*SF[15] + P(11,21)*SPP[10] - (P(10,21)*q0)*0.5f;
|
||||
nextP(2,21) = P(2,21) + P(0,21)*SF[6] + P(1,21)*SF[10] + P(3,21)*SF[8] + P(12,21)*SF[14] - P(10,21)*SPP[10] - (P(11,21)*q0)*0.5f;
|
||||
nextP(3,21) = P(3,21) + P(0,21)*SF[7] + P(1,21)*SF[6] + P(2,21)*SF[9] + P(10,21)*SF[15] - P(11,21)*SF[14] - (P(12,21)*q0)*0.5f;
|
||||
nextP(4,21) = P(4,21) + P(0,21)*SF[5] + P(1,21)*SF[3] - P(3,21)*SF[4] + P(2,21)*SPP[0] + P(13,21)*SPP[3] + P(14,21)*SPP[6] - P(15,21)*SPP[9];
|
||||
nextP(5,21) = P(5,21) + P(0,21)*SF[4] + P(2,21)*SF[3] + P(3,21)*SF[5] - P(1,21)*SPP[0] - P(13,21)*SPP[8] + P(14,21)*SPP[2] + P(15,21)*SPP[5];
|
||||
nextP(6,21) = P(6,21) + P(1,21)*SF[4] - P(2,21)*SF[5] + P(3,21)*SF[3] + P(0,21)*SPP[0] + P(13,21)*SPP[4] - P(14,21)*SPP[7] - P(15,21)*SPP[1];
|
||||
nextP(7,21) = P(7,21) + P(4,21)*dt;
|
||||
nextP(8,21) = P(8,21) + P(5,21)*dt;
|
||||
nextP(9,21) = P(9,21) + P(6,21)*dt;
|
||||
nextP(0,21) = P(0,21) - P(1,21)*PS11 + P(10,21)*PS6 + P(11,21)*PS7 + P(12,21)*PS9 - P(2,21)*PS12 - P(3,21)*PS13;
|
||||
nextP(1,21) = P(0,21)*PS11 + P(1,21) - P(10,21)*PS34 + P(11,21)*PS9 - P(12,21)*PS7 + P(2,21)*PS13 - P(3,21)*PS12;
|
||||
nextP(2,21) = P(0,21)*PS12 - P(1,21)*PS13 - P(10,21)*PS9 - P(11,21)*PS34 + P(12,21)*PS6 + P(2,21) + P(3,21)*PS11;
|
||||
nextP(3,21) = P(0,21)*PS13 + P(1,21)*PS12 + P(10,21)*PS7 - P(11,21)*PS6 - P(12,21)*PS34 - P(2,21)*PS11 + P(3,21);
|
||||
nextP(4,21) = P(0,21)*PS72 + P(1,21)*PS62 - P(13,21)*PS44 + P(14,21)*PS140 - P(15,21)*PS139 + P(2,21)*PS60 - P(3,21)*PS74 + P(4,21);
|
||||
nextP(5,21) = P(0,21)*PS74 - P(1,21)*PS60 - P(13,21)*PS162 - P(14,21)*PS65 + P(15,21)*PS160 + P(2,21)*PS62 + P(3,21)*PS72 + P(5,21);
|
||||
nextP(6,21) = P(0,21)*PS60 + P(1,21)*PS74 + P(13,21)*PS166 - P(14,21)*PS165 - P(15,21)*PS70 - P(2,21)*PS72 + P(3,21)*PS62 + P(6,21);
|
||||
nextP(7,21) = P(4,21)*dt + P(7,21);
|
||||
nextP(8,21) = P(5,21)*dt + P(8,21);
|
||||
nextP(9,21) = P(6,21)*dt + P(9,21);
|
||||
nextP(10,21) = P(10,21);
|
||||
nextP(11,21) = P(11,21);
|
||||
nextP(12,21) = P(12,21);
|
||||
@@ -600,16 +782,16 @@ void Ekf::predictCovariance()
|
||||
if (_control_status.flags.wind) {
|
||||
|
||||
// calculate variances and upper diagonal covariances for wind states
|
||||
nextP(0,22) = P(0,22) + P(1,22)*SF[9] + P(2,22)*SF[11] + P(3,22)*SF[10] + P(10,22)*SF[14] + P(11,22)*SF[15] + P(12,22)*SPP[10];
|
||||
nextP(1,22) = P(1,22) + P(0,22)*SF[8] + P(2,22)*SF[7] + P(3,22)*SF[11] - P(12,22)*SF[15] + P(11,22)*SPP[10] - (P(10,22)*q0)*0.5f;
|
||||
nextP(2,22) = P(2,22) + P(0,22)*SF[6] + P(1,22)*SF[10] + P(3,22)*SF[8] + P(12,22)*SF[14] - P(10,22)*SPP[10] - (P(11,22)*q0)*0.5f;
|
||||
nextP(3,22) = P(3,22) + P(0,22)*SF[7] + P(1,22)*SF[6] + P(2,22)*SF[9] + P(10,22)*SF[15] - P(11,22)*SF[14] - (P(12,22)*q0)*0.5f;
|
||||
nextP(4,22) = P(4,22) + P(0,22)*SF[5] + P(1,22)*SF[3] - P(3,22)*SF[4] + P(2,22)*SPP[0] + P(13,22)*SPP[3] + P(14,22)*SPP[6] - P(15,22)*SPP[9];
|
||||
nextP(5,22) = P(5,22) + P(0,22)*SF[4] + P(2,22)*SF[3] + P(3,22)*SF[5] - P(1,22)*SPP[0] - P(13,22)*SPP[8] + P(14,22)*SPP[2] + P(15,22)*SPP[5];
|
||||
nextP(6,22) = P(6,22) + P(1,22)*SF[4] - P(2,22)*SF[5] + P(3,22)*SF[3] + P(0,22)*SPP[0] + P(13,22)*SPP[4] - P(14,22)*SPP[7] - P(15,22)*SPP[1];
|
||||
nextP(7,22) = P(7,22) + P(4,22)*dt;
|
||||
nextP(8,22) = P(8,22) + P(5,22)*dt;
|
||||
nextP(9,22) = P(9,22) + P(6,22)*dt;
|
||||
nextP(0,22) = P(0,22) - P(1,22)*PS11 + P(10,22)*PS6 + P(11,22)*PS7 + P(12,22)*PS9 - P(2,22)*PS12 - P(3,22)*PS13;
|
||||
nextP(1,22) = P(0,22)*PS11 + P(1,22) - P(10,22)*PS34 + P(11,22)*PS9 - P(12,22)*PS7 + P(2,22)*PS13 - P(3,22)*PS12;
|
||||
nextP(2,22) = P(0,22)*PS12 - P(1,22)*PS13 - P(10,22)*PS9 - P(11,22)*PS34 + P(12,22)*PS6 + P(2,22) + P(3,22)*PS11;
|
||||
nextP(3,22) = P(0,22)*PS13 + P(1,22)*PS12 + P(10,22)*PS7 - P(11,22)*PS6 - P(12,22)*PS34 - P(2,22)*PS11 + P(3,22);
|
||||
nextP(4,22) = P(0,22)*PS72 + P(1,22)*PS62 - P(13,22)*PS44 + P(14,22)*PS140 - P(15,22)*PS139 + P(2,22)*PS60 - P(3,22)*PS74 + P(4,22);
|
||||
nextP(5,22) = P(0,22)*PS74 - P(1,22)*PS60 - P(13,22)*PS162 - P(14,22)*PS65 + P(15,22)*PS160 + P(2,22)*PS62 + P(3,22)*PS72 + P(5,22);
|
||||
nextP(6,22) = P(0,22)*PS60 + P(1,22)*PS74 + P(13,22)*PS166 - P(14,22)*PS165 - P(15,22)*PS70 - P(2,22)*PS72 + P(3,22)*PS62 + P(6,22);
|
||||
nextP(7,22) = P(4,22)*dt + P(7,22);
|
||||
nextP(8,22) = P(5,22)*dt + P(8,22);
|
||||
nextP(9,22) = P(6,22)*dt + P(9,22);
|
||||
nextP(10,22) = P(10,22);
|
||||
nextP(11,22) = P(11,22);
|
||||
nextP(12,22) = P(12,22);
|
||||
@@ -623,16 +805,16 @@ void Ekf::predictCovariance()
|
||||
nextP(20,22) = P(20,22);
|
||||
nextP(21,22) = P(21,22);
|
||||
nextP(22,22) = P(22,22);
|
||||
nextP(0,23) = P(0,23) + P(1,23)*SF[9] + P(2,23)*SF[11] + P(3,23)*SF[10] + P(10,23)*SF[14] + P(11,23)*SF[15] + P(12,23)*SPP[10];
|
||||
nextP(1,23) = P(1,23) + P(0,23)*SF[8] + P(2,23)*SF[7] + P(3,23)*SF[11] - P(12,23)*SF[15] + P(11,23)*SPP[10] - (P(10,23)*q0)*0.5f;
|
||||
nextP(2,23) = P(2,23) + P(0,23)*SF[6] + P(1,23)*SF[10] + P(3,23)*SF[8] + P(12,23)*SF[14] - P(10,23)*SPP[10] - (P(11,23)*q0)*0.5f;
|
||||
nextP(3,23) = P(3,23) + P(0,23)*SF[7] + P(1,23)*SF[6] + P(2,23)*SF[9] + P(10,23)*SF[15] - P(11,23)*SF[14] - (P(12,23)*q0)*0.5f;
|
||||
nextP(4,23) = P(4,23) + P(0,23)*SF[5] + P(1,23)*SF[3] - P(3,23)*SF[4] + P(2,23)*SPP[0] + P(13,23)*SPP[3] + P(14,23)*SPP[6] - P(15,23)*SPP[9];
|
||||
nextP(5,23) = P(5,23) + P(0,23)*SF[4] + P(2,23)*SF[3] + P(3,23)*SF[5] - P(1,23)*SPP[0] - P(13,23)*SPP[8] + P(14,23)*SPP[2] + P(15,23)*SPP[5];
|
||||
nextP(6,23) = P(6,23) + P(1,23)*SF[4] - P(2,23)*SF[5] + P(3,23)*SF[3] + P(0,23)*SPP[0] + P(13,23)*SPP[4] - P(14,23)*SPP[7] - P(15,23)*SPP[1];
|
||||
nextP(7,23) = P(7,23) + P(4,23)*dt;
|
||||
nextP(8,23) = P(8,23) + P(5,23)*dt;
|
||||
nextP(9,23) = P(9,23) + P(6,23)*dt;
|
||||
nextP(0,23) = P(0,23) - P(1,23)*PS11 + P(10,23)*PS6 + P(11,23)*PS7 + P(12,23)*PS9 - P(2,23)*PS12 - P(3,23)*PS13;
|
||||
nextP(1,23) = P(0,23)*PS11 + P(1,23) - P(10,23)*PS34 + P(11,23)*PS9 - P(12,23)*PS7 + P(2,23)*PS13 - P(3,23)*PS12;
|
||||
nextP(2,23) = P(0,23)*PS12 - P(1,23)*PS13 - P(10,23)*PS9 - P(11,23)*PS34 + P(12,23)*PS6 + P(2,23) + P(3,23)*PS11;
|
||||
nextP(3,23) = P(0,23)*PS13 + P(1,23)*PS12 + P(10,23)*PS7 - P(11,23)*PS6 - P(12,23)*PS34 - P(2,23)*PS11 + P(3,23);
|
||||
nextP(4,23) = P(0,23)*PS72 + P(1,23)*PS62 - P(13,23)*PS44 + P(14,23)*PS140 - P(15,23)*PS139 + P(2,23)*PS60 - P(3,23)*PS74 + P(4,23);
|
||||
nextP(5,23) = P(0,23)*PS74 - P(1,23)*PS60 - P(13,23)*PS162 - P(14,23)*PS65 + P(15,23)*PS160 + P(2,23)*PS62 + P(3,23)*PS72 + P(5,23);
|
||||
nextP(6,23) = P(0,23)*PS60 + P(1,23)*PS74 + P(13,23)*PS166 - P(14,23)*PS165 - P(15,23)*PS70 - P(2,23)*PS72 + P(3,23)*PS62 + P(6,23);
|
||||
nextP(7,23) = P(4,23)*dt + P(7,23);
|
||||
nextP(8,23) = P(5,23)*dt + P(8,23);
|
||||
nextP(9,23) = P(6,23)*dt + P(9,23);
|
||||
nextP(10,23) = P(10,23);
|
||||
nextP(11,23) = P(11,23);
|
||||
nextP(12,23) = P(12,23);
|
||||
|
||||
@@ -0,0 +1,8 @@
|
||||
#!/usr/bin/env python3
|
||||
# -*- coding: utf-8 -*-
|
||||
"""
|
||||
Created on Sat Mar 14 13:02:26 2020
|
||||
|
||||
@author: roman
|
||||
"""
|
||||
|
||||
@@ -0,0 +1,55 @@
|
||||
#!/usr/bin/env python3
|
||||
# -*- coding: utf-8 -*-
|
||||
"""
|
||||
Created on Sat Mar 14 12:47:24 2020
|
||||
|
||||
@author: roman
|
||||
"""
|
||||
from sympy import ccode
|
||||
from sympy.codegen.ast import float32, real
|
||||
|
||||
class CodeGenerator:
|
||||
def __init__(self, file_name):
|
||||
self.file_name = file_name
|
||||
self.file = open(self.file_name, 'w')
|
||||
|
||||
def print_string(self, string):
|
||||
self.file.write("// " + string + "\n")
|
||||
|
||||
def get_ccode(self, expression):
|
||||
return ccode(expression, type_aliases={real:float32})
|
||||
|
||||
def write_subexpressions(self,subexpressions):
|
||||
write_string = ""
|
||||
for item in subexpressions:
|
||||
write_string = write_string + "const float " + str(item[0]) + " = " + self.get_ccode(item[1]) + ";\n"
|
||||
|
||||
write_string = write_string + "\n\n"
|
||||
self.file.write(write_string)
|
||||
|
||||
def write_matrix(self, matrix, identifier, is_symmetric=False):
|
||||
write_string = ""
|
||||
|
||||
if matrix.shape[0] * matrix.shape[1] == 1:
|
||||
write_string = write_string + identifier + " = " + self.get_ccode(matrix[0]) + ";\n"
|
||||
elif matrix.shape[0] == 1 or matrix.shape[1] == 1:
|
||||
for i in range(0,len(matrix)):
|
||||
if (identifier == "Kfusion"):
|
||||
# Vector f format used by Kfusion
|
||||
write_string = write_string + identifier + "(" + str(i) + ") = " + self.get_ccode(matrix[i]) + ";\n"
|
||||
else:
|
||||
# legacy array format used by Hfusion
|
||||
write_string = write_string + identifier + "[" + str(i) + "] = " + self.get_ccode(matrix[i]) + ";\n"
|
||||
else:
|
||||
for j in range(0, matrix.shape[1]):
|
||||
for i in range(0, matrix.shape[0]):
|
||||
if j >= i or not is_symmetric:
|
||||
write_string = write_string + identifier + "(" + str(i) + "," + str(j) + ") = " + self.get_ccode(matrix[i,j]) + ";\n"
|
||||
# legacy array format
|
||||
# write_string = write_string + identifier + "[" + str(i) + "][" + str(j) + "] = " + self.get_ccode(matrix[i,j]) + ";\n"
|
||||
|
||||
write_string = write_string + "\n\n"
|
||||
self.file.write(write_string)
|
||||
|
||||
def close(self):
|
||||
self.file.close()
|
||||
@@ -0,0 +1,492 @@
|
||||
// Equations for covariance matrix prediction, without process noise!
|
||||
const float PS0 = powf(q1, 2);
|
||||
const float PS1 = 0.25F*daxVar;
|
||||
const float PS2 = powf(q2, 2);
|
||||
const float PS3 = 0.25F*dayVar;
|
||||
const float PS4 = powf(q3, 2);
|
||||
const float PS5 = 0.25F*dazVar;
|
||||
const float PS6 = 0.5F*q1;
|
||||
const float PS7 = 0.5F*q2;
|
||||
const float PS8 = P(10,11)*PS7;
|
||||
const float PS9 = 0.5F*q3;
|
||||
const float PS10 = P(10,12)*PS9;
|
||||
const float PS11 = 0.5F*dax - 0.5F*dax_b;
|
||||
const float PS12 = 0.5F*day - 0.5F*day_b;
|
||||
const float PS13 = 0.5F*daz - 0.5F*daz_b;
|
||||
const float PS14 = P(0,10) - P(1,10)*PS11 + P(10,10)*PS6 - P(2,10)*PS12 - P(3,10)*PS13 + PS10 + PS8;
|
||||
const float PS15 = P(10,11)*PS6;
|
||||
const float PS16 = P(11,12)*PS9;
|
||||
const float PS17 = P(0,11) - P(1,11)*PS11 + P(11,11)*PS7 - P(2,11)*PS12 - P(3,11)*PS13 + PS15 + PS16;
|
||||
const float PS18 = P(10,12)*PS6;
|
||||
const float PS19 = P(11,12)*PS7;
|
||||
const float PS20 = P(0,12) - P(1,12)*PS11 + P(12,12)*PS9 - P(2,12)*PS12 - P(3,12)*PS13 + PS18 + PS19;
|
||||
const float PS21 = P(1,2)*PS12;
|
||||
const float PS22 = -P(1,3)*PS13;
|
||||
const float PS23 = P(0,1) - P(1,1)*PS11 + P(1,10)*PS6 + P(1,11)*PS7 + P(1,12)*PS9 - PS21 + PS22;
|
||||
const float PS24 = -P(1,2)*PS11;
|
||||
const float PS25 = P(2,3)*PS13;
|
||||
const float PS26 = P(0,2) + P(2,10)*PS6 + P(2,11)*PS7 + P(2,12)*PS9 - P(2,2)*PS12 + PS24 - PS25;
|
||||
const float PS27 = P(1,3)*PS11;
|
||||
const float PS28 = -P(2,3)*PS12;
|
||||
const float PS29 = P(0,3) + P(3,10)*PS6 + P(3,11)*PS7 + P(3,12)*PS9 - P(3,3)*PS13 - PS27 + PS28;
|
||||
const float PS30 = P(0,1)*PS11;
|
||||
const float PS31 = P(0,2)*PS12;
|
||||
const float PS32 = P(0,3)*PS13;
|
||||
const float PS33 = P(0,0) + P(0,10)*PS6 + P(0,11)*PS7 + P(0,12)*PS9 - PS30 - PS31 - PS32;
|
||||
const float PS34 = 0.5F*q0;
|
||||
const float PS35 = q2*q3;
|
||||
const float PS36 = q0*q1;
|
||||
const float PS37 = q1*q3;
|
||||
const float PS38 = q0*q2;
|
||||
const float PS39 = q1*q2;
|
||||
const float PS40 = q0*q3;
|
||||
const float PS41 = -PS2;
|
||||
const float PS42 = powf(q0, 2);
|
||||
const float PS43 = -PS4 + PS42;
|
||||
const float PS44 = PS0 + PS41 + PS43;
|
||||
const float PS45 = P(0,13) - P(1,13)*PS11 + P(10,13)*PS6 + P(11,13)*PS7 + P(12,13)*PS9 - P(2,13)*PS12 - P(3,13)*PS13;
|
||||
const float PS46 = PS37 + PS38;
|
||||
const float PS47 = P(0,15) - P(1,15)*PS11 + P(10,15)*PS6 + P(11,15)*PS7 + P(12,15)*PS9 - P(2,15)*PS12 - P(3,15)*PS13;
|
||||
const float PS48 = 2*PS47;
|
||||
const float PS49 = dvy - dvy_b;
|
||||
const float PS50 = dvx - dvx_b;
|
||||
const float PS51 = dvz - dvz_b;
|
||||
const float PS52 = PS49*q0 + PS50*q3 - PS51*q1;
|
||||
const float PS53 = 2*PS29;
|
||||
const float PS54 = -PS39 + PS40;
|
||||
const float PS55 = P(0,14) - P(1,14)*PS11 + P(10,14)*PS6 + P(11,14)*PS7 + P(12,14)*PS9 - P(2,14)*PS12 - P(3,14)*PS13;
|
||||
const float PS56 = 2*PS55;
|
||||
const float PS57 = -PS49*q3 + PS50*q0 + PS51*q2;
|
||||
const float PS58 = 2*PS33;
|
||||
const float PS59 = PS49*q1 - PS50*q2 + PS51*q0;
|
||||
const float PS60 = 2*PS59;
|
||||
const float PS61 = PS49*q2 + PS50*q1 + PS51*q3;
|
||||
const float PS62 = 2*PS61;
|
||||
const float PS63 = P(0,4) - P(1,4)*PS11 - P(2,4)*PS12 - P(3,4)*PS13 + P(4,10)*PS6 + P(4,11)*PS7 + P(4,12)*PS9;
|
||||
const float PS64 = -PS0;
|
||||
const float PS65 = PS2 + PS43 + PS64;
|
||||
const float PS66 = PS39 + PS40;
|
||||
const float PS67 = 2*PS45;
|
||||
const float PS68 = -PS35 + PS36;
|
||||
const float PS69 = P(0,5) - P(1,5)*PS11 - P(2,5)*PS12 - P(3,5)*PS13 + P(5,10)*PS6 + P(5,11)*PS7 + P(5,12)*PS9;
|
||||
const float PS70 = PS4 + PS41 + PS42 + PS64;
|
||||
const float PS71 = PS35 + PS36;
|
||||
const float PS72 = 2*PS57;
|
||||
const float PS73 = -PS37 + PS38;
|
||||
const float PS74 = 2*PS52;
|
||||
const float PS75 = P(0,6) - P(1,6)*PS11 - P(2,6)*PS12 - P(3,6)*PS13 + P(6,10)*PS6 + P(6,11)*PS7 + P(6,12)*PS9;
|
||||
const float PS76 = -P(10,11)*PS34;
|
||||
const float PS77 = P(0,11)*PS11 + P(1,11) + P(11,11)*PS9 + P(2,11)*PS13 - P(3,11)*PS12 - PS19 + PS76;
|
||||
const float PS78 = P(0,2)*PS13;
|
||||
const float PS79 = P(0,3)*PS12;
|
||||
const float PS80 = P(0,0)*PS11 + P(0,1) - P(0,10)*PS34 + P(0,11)*PS9 - P(0,12)*PS7 + PS78 - PS79;
|
||||
const float PS81 = P(0,2)*PS11;
|
||||
const float PS82 = P(1,2) - P(2,10)*PS34 + P(2,11)*PS9 - P(2,12)*PS7 + P(2,2)*PS13 + PS28 + PS81;
|
||||
const float PS83 = P(10,11)*PS9;
|
||||
const float PS84 = P(10,12)*PS7;
|
||||
const float PS85 = P(0,10)*PS11 + P(1,10) - P(10,10)*PS34 + P(2,10)*PS13 - P(3,10)*PS12 + PS83 - PS84;
|
||||
const float PS86 = -P(10,12)*PS34;
|
||||
const float PS87 = P(0,12)*PS11 + P(1,12) - P(12,12)*PS7 + P(2,12)*PS13 - P(3,12)*PS12 + PS16 + PS86;
|
||||
const float PS88 = P(0,3)*PS11;
|
||||
const float PS89 = P(1,3) - P(3,10)*PS34 + P(3,11)*PS9 - P(3,12)*PS7 - P(3,3)*PS12 + PS25 + PS88;
|
||||
const float PS90 = P(1,2)*PS13;
|
||||
const float PS91 = P(1,3)*PS12;
|
||||
const float PS92 = P(1,1) - P(1,10)*PS34 + P(1,11)*PS9 - P(1,12)*PS7 + PS30 + PS90 - PS91;
|
||||
const float PS93 = P(0,13)*PS11 + P(1,13) - P(10,13)*PS34 + P(11,13)*PS9 - P(12,13)*PS7 + P(2,13)*PS13 - P(3,13)*PS12;
|
||||
const float PS94 = P(0,15)*PS11 + P(1,15) - P(10,15)*PS34 + P(11,15)*PS9 - P(12,15)*PS7 + P(2,15)*PS13 - P(3,15)*PS12;
|
||||
const float PS95 = 2*PS94;
|
||||
const float PS96 = P(0,14)*PS11 + P(1,14) - P(10,14)*PS34 + P(11,14)*PS9 - P(12,14)*PS7 + P(2,14)*PS13 - P(3,14)*PS12;
|
||||
const float PS97 = 2*PS96;
|
||||
const float PS98 = P(0,4)*PS11 + P(1,4) + P(2,4)*PS13 - P(3,4)*PS12 - P(4,10)*PS34 + P(4,11)*PS9 - P(4,12)*PS7;
|
||||
const float PS99 = 2*PS93;
|
||||
const float PS100 = P(0,5)*PS11 + P(1,5) + P(2,5)*PS13 - P(3,5)*PS12 - P(5,10)*PS34 + P(5,11)*PS9 - P(5,12)*PS7;
|
||||
const float PS101 = P(0,6)*PS11 + P(1,6) + P(2,6)*PS13 - P(3,6)*PS12 - P(6,10)*PS34 + P(6,11)*PS9 - P(6,12)*PS7;
|
||||
const float PS102 = -P(11,12)*PS34;
|
||||
const float PS103 = P(0,12)*PS12 - P(1,12)*PS13 + P(12,12)*PS6 + P(2,12) + P(3,12)*PS11 - PS10 + PS102;
|
||||
const float PS104 = P(2,3) - P(3,10)*PS9 - P(3,11)*PS34 + P(3,12)*PS6 + P(3,3)*PS11 + PS22 + PS79;
|
||||
const float PS105 = P(0,1)*PS13;
|
||||
const float PS106 = P(0,0)*PS12 - P(0,10)*PS9 - P(0,11)*PS34 + P(0,12)*PS6 + P(0,2) - PS105 + PS88;
|
||||
const float PS107 = P(11,12)*PS6;
|
||||
const float PS108 = P(0,11)*PS12 - P(1,11)*PS13 - P(11,11)*PS34 + P(2,11) + P(3,11)*PS11 + PS107 - PS83;
|
||||
const float PS109 = P(0,10)*PS12 - P(1,10)*PS13 - P(10,10)*PS9 + P(2,10) + P(3,10)*PS11 + PS18 + PS76;
|
||||
const float PS110 = P(0,1)*PS12;
|
||||
const float PS111 = -P(1,1)*PS13 - P(1,10)*PS9 - P(1,11)*PS34 + P(1,12)*PS6 + P(1,2) + PS110 + PS27;
|
||||
const float PS112 = P(2,3)*PS11;
|
||||
const float PS113 = -P(2,10)*PS9 - P(2,11)*PS34 + P(2,12)*PS6 + P(2,2) + PS112 + PS31 - PS90;
|
||||
const float PS114 = P(0,13)*PS12 - P(1,13)*PS13 - P(10,13)*PS9 - P(11,13)*PS34 + P(12,13)*PS6 + P(2,13) + P(3,13)*PS11;
|
||||
const float PS115 = P(0,15)*PS12 - P(1,15)*PS13 - P(10,15)*PS9 - P(11,15)*PS34 + P(12,15)*PS6 + P(2,15) + P(3,15)*PS11;
|
||||
const float PS116 = 2*PS115;
|
||||
const float PS117 = P(0,14)*PS12 - P(1,14)*PS13 - P(10,14)*PS9 - P(11,14)*PS34 + P(12,14)*PS6 + P(2,14) + P(3,14)*PS11;
|
||||
const float PS118 = 2*PS117;
|
||||
const float PS119 = P(0,4)*PS12 - P(1,4)*PS13 + P(2,4) + P(3,4)*PS11 - P(4,10)*PS9 - P(4,11)*PS34 + P(4,12)*PS6;
|
||||
const float PS120 = 2*PS114;
|
||||
const float PS121 = P(0,5)*PS12 - P(1,5)*PS13 + P(2,5) + P(3,5)*PS11 - P(5,10)*PS9 - P(5,11)*PS34 + P(5,12)*PS6;
|
||||
const float PS122 = P(0,6)*PS12 - P(1,6)*PS13 + P(2,6) + P(3,6)*PS11 - P(6,10)*PS9 - P(6,11)*PS34 + P(6,12)*PS6;
|
||||
const float PS123 = P(0,10)*PS13 + P(1,10)*PS12 + P(10,10)*PS7 - P(2,10)*PS11 + P(3,10) - PS15 + PS86;
|
||||
const float PS124 = P(1,1)*PS12 + P(1,10)*PS7 - P(1,11)*PS6 - P(1,12)*PS34 + P(1,3) + PS105 + PS24;
|
||||
const float PS125 = P(0,0)*PS13 + P(0,10)*PS7 - P(0,11)*PS6 - P(0,12)*PS34 + P(0,3) + PS110 - PS81;
|
||||
const float PS126 = P(0,12)*PS13 + P(1,12)*PS12 - P(12,12)*PS34 - P(2,12)*PS11 + P(3,12) - PS107 + PS84;
|
||||
const float PS127 = P(0,11)*PS13 + P(1,11)*PS12 - P(11,11)*PS6 - P(2,11)*PS11 + P(3,11) + PS102 + PS8;
|
||||
const float PS128 = P(2,10)*PS7 - P(2,11)*PS6 - P(2,12)*PS34 - P(2,2)*PS11 + P(2,3) + PS21 + PS78;
|
||||
const float PS129 = P(3,10)*PS7 - P(3,11)*PS6 - P(3,12)*PS34 + P(3,3) - PS112 + PS32 + PS91;
|
||||
const float PS130 = P(0,13)*PS13 + P(1,13)*PS12 + P(10,13)*PS7 - P(11,13)*PS6 - P(12,13)*PS34 - P(2,13)*PS11 + P(3,13);
|
||||
const float PS131 = P(0,15)*PS13 + P(1,15)*PS12 + P(10,15)*PS7 - P(11,15)*PS6 - P(12,15)*PS34 - P(2,15)*PS11 + P(3,15);
|
||||
const float PS132 = 2*PS131;
|
||||
const float PS133 = P(0,14)*PS13 + P(1,14)*PS12 + P(10,14)*PS7 - P(11,14)*PS6 - P(12,14)*PS34 - P(2,14)*PS11 + P(3,14);
|
||||
const float PS134 = 2*PS133;
|
||||
const float PS135 = P(0,4)*PS13 + P(1,4)*PS12 - P(2,4)*PS11 + P(3,4) + P(4,10)*PS7 - P(4,11)*PS6 - P(4,12)*PS34;
|
||||
const float PS136 = 2*PS130;
|
||||
const float PS137 = P(0,5)*PS13 + P(1,5)*PS12 - P(2,5)*PS11 + P(3,5) + P(5,10)*PS7 - P(5,11)*PS6 - P(5,12)*PS34;
|
||||
const float PS138 = P(0,6)*PS13 + P(1,6)*PS12 - P(2,6)*PS11 + P(3,6) + P(6,10)*PS7 - P(6,11)*PS6 - P(6,12)*PS34;
|
||||
const float PS139 = 2*PS46;
|
||||
const float PS140 = 2*PS54;
|
||||
const float PS141 = P(0,13)*PS72 + P(1,13)*PS62 - P(13,13)*PS44 + P(13,14)*PS140 - P(13,15)*PS139 + P(2,13)*PS60 - P(3,13)*PS74 + P(4,13);
|
||||
const float PS142 = P(0,15)*PS72 + P(1,15)*PS62 - P(13,15)*PS44 + P(14,15)*PS140 - P(15,15)*PS139 + P(2,15)*PS60 - P(3,15)*PS74 + P(4,15);
|
||||
const float PS143 = P(1,3)*PS62;
|
||||
const float PS144 = P(0,3)*PS72;
|
||||
const float PS145 = P(2,3)*PS60 - P(3,13)*PS44 + P(3,14)*PS140 - P(3,15)*PS139 - P(3,3)*PS74 + P(3,4) + PS143 + PS144;
|
||||
const float PS146 = P(0,14)*PS72 + P(1,14)*PS62 - P(13,14)*PS44 + P(14,14)*PS140 - P(14,15)*PS139 + P(2,14)*PS60 - P(3,14)*PS74 + P(4,14);
|
||||
const float PS147 = P(0,2)*PS60;
|
||||
const float PS148 = P(0,3)*PS74;
|
||||
const float PS149 = P(0,0)*PS72 + P(0,1)*PS62 - P(0,13)*PS44 + P(0,14)*PS140 - P(0,15)*PS139 + P(0,4) + PS147 - PS148;
|
||||
const float PS150 = P(1,2)*PS62;
|
||||
const float PS151 = P(0,2)*PS72;
|
||||
const float PS152 = -P(2,13)*PS44 + P(2,14)*PS140 - P(2,15)*PS139 + P(2,2)*PS60 - P(2,3)*PS74 + P(2,4) + PS150 + PS151;
|
||||
const float PS153 = P(1,2)*PS60;
|
||||
const float PS154 = P(1,3)*PS74;
|
||||
const float PS155 = P(0,1)*PS72 + P(1,1)*PS62 - P(1,13)*PS44 + P(1,14)*PS140 - P(1,15)*PS139 + P(1,4) + PS153 - PS154;
|
||||
const float PS156 = 4*dvyVar;
|
||||
const float PS157 = 4*dvzVar;
|
||||
const float PS158 = P(0,4)*PS72 + P(1,4)*PS62 + P(2,4)*PS60 - P(3,4)*PS74 - P(4,13)*PS44 + P(4,14)*PS140 - P(4,15)*PS139 + P(4,4);
|
||||
const float PS159 = 2*PS141;
|
||||
const float PS160 = 2*PS68;
|
||||
const float PS161 = PS65*dvyVar;
|
||||
const float PS162 = 2*PS66;
|
||||
const float PS163 = PS44*dvxVar;
|
||||
const float PS164 = P(0,5)*PS72 + P(1,5)*PS62 + P(2,5)*PS60 - P(3,5)*PS74 + P(4,5) - P(5,13)*PS44 + P(5,14)*PS140 - P(5,15)*PS139;
|
||||
const float PS165 = 2*PS71;
|
||||
const float PS166 = 2*PS73;
|
||||
const float PS167 = PS70*dvzVar;
|
||||
const float PS168 = P(0,6)*PS72 + P(1,6)*PS62 + P(2,6)*PS60 - P(3,6)*PS74 + P(4,6) - P(6,13)*PS44 + P(6,14)*PS140 - P(6,15)*PS139;
|
||||
const float PS169 = P(0,14)*PS74 - P(1,14)*PS60 - P(13,14)*PS162 - P(14,14)*PS65 + P(14,15)*PS160 + P(2,14)*PS62 + P(3,14)*PS72 + P(5,14);
|
||||
const float PS170 = P(0,13)*PS74 - P(1,13)*PS60 - P(13,13)*PS162 - P(13,14)*PS65 + P(13,15)*PS160 + P(2,13)*PS62 + P(3,13)*PS72 + P(5,13);
|
||||
const float PS171 = P(0,1)*PS74;
|
||||
const float PS172 = -P(1,1)*PS60 - P(1,13)*PS162 - P(1,14)*PS65 + P(1,15)*PS160 + P(1,3)*PS72 + P(1,5) + PS150 + PS171;
|
||||
const float PS173 = P(0,15)*PS74 - P(1,15)*PS60 - P(13,15)*PS162 - P(14,15)*PS65 + P(15,15)*PS160 + P(2,15)*PS62 + P(3,15)*PS72 + P(5,15);
|
||||
const float PS174 = P(2,3)*PS62;
|
||||
const float PS175 = -P(1,3)*PS60 - P(3,13)*PS162 - P(3,14)*PS65 + P(3,15)*PS160 + P(3,3)*PS72 + P(3,5) + PS148 + PS174;
|
||||
const float PS176 = P(0,1)*PS60;
|
||||
const float PS177 = P(0,0)*PS74 - P(0,13)*PS162 - P(0,14)*PS65 + P(0,15)*PS160 + P(0,2)*PS62 + P(0,5) + PS144 - PS176;
|
||||
const float PS178 = P(2,3)*PS72;
|
||||
const float PS179 = P(0,2)*PS74 - P(2,13)*PS162 - P(2,14)*PS65 + P(2,15)*PS160 + P(2,2)*PS62 + P(2,5) - PS153 + PS178;
|
||||
const float PS180 = 4*dvxVar;
|
||||
const float PS181 = P(0,5)*PS74 - P(1,5)*PS60 + P(2,5)*PS62 + P(3,5)*PS72 - P(5,13)*PS162 - P(5,14)*PS65 + P(5,15)*PS160 + P(5,5);
|
||||
const float PS182 = P(0,6)*PS74 - P(1,6)*PS60 + P(2,6)*PS62 + P(3,6)*PS72 + P(5,6) - P(6,13)*PS162 - P(6,14)*PS65 + P(6,15)*PS160;
|
||||
const float PS183 = P(0,15)*PS60 + P(1,15)*PS74 + P(13,15)*PS166 - P(14,15)*PS165 - P(15,15)*PS70 - P(2,15)*PS72 + P(3,15)*PS62 + P(6,15);
|
||||
const float PS184 = P(0,14)*PS60 + P(1,14)*PS74 + P(13,14)*PS166 - P(14,14)*PS165 - P(14,15)*PS70 - P(2,14)*PS72 + P(3,14)*PS62 + P(6,14);
|
||||
const float PS185 = P(0,13)*PS60 + P(1,13)*PS74 + P(13,13)*PS166 - P(13,14)*PS165 - P(13,15)*PS70 - P(2,13)*PS72 + P(3,13)*PS62 + P(6,13);
|
||||
const float PS186 = P(0,6)*PS60 + P(1,6)*PS74 - P(2,6)*PS72 + P(3,6)*PS62 + P(6,13)*PS166 - P(6,14)*PS165 - P(6,15)*PS70 + P(6,6);
|
||||
|
||||
|
||||
nextP(0,0) = PS0*PS1 - PS11*PS23 - PS12*PS26 - PS13*PS29 + PS14*PS6 + PS17*PS7 + PS2*PS3 + PS20*PS9 + PS33 + PS4*PS5;
|
||||
nextP(0,1) = -PS1*PS36 + PS11*PS33 - PS12*PS29 + PS13*PS26 - PS14*PS34 + PS17*PS9 - PS20*PS7 + PS23 + PS3*PS35 - PS35*PS5;
|
||||
nextP(1,1) = PS1*PS42 + PS11*PS80 - PS12*PS89 + PS13*PS82 + PS2*PS5 + PS3*PS4 - PS34*PS85 - PS7*PS87 + PS77*PS9 + PS92;
|
||||
nextP(0,2) = -PS1*PS37 + PS11*PS29 + PS12*PS33 - PS13*PS23 - PS14*PS9 - PS17*PS34 + PS20*PS6 + PS26 - PS3*PS38 + PS37*PS5;
|
||||
nextP(1,2) = PS1*PS40 + PS11*PS89 + PS12*PS80 - PS13*PS92 - PS3*PS40 - PS34*PS77 - PS39*PS5 + PS6*PS87 + PS82 - PS85*PS9;
|
||||
nextP(2,2) = PS0*PS5 + PS1*PS4 + PS103*PS6 + PS104*PS11 + PS106*PS12 - PS108*PS34 - PS109*PS9 - PS111*PS13 + PS113 + PS3*PS42;
|
||||
nextP(0,3) = PS1*PS39 - PS11*PS26 + PS12*PS23 + PS13*PS33 + PS14*PS7 - PS17*PS6 - PS20*PS34 + PS29 - PS3*PS39 - PS40*PS5;
|
||||
nextP(1,3) = -PS1*PS38 - PS11*PS82 + PS12*PS92 + PS13*PS80 - PS3*PS37 - PS34*PS87 + PS38*PS5 - PS6*PS77 + PS7*PS85 + PS89;
|
||||
nextP(2,3) = -PS1*PS35 - PS103*PS34 + PS104 + PS106*PS13 - PS108*PS6 + PS109*PS7 - PS11*PS113 + PS111*PS12 + PS3*PS36 - PS36*PS5;
|
||||
nextP(3,3) = PS0*PS3 + PS1*PS2 - PS11*PS128 + PS12*PS124 + PS123*PS7 + PS125*PS13 - PS126*PS34 - PS127*PS6 + PS129 + PS42*PS5;
|
||||
nextP(0,4) = PS23*PS62 + PS26*PS60 - PS44*PS45 - PS46*PS48 - PS52*PS53 + PS54*PS56 + PS57*PS58 + PS63;
|
||||
nextP(1,4) = -PS44*PS93 - PS46*PS95 + PS54*PS97 + PS60*PS82 + PS62*PS92 + PS72*PS80 - PS74*PS89 + PS98;
|
||||
nextP(2,4) = -PS104*PS74 + PS106*PS72 + PS111*PS62 + PS113*PS60 - PS114*PS44 - PS116*PS46 + PS118*PS54 + PS119;
|
||||
nextP(3,4) = PS124*PS62 + PS125*PS72 + PS128*PS60 - PS129*PS74 - PS130*PS44 - PS132*PS46 + PS134*PS54 + PS135;
|
||||
nextP(4,4) = -PS139*PS142 + PS140*PS146 - PS141*PS44 - PS145*PS74 + PS149*PS72 + PS152*PS60 + PS155*PS62 + PS156*powf(PS54, 2) + PS157*powf(PS46, 2) + PS158 + powf(PS44, 2)*dvxVar;
|
||||
nextP(0,5) = -PS23*PS60 + PS26*PS62 + PS48*PS68 + PS52*PS58 + PS53*PS57 - PS55*PS65 - PS66*PS67 + PS69;
|
||||
nextP(1,5) = PS100 - PS60*PS92 + PS62*PS82 - PS65*PS96 - PS66*PS99 + PS68*PS95 + PS72*PS89 + PS74*PS80;
|
||||
nextP(2,5) = PS104*PS72 + PS106*PS74 - PS111*PS60 + PS113*PS62 + PS116*PS68 - PS117*PS65 - PS120*PS66 + PS121;
|
||||
nextP(3,5) = -PS124*PS60 + PS125*PS74 + PS128*PS62 + PS129*PS72 + PS132*PS68 - PS133*PS65 - PS136*PS66 + PS137;
|
||||
nextP(4,5) = -PS140*PS161 + PS142*PS160 + PS145*PS72 - PS146*PS65 + PS149*PS74 + PS152*PS62 - PS155*PS60 - PS157*PS46*PS68 - PS159*PS66 + PS162*PS163 + PS164;
|
||||
nextP(5,5) = PS157*powf(PS68, 2) + PS160*PS173 - PS162*PS170 - PS169*PS65 - PS172*PS60 + PS175*PS72 + PS177*PS74 + PS179*PS62 + PS180*powf(PS66, 2) + PS181 + powf(PS65, 2)*dvyVar;
|
||||
nextP(0,6) = PS23*PS74 - PS26*PS72 - PS47*PS70 + PS53*PS61 - PS56*PS71 + PS58*PS59 + PS67*PS73 + PS75;
|
||||
nextP(1,6) = PS101 + PS60*PS80 + PS62*PS89 - PS70*PS94 - PS71*PS97 - PS72*PS82 + PS73*PS99 + PS74*PS92;
|
||||
nextP(2,6) = PS104*PS62 + PS106*PS60 + PS111*PS74 - PS113*PS72 - PS115*PS70 - PS118*PS71 + PS120*PS73 + PS122;
|
||||
nextP(3,6) = PS124*PS74 + PS125*PS60 - PS128*PS72 + PS129*PS62 - PS131*PS70 - PS134*PS71 + PS136*PS73 + PS138;
|
||||
nextP(4,6) = PS139*PS167 - PS142*PS70 + PS145*PS62 - PS146*PS165 + PS149*PS60 - PS152*PS72 + PS155*PS74 - PS156*PS54*PS71 + PS159*PS73 - PS163*PS166 + PS168;
|
||||
nextP(5,6) = -PS160*PS167 + PS161*PS165 - PS165*PS169 + PS166*PS170 + PS172*PS74 - PS173*PS70 + PS175*PS62 + PS177*PS60 - PS179*PS72 - PS180*PS66*PS73 + PS182;
|
||||
nextP(6,6) = PS156*powf(PS71, 2) - PS165*PS184 + PS166*PS185 + PS180*powf(PS73, 2) - PS183*PS70 + PS186 + PS60*(P(0,0)*PS60 + P(0,13)*PS166 - P(0,14)*PS165 - P(0,15)*PS70 + P(0,3)*PS62 + P(0,6) - PS151 + PS171) + PS62*(P(0,3)*PS60 + P(3,13)*PS166 - P(3,14)*PS165 - P(3,15)*PS70 + P(3,3)*PS62 + P(3,6) + PS154 - PS178) + powf(PS70, 2)*dvzVar - PS72*(P(1,2)*PS74 + P(2,13)*PS166 - P(2,14)*PS165 - P(2,15)*PS70 - P(2,2)*PS72 + P(2,6) + PS147 + PS174) + PS74*(P(1,1)*PS74 + P(1,13)*PS166 - P(1,14)*PS165 - P(1,15)*PS70 - P(1,2)*PS72 + P(1,6) + PS143 + PS176);
|
||||
nextP(0,7) = P(0,7) - P(1,7)*PS11 - P(2,7)*PS12 - P(3,7)*PS13 + P(7,10)*PS6 + P(7,11)*PS7 + P(7,12)*PS9 + PS63*dt;
|
||||
nextP(1,7) = P(0,7)*PS11 + P(1,7) + P(2,7)*PS13 - P(3,7)*PS12 - P(7,10)*PS34 + P(7,11)*PS9 - P(7,12)*PS7 + PS98*dt;
|
||||
nextP(2,7) = P(0,7)*PS12 - P(1,7)*PS13 + P(2,7) + P(3,7)*PS11 - P(7,10)*PS9 - P(7,11)*PS34 + P(7,12)*PS6 + PS119*dt;
|
||||
nextP(3,7) = P(0,7)*PS13 + P(1,7)*PS12 - P(2,7)*PS11 + P(3,7) + P(7,10)*PS7 - P(7,11)*PS6 - P(7,12)*PS34 + PS135*dt;
|
||||
nextP(4,7) = P(0,7)*PS72 + P(1,7)*PS62 + P(2,7)*PS60 - P(3,7)*PS74 + P(4,7) - P(7,13)*PS44 + P(7,14)*PS140 - P(7,15)*PS139 + PS158*dt;
|
||||
nextP(5,7) = P(0,7)*PS74 - P(1,7)*PS60 + P(2,7)*PS62 + P(3,7)*PS72 + P(5,7) - P(7,13)*PS162 - P(7,14)*PS65 + P(7,15)*PS160 + dt*(P(0,4)*PS74 - P(1,4)*PS60 + P(2,4)*PS62 + P(3,4)*PS72 - P(4,13)*PS162 - P(4,14)*PS65 + P(4,15)*PS160 + P(4,5));
|
||||
nextP(6,7) = P(0,7)*PS60 + P(1,7)*PS74 - P(2,7)*PS72 + P(3,7)*PS62 + P(6,7) + P(7,13)*PS166 - P(7,14)*PS165 - P(7,15)*PS70 + dt*(P(0,4)*PS60 + P(1,4)*PS74 - P(2,4)*PS72 + P(3,4)*PS62 + P(4,13)*PS166 - P(4,14)*PS165 - P(4,15)*PS70 + P(4,6));
|
||||
nextP(7,7) = P(4,7)*dt + P(7,7) + dt*(P(4,4)*dt + P(4,7));
|
||||
nextP(0,8) = P(0,8) - P(1,8)*PS11 - P(2,8)*PS12 - P(3,8)*PS13 + P(8,10)*PS6 + P(8,11)*PS7 + P(8,12)*PS9 + PS69*dt;
|
||||
nextP(1,8) = P(0,8)*PS11 + P(1,8) + P(2,8)*PS13 - P(3,8)*PS12 - P(8,10)*PS34 + P(8,11)*PS9 - P(8,12)*PS7 + PS100*dt;
|
||||
nextP(2,8) = P(0,8)*PS12 - P(1,8)*PS13 + P(2,8) + P(3,8)*PS11 - P(8,10)*PS9 - P(8,11)*PS34 + P(8,12)*PS6 + PS121*dt;
|
||||
nextP(3,8) = P(0,8)*PS13 + P(1,8)*PS12 - P(2,8)*PS11 + P(3,8) + P(8,10)*PS7 - P(8,11)*PS6 - P(8,12)*PS34 + PS137*dt;
|
||||
nextP(4,8) = P(0,8)*PS72 + P(1,8)*PS62 + P(2,8)*PS60 - P(3,8)*PS74 + P(4,8) - P(8,13)*PS44 + P(8,14)*PS140 - P(8,15)*PS139 + PS164*dt;
|
||||
nextP(5,8) = P(0,8)*PS74 - P(1,8)*PS60 + P(2,8)*PS62 + P(3,8)*PS72 + P(5,8) - P(8,13)*PS162 - P(8,14)*PS65 + P(8,15)*PS160 + PS181*dt;
|
||||
nextP(6,8) = P(0,8)*PS60 + P(1,8)*PS74 - P(2,8)*PS72 + P(3,8)*PS62 + P(6,8) + P(8,13)*PS166 - P(8,14)*PS165 - P(8,15)*PS70 + dt*(P(0,5)*PS60 + P(1,5)*PS74 - P(2,5)*PS72 + P(3,5)*PS62 + P(5,13)*PS166 - P(5,14)*PS165 - P(5,15)*PS70 + P(5,6));
|
||||
nextP(7,8) = P(4,8)*dt + P(7,8) + dt*(P(4,5)*dt + P(5,7));
|
||||
nextP(8,8) = P(5,8)*dt + P(8,8) + dt*(P(5,5)*dt + P(5,8));
|
||||
nextP(0,9) = P(0,9) - P(1,9)*PS11 - P(2,9)*PS12 - P(3,9)*PS13 + P(9,10)*PS6 + P(9,11)*PS7 + P(9,12)*PS9 + PS75*dt;
|
||||
nextP(1,9) = P(0,9)*PS11 + P(1,9) + P(2,9)*PS13 - P(3,9)*PS12 - P(9,10)*PS34 + P(9,11)*PS9 - P(9,12)*PS7 + PS101*dt;
|
||||
nextP(2,9) = P(0,9)*PS12 - P(1,9)*PS13 + P(2,9) + P(3,9)*PS11 - P(9,10)*PS9 - P(9,11)*PS34 + P(9,12)*PS6 + PS122*dt;
|
||||
nextP(3,9) = P(0,9)*PS13 + P(1,9)*PS12 - P(2,9)*PS11 + P(3,9) + P(9,10)*PS7 - P(9,11)*PS6 - P(9,12)*PS34 + PS138*dt;
|
||||
nextP(4,9) = P(0,9)*PS72 + P(1,9)*PS62 + P(2,9)*PS60 - P(3,9)*PS74 + P(4,9) - P(9,13)*PS44 + P(9,14)*PS140 - P(9,15)*PS139 + PS168*dt;
|
||||
nextP(5,9) = P(0,9)*PS74 - P(1,9)*PS60 + P(2,9)*PS62 + P(3,9)*PS72 + P(5,9) - P(9,13)*PS162 - P(9,14)*PS65 + P(9,15)*PS160 + PS182*dt;
|
||||
nextP(6,9) = P(0,9)*PS60 + P(1,9)*PS74 - P(2,9)*PS72 + P(3,9)*PS62 + P(6,9) + P(9,13)*PS166 - P(9,14)*PS165 - P(9,15)*PS70 + PS186*dt;
|
||||
nextP(7,9) = P(4,9)*dt + P(7,9) + dt*(P(4,6)*dt + P(6,7));
|
||||
nextP(8,9) = P(5,9)*dt + P(8,9) + dt*(P(5,6)*dt + P(6,8));
|
||||
nextP(9,9) = P(6,9)*dt + P(9,9) + dt*(P(6,6)*dt + P(6,9));
|
||||
nextP(0,10) = PS14;
|
||||
nextP(1,10) = PS85;
|
||||
nextP(2,10) = PS109;
|
||||
nextP(3,10) = PS123;
|
||||
nextP(4,10) = P(0,10)*PS72 + P(1,10)*PS62 - P(10,13)*PS44 + P(10,14)*PS140 - P(10,15)*PS139 + P(2,10)*PS60 - P(3,10)*PS74 + P(4,10);
|
||||
nextP(5,10) = P(0,10)*PS74 - P(1,10)*PS60 - P(10,13)*PS162 - P(10,14)*PS65 + P(10,15)*PS160 + P(2,10)*PS62 + P(3,10)*PS72 + P(5,10);
|
||||
nextP(6,10) = P(0,10)*PS60 + P(1,10)*PS74 + P(10,13)*PS166 - P(10,14)*PS165 - P(10,15)*PS70 - P(2,10)*PS72 + P(3,10)*PS62 + P(6,10);
|
||||
nextP(7,10) = P(4,10)*dt + P(7,10);
|
||||
nextP(8,10) = P(5,10)*dt + P(8,10);
|
||||
nextP(9,10) = P(6,10)*dt + P(9,10);
|
||||
nextP(10,10) = P(10,10);
|
||||
nextP(0,11) = PS17;
|
||||
nextP(1,11) = PS77;
|
||||
nextP(2,11) = PS108;
|
||||
nextP(3,11) = PS127;
|
||||
nextP(4,11) = P(0,11)*PS72 + P(1,11)*PS62 - P(11,13)*PS44 + P(11,14)*PS140 - P(11,15)*PS139 + P(2,11)*PS60 - P(3,11)*PS74 + P(4,11);
|
||||
nextP(5,11) = P(0,11)*PS74 - P(1,11)*PS60 - P(11,13)*PS162 - P(11,14)*PS65 + P(11,15)*PS160 + P(2,11)*PS62 + P(3,11)*PS72 + P(5,11);
|
||||
nextP(6,11) = P(0,11)*PS60 + P(1,11)*PS74 + P(11,13)*PS166 - P(11,14)*PS165 - P(11,15)*PS70 - P(2,11)*PS72 + P(3,11)*PS62 + P(6,11);
|
||||
nextP(7,11) = P(4,11)*dt + P(7,11);
|
||||
nextP(8,11) = P(5,11)*dt + P(8,11);
|
||||
nextP(9,11) = P(6,11)*dt + P(9,11);
|
||||
nextP(10,11) = P(10,11);
|
||||
nextP(11,11) = P(11,11);
|
||||
nextP(0,12) = PS20;
|
||||
nextP(1,12) = PS87;
|
||||
nextP(2,12) = PS103;
|
||||
nextP(3,12) = PS126;
|
||||
nextP(4,12) = P(0,12)*PS72 + P(1,12)*PS62 - P(12,13)*PS44 + P(12,14)*PS140 - P(12,15)*PS139 + P(2,12)*PS60 - P(3,12)*PS74 + P(4,12);
|
||||
nextP(5,12) = P(0,12)*PS74 - P(1,12)*PS60 - P(12,13)*PS162 - P(12,14)*PS65 + P(12,15)*PS160 + P(2,12)*PS62 + P(3,12)*PS72 + P(5,12);
|
||||
nextP(6,12) = P(0,12)*PS60 + P(1,12)*PS74 + P(12,13)*PS166 - P(12,14)*PS165 - P(12,15)*PS70 - P(2,12)*PS72 + P(3,12)*PS62 + P(6,12);
|
||||
nextP(7,12) = P(4,12)*dt + P(7,12);
|
||||
nextP(8,12) = P(5,12)*dt + P(8,12);
|
||||
nextP(9,12) = P(6,12)*dt + P(9,12);
|
||||
nextP(10,12) = P(10,12);
|
||||
nextP(11,12) = P(11,12);
|
||||
nextP(12,12) = P(12,12);
|
||||
nextP(0,13) = PS45;
|
||||
nextP(1,13) = PS93;
|
||||
nextP(2,13) = PS114;
|
||||
nextP(3,13) = PS130;
|
||||
nextP(4,13) = PS141;
|
||||
nextP(5,13) = PS170;
|
||||
nextP(6,13) = PS185;
|
||||
nextP(7,13) = P(4,13)*dt + P(7,13);
|
||||
nextP(8,13) = P(5,13)*dt + P(8,13);
|
||||
nextP(9,13) = P(6,13)*dt + P(9,13);
|
||||
nextP(10,13) = P(10,13);
|
||||
nextP(11,13) = P(11,13);
|
||||
nextP(12,13) = P(12,13);
|
||||
nextP(13,13) = P(13,13);
|
||||
nextP(0,14) = PS55;
|
||||
nextP(1,14) = PS96;
|
||||
nextP(2,14) = PS117;
|
||||
nextP(3,14) = PS133;
|
||||
nextP(4,14) = PS146;
|
||||
nextP(5,14) = PS169;
|
||||
nextP(6,14) = PS184;
|
||||
nextP(7,14) = P(4,14)*dt + P(7,14);
|
||||
nextP(8,14) = P(5,14)*dt + P(8,14);
|
||||
nextP(9,14) = P(6,14)*dt + P(9,14);
|
||||
nextP(10,14) = P(10,14);
|
||||
nextP(11,14) = P(11,14);
|
||||
nextP(12,14) = P(12,14);
|
||||
nextP(13,14) = P(13,14);
|
||||
nextP(14,14) = P(14,14);
|
||||
nextP(0,15) = PS47;
|
||||
nextP(1,15) = PS94;
|
||||
nextP(2,15) = PS115;
|
||||
nextP(3,15) = PS131;
|
||||
nextP(4,15) = PS142;
|
||||
nextP(5,15) = PS173;
|
||||
nextP(6,15) = PS183;
|
||||
nextP(7,15) = P(4,15)*dt + P(7,15);
|
||||
nextP(8,15) = P(5,15)*dt + P(8,15);
|
||||
nextP(9,15) = P(6,15)*dt + P(9,15);
|
||||
nextP(10,15) = P(10,15);
|
||||
nextP(11,15) = P(11,15);
|
||||
nextP(12,15) = P(12,15);
|
||||
nextP(13,15) = P(13,15);
|
||||
nextP(14,15) = P(14,15);
|
||||
nextP(15,15) = P(15,15);
|
||||
nextP(0,16) = P(0,16) - P(1,16)*PS11 + P(10,16)*PS6 + P(11,16)*PS7 + P(12,16)*PS9 - P(2,16)*PS12 - P(3,16)*PS13;
|
||||
nextP(1,16) = P(0,16)*PS11 + P(1,16) - P(10,16)*PS34 + P(11,16)*PS9 - P(12,16)*PS7 + P(2,16)*PS13 - P(3,16)*PS12;
|
||||
nextP(2,16) = P(0,16)*PS12 - P(1,16)*PS13 - P(10,16)*PS9 - P(11,16)*PS34 + P(12,16)*PS6 + P(2,16) + P(3,16)*PS11;
|
||||
nextP(3,16) = P(0,16)*PS13 + P(1,16)*PS12 + P(10,16)*PS7 - P(11,16)*PS6 - P(12,16)*PS34 - P(2,16)*PS11 + P(3,16);
|
||||
nextP(4,16) = P(0,16)*PS72 + P(1,16)*PS62 - P(13,16)*PS44 + P(14,16)*PS140 - P(15,16)*PS139 + P(2,16)*PS60 - P(3,16)*PS74 + P(4,16);
|
||||
nextP(5,16) = P(0,16)*PS74 - P(1,16)*PS60 - P(13,16)*PS162 - P(14,16)*PS65 + P(15,16)*PS160 + P(2,16)*PS62 + P(3,16)*PS72 + P(5,16);
|
||||
nextP(6,16) = P(0,16)*PS60 + P(1,16)*PS74 + P(13,16)*PS166 - P(14,16)*PS165 - P(15,16)*PS70 - P(2,16)*PS72 + P(3,16)*PS62 + P(6,16);
|
||||
nextP(7,16) = P(4,16)*dt + P(7,16);
|
||||
nextP(8,16) = P(5,16)*dt + P(8,16);
|
||||
nextP(9,16) = P(6,16)*dt + P(9,16);
|
||||
nextP(10,16) = P(10,16);
|
||||
nextP(11,16) = P(11,16);
|
||||
nextP(12,16) = P(12,16);
|
||||
nextP(13,16) = P(13,16);
|
||||
nextP(14,16) = P(14,16);
|
||||
nextP(15,16) = P(15,16);
|
||||
nextP(16,16) = P(16,16);
|
||||
nextP(0,17) = P(0,17) - P(1,17)*PS11 + P(10,17)*PS6 + P(11,17)*PS7 + P(12,17)*PS9 - P(2,17)*PS12 - P(3,17)*PS13;
|
||||
nextP(1,17) = P(0,17)*PS11 + P(1,17) - P(10,17)*PS34 + P(11,17)*PS9 - P(12,17)*PS7 + P(2,17)*PS13 - P(3,17)*PS12;
|
||||
nextP(2,17) = P(0,17)*PS12 - P(1,17)*PS13 - P(10,17)*PS9 - P(11,17)*PS34 + P(12,17)*PS6 + P(2,17) + P(3,17)*PS11;
|
||||
nextP(3,17) = P(0,17)*PS13 + P(1,17)*PS12 + P(10,17)*PS7 - P(11,17)*PS6 - P(12,17)*PS34 - P(2,17)*PS11 + P(3,17);
|
||||
nextP(4,17) = P(0,17)*PS72 + P(1,17)*PS62 - P(13,17)*PS44 + P(14,17)*PS140 - P(15,17)*PS139 + P(2,17)*PS60 - P(3,17)*PS74 + P(4,17);
|
||||
nextP(5,17) = P(0,17)*PS74 - P(1,17)*PS60 - P(13,17)*PS162 - P(14,17)*PS65 + P(15,17)*PS160 + P(2,17)*PS62 + P(3,17)*PS72 + P(5,17);
|
||||
nextP(6,17) = P(0,17)*PS60 + P(1,17)*PS74 + P(13,17)*PS166 - P(14,17)*PS165 - P(15,17)*PS70 - P(2,17)*PS72 + P(3,17)*PS62 + P(6,17);
|
||||
nextP(7,17) = P(4,17)*dt + P(7,17);
|
||||
nextP(8,17) = P(5,17)*dt + P(8,17);
|
||||
nextP(9,17) = P(6,17)*dt + P(9,17);
|
||||
nextP(10,17) = P(10,17);
|
||||
nextP(11,17) = P(11,17);
|
||||
nextP(12,17) = P(12,17);
|
||||
nextP(13,17) = P(13,17);
|
||||
nextP(14,17) = P(14,17);
|
||||
nextP(15,17) = P(15,17);
|
||||
nextP(16,17) = P(16,17);
|
||||
nextP(17,17) = P(17,17);
|
||||
nextP(0,18) = P(0,18) - P(1,18)*PS11 + P(10,18)*PS6 + P(11,18)*PS7 + P(12,18)*PS9 - P(2,18)*PS12 - P(3,18)*PS13;
|
||||
nextP(1,18) = P(0,18)*PS11 + P(1,18) - P(10,18)*PS34 + P(11,18)*PS9 - P(12,18)*PS7 + P(2,18)*PS13 - P(3,18)*PS12;
|
||||
nextP(2,18) = P(0,18)*PS12 - P(1,18)*PS13 - P(10,18)*PS9 - P(11,18)*PS34 + P(12,18)*PS6 + P(2,18) + P(3,18)*PS11;
|
||||
nextP(3,18) = P(0,18)*PS13 + P(1,18)*PS12 + P(10,18)*PS7 - P(11,18)*PS6 - P(12,18)*PS34 - P(2,18)*PS11 + P(3,18);
|
||||
nextP(4,18) = P(0,18)*PS72 + P(1,18)*PS62 - P(13,18)*PS44 + P(14,18)*PS140 - P(15,18)*PS139 + P(2,18)*PS60 - P(3,18)*PS74 + P(4,18);
|
||||
nextP(5,18) = P(0,18)*PS74 - P(1,18)*PS60 - P(13,18)*PS162 - P(14,18)*PS65 + P(15,18)*PS160 + P(2,18)*PS62 + P(3,18)*PS72 + P(5,18);
|
||||
nextP(6,18) = P(0,18)*PS60 + P(1,18)*PS74 + P(13,18)*PS166 - P(14,18)*PS165 - P(15,18)*PS70 - P(2,18)*PS72 + P(3,18)*PS62 + P(6,18);
|
||||
nextP(7,18) = P(4,18)*dt + P(7,18);
|
||||
nextP(8,18) = P(5,18)*dt + P(8,18);
|
||||
nextP(9,18) = P(6,18)*dt + P(9,18);
|
||||
nextP(10,18) = P(10,18);
|
||||
nextP(11,18) = P(11,18);
|
||||
nextP(12,18) = P(12,18);
|
||||
nextP(13,18) = P(13,18);
|
||||
nextP(14,18) = P(14,18);
|
||||
nextP(15,18) = P(15,18);
|
||||
nextP(16,18) = P(16,18);
|
||||
nextP(17,18) = P(17,18);
|
||||
nextP(18,18) = P(18,18);
|
||||
nextP(0,19) = P(0,19) - P(1,19)*PS11 + P(10,19)*PS6 + P(11,19)*PS7 + P(12,19)*PS9 - P(2,19)*PS12 - P(3,19)*PS13;
|
||||
nextP(1,19) = P(0,19)*PS11 + P(1,19) - P(10,19)*PS34 + P(11,19)*PS9 - P(12,19)*PS7 + P(2,19)*PS13 - P(3,19)*PS12;
|
||||
nextP(2,19) = P(0,19)*PS12 - P(1,19)*PS13 - P(10,19)*PS9 - P(11,19)*PS34 + P(12,19)*PS6 + P(2,19) + P(3,19)*PS11;
|
||||
nextP(3,19) = P(0,19)*PS13 + P(1,19)*PS12 + P(10,19)*PS7 - P(11,19)*PS6 - P(12,19)*PS34 - P(2,19)*PS11 + P(3,19);
|
||||
nextP(4,19) = P(0,19)*PS72 + P(1,19)*PS62 - P(13,19)*PS44 + P(14,19)*PS140 - P(15,19)*PS139 + P(2,19)*PS60 - P(3,19)*PS74 + P(4,19);
|
||||
nextP(5,19) = P(0,19)*PS74 - P(1,19)*PS60 - P(13,19)*PS162 - P(14,19)*PS65 + P(15,19)*PS160 + P(2,19)*PS62 + P(3,19)*PS72 + P(5,19);
|
||||
nextP(6,19) = P(0,19)*PS60 + P(1,19)*PS74 + P(13,19)*PS166 - P(14,19)*PS165 - P(15,19)*PS70 - P(2,19)*PS72 + P(3,19)*PS62 + P(6,19);
|
||||
nextP(7,19) = P(4,19)*dt + P(7,19);
|
||||
nextP(8,19) = P(5,19)*dt + P(8,19);
|
||||
nextP(9,19) = P(6,19)*dt + P(9,19);
|
||||
nextP(10,19) = P(10,19);
|
||||
nextP(11,19) = P(11,19);
|
||||
nextP(12,19) = P(12,19);
|
||||
nextP(13,19) = P(13,19);
|
||||
nextP(14,19) = P(14,19);
|
||||
nextP(15,19) = P(15,19);
|
||||
nextP(16,19) = P(16,19);
|
||||
nextP(17,19) = P(17,19);
|
||||
nextP(18,19) = P(18,19);
|
||||
nextP(19,19) = P(19,19);
|
||||
nextP(0,20) = P(0,20) - P(1,20)*PS11 + P(10,20)*PS6 + P(11,20)*PS7 + P(12,20)*PS9 - P(2,20)*PS12 - P(3,20)*PS13;
|
||||
nextP(1,20) = P(0,20)*PS11 + P(1,20) - P(10,20)*PS34 + P(11,20)*PS9 - P(12,20)*PS7 + P(2,20)*PS13 - P(3,20)*PS12;
|
||||
nextP(2,20) = P(0,20)*PS12 - P(1,20)*PS13 - P(10,20)*PS9 - P(11,20)*PS34 + P(12,20)*PS6 + P(2,20) + P(3,20)*PS11;
|
||||
nextP(3,20) = P(0,20)*PS13 + P(1,20)*PS12 + P(10,20)*PS7 - P(11,20)*PS6 - P(12,20)*PS34 - P(2,20)*PS11 + P(3,20);
|
||||
nextP(4,20) = P(0,20)*PS72 + P(1,20)*PS62 - P(13,20)*PS44 + P(14,20)*PS140 - P(15,20)*PS139 + P(2,20)*PS60 - P(3,20)*PS74 + P(4,20);
|
||||
nextP(5,20) = P(0,20)*PS74 - P(1,20)*PS60 - P(13,20)*PS162 - P(14,20)*PS65 + P(15,20)*PS160 + P(2,20)*PS62 + P(3,20)*PS72 + P(5,20);
|
||||
nextP(6,20) = P(0,20)*PS60 + P(1,20)*PS74 + P(13,20)*PS166 - P(14,20)*PS165 - P(15,20)*PS70 - P(2,20)*PS72 + P(3,20)*PS62 + P(6,20);
|
||||
nextP(7,20) = P(4,20)*dt + P(7,20);
|
||||
nextP(8,20) = P(5,20)*dt + P(8,20);
|
||||
nextP(9,20) = P(6,20)*dt + P(9,20);
|
||||
nextP(10,20) = P(10,20);
|
||||
nextP(11,20) = P(11,20);
|
||||
nextP(12,20) = P(12,20);
|
||||
nextP(13,20) = P(13,20);
|
||||
nextP(14,20) = P(14,20);
|
||||
nextP(15,20) = P(15,20);
|
||||
nextP(16,20) = P(16,20);
|
||||
nextP(17,20) = P(17,20);
|
||||
nextP(18,20) = P(18,20);
|
||||
nextP(19,20) = P(19,20);
|
||||
nextP(20,20) = P(20,20);
|
||||
nextP(0,21) = P(0,21) - P(1,21)*PS11 + P(10,21)*PS6 + P(11,21)*PS7 + P(12,21)*PS9 - P(2,21)*PS12 - P(3,21)*PS13;
|
||||
nextP(1,21) = P(0,21)*PS11 + P(1,21) - P(10,21)*PS34 + P(11,21)*PS9 - P(12,21)*PS7 + P(2,21)*PS13 - P(3,21)*PS12;
|
||||
nextP(2,21) = P(0,21)*PS12 - P(1,21)*PS13 - P(10,21)*PS9 - P(11,21)*PS34 + P(12,21)*PS6 + P(2,21) + P(3,21)*PS11;
|
||||
nextP(3,21) = P(0,21)*PS13 + P(1,21)*PS12 + P(10,21)*PS7 - P(11,21)*PS6 - P(12,21)*PS34 - P(2,21)*PS11 + P(3,21);
|
||||
nextP(4,21) = P(0,21)*PS72 + P(1,21)*PS62 - P(13,21)*PS44 + P(14,21)*PS140 - P(15,21)*PS139 + P(2,21)*PS60 - P(3,21)*PS74 + P(4,21);
|
||||
nextP(5,21) = P(0,21)*PS74 - P(1,21)*PS60 - P(13,21)*PS162 - P(14,21)*PS65 + P(15,21)*PS160 + P(2,21)*PS62 + P(3,21)*PS72 + P(5,21);
|
||||
nextP(6,21) = P(0,21)*PS60 + P(1,21)*PS74 + P(13,21)*PS166 - P(14,21)*PS165 - P(15,21)*PS70 - P(2,21)*PS72 + P(3,21)*PS62 + P(6,21);
|
||||
nextP(7,21) = P(4,21)*dt + P(7,21);
|
||||
nextP(8,21) = P(5,21)*dt + P(8,21);
|
||||
nextP(9,21) = P(6,21)*dt + P(9,21);
|
||||
nextP(10,21) = P(10,21);
|
||||
nextP(11,21) = P(11,21);
|
||||
nextP(12,21) = P(12,21);
|
||||
nextP(13,21) = P(13,21);
|
||||
nextP(14,21) = P(14,21);
|
||||
nextP(15,21) = P(15,21);
|
||||
nextP(16,21) = P(16,21);
|
||||
nextP(17,21) = P(17,21);
|
||||
nextP(18,21) = P(18,21);
|
||||
nextP(19,21) = P(19,21);
|
||||
nextP(20,21) = P(20,21);
|
||||
nextP(21,21) = P(21,21);
|
||||
nextP(0,22) = P(0,22) - P(1,22)*PS11 + P(10,22)*PS6 + P(11,22)*PS7 + P(12,22)*PS9 - P(2,22)*PS12 - P(3,22)*PS13;
|
||||
nextP(1,22) = P(0,22)*PS11 + P(1,22) - P(10,22)*PS34 + P(11,22)*PS9 - P(12,22)*PS7 + P(2,22)*PS13 - P(3,22)*PS12;
|
||||
nextP(2,22) = P(0,22)*PS12 - P(1,22)*PS13 - P(10,22)*PS9 - P(11,22)*PS34 + P(12,22)*PS6 + P(2,22) + P(3,22)*PS11;
|
||||
nextP(3,22) = P(0,22)*PS13 + P(1,22)*PS12 + P(10,22)*PS7 - P(11,22)*PS6 - P(12,22)*PS34 - P(2,22)*PS11 + P(3,22);
|
||||
nextP(4,22) = P(0,22)*PS72 + P(1,22)*PS62 - P(13,22)*PS44 + P(14,22)*PS140 - P(15,22)*PS139 + P(2,22)*PS60 - P(3,22)*PS74 + P(4,22);
|
||||
nextP(5,22) = P(0,22)*PS74 - P(1,22)*PS60 - P(13,22)*PS162 - P(14,22)*PS65 + P(15,22)*PS160 + P(2,22)*PS62 + P(3,22)*PS72 + P(5,22);
|
||||
nextP(6,22) = P(0,22)*PS60 + P(1,22)*PS74 + P(13,22)*PS166 - P(14,22)*PS165 - P(15,22)*PS70 - P(2,22)*PS72 + P(3,22)*PS62 + P(6,22);
|
||||
nextP(7,22) = P(4,22)*dt + P(7,22);
|
||||
nextP(8,22) = P(5,22)*dt + P(8,22);
|
||||
nextP(9,22) = P(6,22)*dt + P(9,22);
|
||||
nextP(10,22) = P(10,22);
|
||||
nextP(11,22) = P(11,22);
|
||||
nextP(12,22) = P(12,22);
|
||||
nextP(13,22) = P(13,22);
|
||||
nextP(14,22) = P(14,22);
|
||||
nextP(15,22) = P(15,22);
|
||||
nextP(16,22) = P(16,22);
|
||||
nextP(17,22) = P(17,22);
|
||||
nextP(18,22) = P(18,22);
|
||||
nextP(19,22) = P(19,22);
|
||||
nextP(20,22) = P(20,22);
|
||||
nextP(21,22) = P(21,22);
|
||||
nextP(22,22) = P(22,22);
|
||||
nextP(0,23) = P(0,23) - P(1,23)*PS11 + P(10,23)*PS6 + P(11,23)*PS7 + P(12,23)*PS9 - P(2,23)*PS12 - P(3,23)*PS13;
|
||||
nextP(1,23) = P(0,23)*PS11 + P(1,23) - P(10,23)*PS34 + P(11,23)*PS9 - P(12,23)*PS7 + P(2,23)*PS13 - P(3,23)*PS12;
|
||||
nextP(2,23) = P(0,23)*PS12 - P(1,23)*PS13 - P(10,23)*PS9 - P(11,23)*PS34 + P(12,23)*PS6 + P(2,23) + P(3,23)*PS11;
|
||||
nextP(3,23) = P(0,23)*PS13 + P(1,23)*PS12 + P(10,23)*PS7 - P(11,23)*PS6 - P(12,23)*PS34 - P(2,23)*PS11 + P(3,23);
|
||||
nextP(4,23) = P(0,23)*PS72 + P(1,23)*PS62 - P(13,23)*PS44 + P(14,23)*PS140 - P(15,23)*PS139 + P(2,23)*PS60 - P(3,23)*PS74 + P(4,23);
|
||||
nextP(5,23) = P(0,23)*PS74 - P(1,23)*PS60 - P(13,23)*PS162 - P(14,23)*PS65 + P(15,23)*PS160 + P(2,23)*PS62 + P(3,23)*PS72 + P(5,23);
|
||||
nextP(6,23) = P(0,23)*PS60 + P(1,23)*PS74 + P(13,23)*PS166 - P(14,23)*PS165 - P(15,23)*PS70 - P(2,23)*PS72 + P(3,23)*PS62 + P(6,23);
|
||||
nextP(7,23) = P(4,23)*dt + P(7,23);
|
||||
nextP(8,23) = P(5,23)*dt + P(8,23);
|
||||
nextP(9,23) = P(6,23)*dt + P(9,23);
|
||||
nextP(10,23) = P(10,23);
|
||||
nextP(11,23) = P(11,23);
|
||||
nextP(12,23) = P(12,23);
|
||||
nextP(13,23) = P(13,23);
|
||||
nextP(14,23) = P(14,23);
|
||||
nextP(15,23) = P(15,23);
|
||||
nextP(16,23) = P(16,23);
|
||||
nextP(17,23) = P(17,23);
|
||||
nextP(18,23) = P(18,23);
|
||||
nextP(19,23) = P(19,23);
|
||||
nextP(20,23) = P(20,23);
|
||||
nextP(21,23) = P(21,23);
|
||||
nextP(22,23) = P(22,23);
|
||||
nextP(23,23) = P(23,23);
|
||||
|
||||
|
||||
@@ -0,0 +1,955 @@
|
||||
#include <math.h>
|
||||
#include <stdio.h>
|
||||
#include <cstdlib>
|
||||
#include "../../../../../matrix/matrix/math.hpp"
|
||||
|
||||
typedef matrix::SquareMatrix<float, 24> SquareMatrix24f;
|
||||
|
||||
inline float sq(float in) {
|
||||
return in * in;
|
||||
}
|
||||
|
||||
namespace ecl{
|
||||
inline float powf(float x, int exp)
|
||||
{
|
||||
float ret;
|
||||
if (exp > 0) {
|
||||
ret = x;
|
||||
for (int count = 1; count < exp; count++) {
|
||||
ret *= x;
|
||||
}
|
||||
return ret;
|
||||
} else if (exp < 0) {
|
||||
return 1.0f / ecl::powf(x, -exp);
|
||||
}
|
||||
return 1.0f;
|
||||
}
|
||||
}
|
||||
|
||||
int main()
|
||||
{
|
||||
// create input data
|
||||
const float dt = 0.01f;
|
||||
|
||||
for (uint8_t iteration=0; iteration<100; iteration++) {
|
||||
// quaternion states must be normalised
|
||||
float q0 = 2.0f * ((float)rand() - 0.5f);
|
||||
float q1 = 2.0f * ((float)rand() - 0.5f);
|
||||
float q2 = 2.0f * ((float)rand() - 0.5f);
|
||||
float q3 = 2.0f * ((float)rand() - 0.5f);
|
||||
const float length = sqrtf(sq(q0) + sq(q1) + sq(q2) + sq(q3));
|
||||
q0 /= length;
|
||||
q1 /= length;
|
||||
q2 /= length;
|
||||
q3 /= length;
|
||||
|
||||
// up to 1 rad/sec of rate
|
||||
const float dax = 2.0f * dt * ((float)rand() - 0.5f);
|
||||
const float day = 2.0f * dt * ((float)rand() - 0.5f);
|
||||
const float daz = 2.0f * dt * ((float)rand() - 0.5f);
|
||||
|
||||
// up to 2g of accel
|
||||
const float dvx = 2.0f * 20.0f * dt * ((float)rand() - 0.5f);
|
||||
const float dvy = 2.0f * 20.0f * dt * ((float)rand() - 0.5f);
|
||||
const float dvz = 2.0f * 20.0f * dt * ((float)rand() - 0.5f);
|
||||
|
||||
// up to 0.1 rad/sec of gyro bias
|
||||
const float dax_b = 2.0f * 0.1f * dt * ((float)rand() - 0.5f);
|
||||
const float day_b = 2.0f * 0.1f * dt * ((float)rand() - 0.5f);
|
||||
const float daz_b = 2.0f * 0.1f * dt * ((float)rand() - 0.5f);
|
||||
|
||||
// up to 0.5 m/s/s of accel bias
|
||||
const float dvx_b = 2.0f * 0.5f * dt * ((float)rand() - 0.5f);
|
||||
const float dvy_b = 2.0f * 0.5f * dt * ((float)rand() - 0.5f);
|
||||
const float dvz_b = 2.0f * 0.5f * dt * ((float)rand() - 0.5f);
|
||||
|
||||
|
||||
const float daxVar = sq(dt * 0.015f);
|
||||
const float dayVar = daxVar;
|
||||
const float dazVar = daxVar;
|
||||
|
||||
const float dvxVar = sq(dt * 0.3f);
|
||||
const float dvyVar = dvxVar;
|
||||
const float dvzVar = dvxVar;
|
||||
|
||||
// create a symmetrical positive dfinite matrix with off diagonals between -1 and 1 and diagonals between 0 and 1
|
||||
SquareMatrix24f P;
|
||||
for (int col=0; col<=23; col++) {
|
||||
for (int row=0; row<=col; row++) {
|
||||
if (row == col) {
|
||||
P(row,col) = (float)rand();
|
||||
} else {
|
||||
P(col,row) = P(row,col) = 0.01f * 2.0f * ((float)rand() - 0.5f);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Equations for covariance matrix prediction, without process noise!
|
||||
const float PS0 = ecl::powf(q1, 2);
|
||||
const float PS1 = 0.25F*daxVar;
|
||||
const float PS2 = ecl::powf(q2, 2);
|
||||
const float PS3 = 0.25F*dayVar;
|
||||
const float PS4 = ecl::powf(q3, 2);
|
||||
const float PS5 = 0.25F*dazVar;
|
||||
const float PS6 = 0.5F*q1;
|
||||
const float PS7 = 0.5F*q2;
|
||||
const float PS8 = P(10,11)*PS7;
|
||||
const float PS9 = 0.5F*q3;
|
||||
const float PS10 = P(10,12)*PS9;
|
||||
const float PS11 = 0.5F*dax - 0.5F*dax_b;
|
||||
const float PS12 = 0.5F*day - 0.5F*day_b;
|
||||
const float PS13 = 0.5F*daz - 0.5F*daz_b;
|
||||
const float PS14 = P(0,10) - P(1,10)*PS11 + P(10,10)*PS6 - P(2,10)*PS12 - P(3,10)*PS13 + PS10 + PS8;
|
||||
const float PS15 = P(10,11)*PS6;
|
||||
const float PS16 = P(11,12)*PS9;
|
||||
const float PS17 = P(0,11) - P(1,11)*PS11 + P(11,11)*PS7 - P(2,11)*PS12 - P(3,11)*PS13 + PS15 + PS16;
|
||||
const float PS18 = P(10,12)*PS6;
|
||||
const float PS19 = P(11,12)*PS7;
|
||||
const float PS20 = P(0,12) - P(1,12)*PS11 + P(12,12)*PS9 - P(2,12)*PS12 - P(3,12)*PS13 + PS18 + PS19;
|
||||
const float PS21 = P(1,2)*PS12;
|
||||
const float PS22 = -P(1,3)*PS13;
|
||||
const float PS23 = P(0,1) - P(1,1)*PS11 + P(1,10)*PS6 + P(1,11)*PS7 + P(1,12)*PS9 - PS21 + PS22;
|
||||
const float PS24 = -P(1,2)*PS11;
|
||||
const float PS25 = P(2,3)*PS13;
|
||||
const float PS26 = P(0,2) + P(2,10)*PS6 + P(2,11)*PS7 + P(2,12)*PS9 - P(2,2)*PS12 + PS24 - PS25;
|
||||
const float PS27 = P(1,3)*PS11;
|
||||
const float PS28 = -P(2,3)*PS12;
|
||||
const float PS29 = P(0,3) + P(3,10)*PS6 + P(3,11)*PS7 + P(3,12)*PS9 - P(3,3)*PS13 - PS27 + PS28;
|
||||
const float PS30 = P(0,1)*PS11;
|
||||
const float PS31 = P(0,2)*PS12;
|
||||
const float PS32 = P(0,3)*PS13;
|
||||
const float PS33 = P(0,0) + P(0,10)*PS6 + P(0,11)*PS7 + P(0,12)*PS9 - PS30 - PS31 - PS32;
|
||||
const float PS34 = 0.5F*q0;
|
||||
const float PS35 = q2*q3;
|
||||
const float PS36 = q0*q1;
|
||||
const float PS37 = q1*q3;
|
||||
const float PS38 = q0*q2;
|
||||
const float PS39 = q1*q2;
|
||||
const float PS40 = q0*q3;
|
||||
const float PS41 = -PS2;
|
||||
const float PS42 = ecl::powf(q0, 2);
|
||||
const float PS43 = -PS4 + PS42;
|
||||
const float PS44 = PS0 + PS41 + PS43;
|
||||
const float PS45 = P(0,13) - P(1,13)*PS11 + P(10,13)*PS6 + P(11,13)*PS7 + P(12,13)*PS9 - P(2,13)*PS12 - P(3,13)*PS13;
|
||||
const float PS46 = PS37 + PS38;
|
||||
const float PS47 = P(0,15) - P(1,15)*PS11 + P(10,15)*PS6 + P(11,15)*PS7 + P(12,15)*PS9 - P(2,15)*PS12 - P(3,15)*PS13;
|
||||
const float PS48 = 2*PS47;
|
||||
const float PS49 = dvy - dvy_b;
|
||||
const float PS50 = dvx - dvx_b;
|
||||
const float PS51 = dvz - dvz_b;
|
||||
const float PS52 = PS49*q0 + PS50*q3 - PS51*q1;
|
||||
const float PS53 = 2*PS29;
|
||||
const float PS54 = -PS39 + PS40;
|
||||
const float PS55 = P(0,14) - P(1,14)*PS11 + P(10,14)*PS6 + P(11,14)*PS7 + P(12,14)*PS9 - P(2,14)*PS12 - P(3,14)*PS13;
|
||||
const float PS56 = 2*PS55;
|
||||
const float PS57 = -PS49*q3 + PS50*q0 + PS51*q2;
|
||||
const float PS58 = 2*PS33;
|
||||
const float PS59 = PS49*q1 - PS50*q2 + PS51*q0;
|
||||
const float PS60 = 2*PS59;
|
||||
const float PS61 = PS49*q2 + PS50*q1 + PS51*q3;
|
||||
const float PS62 = 2*PS61;
|
||||
const float PS63 = P(0,4) - P(1,4)*PS11 - P(2,4)*PS12 - P(3,4)*PS13 + P(4,10)*PS6 + P(4,11)*PS7 + P(4,12)*PS9;
|
||||
const float PS64 = -PS0;
|
||||
const float PS65 = PS2 + PS43 + PS64;
|
||||
const float PS66 = PS39 + PS40;
|
||||
const float PS67 = 2*PS45;
|
||||
const float PS68 = -PS35 + PS36;
|
||||
const float PS69 = P(0,5) - P(1,5)*PS11 - P(2,5)*PS12 - P(3,5)*PS13 + P(5,10)*PS6 + P(5,11)*PS7 + P(5,12)*PS9;
|
||||
const float PS70 = PS4 + PS41 + PS42 + PS64;
|
||||
const float PS71 = PS35 + PS36;
|
||||
const float PS72 = 2*PS57;
|
||||
const float PS73 = -PS37 + PS38;
|
||||
const float PS74 = 2*PS52;
|
||||
const float PS75 = P(0,6) - P(1,6)*PS11 - P(2,6)*PS12 - P(3,6)*PS13 + P(6,10)*PS6 + P(6,11)*PS7 + P(6,12)*PS9;
|
||||
const float PS76 = -P(10,11)*PS34;
|
||||
const float PS77 = P(0,11)*PS11 + P(1,11) + P(11,11)*PS9 + P(2,11)*PS13 - P(3,11)*PS12 - PS19 + PS76;
|
||||
const float PS78 = P(0,2)*PS13;
|
||||
const float PS79 = P(0,3)*PS12;
|
||||
const float PS80 = P(0,0)*PS11 + P(0,1) - P(0,10)*PS34 + P(0,11)*PS9 - P(0,12)*PS7 + PS78 - PS79;
|
||||
const float PS81 = P(0,2)*PS11;
|
||||
const float PS82 = P(1,2) - P(2,10)*PS34 + P(2,11)*PS9 - P(2,12)*PS7 + P(2,2)*PS13 + PS28 + PS81;
|
||||
const float PS83 = P(10,11)*PS9;
|
||||
const float PS84 = P(10,12)*PS7;
|
||||
const float PS85 = P(0,10)*PS11 + P(1,10) - P(10,10)*PS34 + P(2,10)*PS13 - P(3,10)*PS12 + PS83 - PS84;
|
||||
const float PS86 = -P(10,12)*PS34;
|
||||
const float PS87 = P(0,12)*PS11 + P(1,12) - P(12,12)*PS7 + P(2,12)*PS13 - P(3,12)*PS12 + PS16 + PS86;
|
||||
const float PS88 = P(0,3)*PS11;
|
||||
const float PS89 = P(1,3) - P(3,10)*PS34 + P(3,11)*PS9 - P(3,12)*PS7 - P(3,3)*PS12 + PS25 + PS88;
|
||||
const float PS90 = P(1,2)*PS13;
|
||||
const float PS91 = P(1,3)*PS12;
|
||||
const float PS92 = P(1,1) - P(1,10)*PS34 + P(1,11)*PS9 - P(1,12)*PS7 + PS30 + PS90 - PS91;
|
||||
const float PS93 = P(0,13)*PS11 + P(1,13) - P(10,13)*PS34 + P(11,13)*PS9 - P(12,13)*PS7 + P(2,13)*PS13 - P(3,13)*PS12;
|
||||
const float PS94 = P(0,15)*PS11 + P(1,15) - P(10,15)*PS34 + P(11,15)*PS9 - P(12,15)*PS7 + P(2,15)*PS13 - P(3,15)*PS12;
|
||||
const float PS95 = 2*PS94;
|
||||
const float PS96 = P(0,14)*PS11 + P(1,14) - P(10,14)*PS34 + P(11,14)*PS9 - P(12,14)*PS7 + P(2,14)*PS13 - P(3,14)*PS12;
|
||||
const float PS97 = 2*PS96;
|
||||
const float PS98 = P(0,4)*PS11 + P(1,4) + P(2,4)*PS13 - P(3,4)*PS12 - P(4,10)*PS34 + P(4,11)*PS9 - P(4,12)*PS7;
|
||||
const float PS99 = 2*PS93;
|
||||
const float PS100 = P(0,5)*PS11 + P(1,5) + P(2,5)*PS13 - P(3,5)*PS12 - P(5,10)*PS34 + P(5,11)*PS9 - P(5,12)*PS7;
|
||||
const float PS101 = P(0,6)*PS11 + P(1,6) + P(2,6)*PS13 - P(3,6)*PS12 - P(6,10)*PS34 + P(6,11)*PS9 - P(6,12)*PS7;
|
||||
const float PS102 = -P(11,12)*PS34;
|
||||
const float PS103 = P(0,12)*PS12 - P(1,12)*PS13 + P(12,12)*PS6 + P(2,12) + P(3,12)*PS11 - PS10 + PS102;
|
||||
const float PS104 = P(2,3) - P(3,10)*PS9 - P(3,11)*PS34 + P(3,12)*PS6 + P(3,3)*PS11 + PS22 + PS79;
|
||||
const float PS105 = P(0,1)*PS13;
|
||||
const float PS106 = P(0,0)*PS12 - P(0,10)*PS9 - P(0,11)*PS34 + P(0,12)*PS6 + P(0,2) - PS105 + PS88;
|
||||
const float PS107 = P(11,12)*PS6;
|
||||
const float PS108 = P(0,11)*PS12 - P(1,11)*PS13 - P(11,11)*PS34 + P(2,11) + P(3,11)*PS11 + PS107 - PS83;
|
||||
const float PS109 = P(0,10)*PS12 - P(1,10)*PS13 - P(10,10)*PS9 + P(2,10) + P(3,10)*PS11 + PS18 + PS76;
|
||||
const float PS110 = P(0,1)*PS12;
|
||||
const float PS111 = -P(1,1)*PS13 - P(1,10)*PS9 - P(1,11)*PS34 + P(1,12)*PS6 + P(1,2) + PS110 + PS27;
|
||||
const float PS112 = P(2,3)*PS11;
|
||||
const float PS113 = -P(2,10)*PS9 - P(2,11)*PS34 + P(2,12)*PS6 + P(2,2) + PS112 + PS31 - PS90;
|
||||
const float PS114 = P(0,13)*PS12 - P(1,13)*PS13 - P(10,13)*PS9 - P(11,13)*PS34 + P(12,13)*PS6 + P(2,13) + P(3,13)*PS11;
|
||||
const float PS115 = P(0,15)*PS12 - P(1,15)*PS13 - P(10,15)*PS9 - P(11,15)*PS34 + P(12,15)*PS6 + P(2,15) + P(3,15)*PS11;
|
||||
const float PS116 = 2*PS115;
|
||||
const float PS117 = P(0,14)*PS12 - P(1,14)*PS13 - P(10,14)*PS9 - P(11,14)*PS34 + P(12,14)*PS6 + P(2,14) + P(3,14)*PS11;
|
||||
const float PS118 = 2*PS117;
|
||||
const float PS119 = P(0,4)*PS12 - P(1,4)*PS13 + P(2,4) + P(3,4)*PS11 - P(4,10)*PS9 - P(4,11)*PS34 + P(4,12)*PS6;
|
||||
const float PS120 = 2*PS114;
|
||||
const float PS121 = P(0,5)*PS12 - P(1,5)*PS13 + P(2,5) + P(3,5)*PS11 - P(5,10)*PS9 - P(5,11)*PS34 + P(5,12)*PS6;
|
||||
const float PS122 = P(0,6)*PS12 - P(1,6)*PS13 + P(2,6) + P(3,6)*PS11 - P(6,10)*PS9 - P(6,11)*PS34 + P(6,12)*PS6;
|
||||
const float PS123 = P(0,10)*PS13 + P(1,10)*PS12 + P(10,10)*PS7 - P(2,10)*PS11 + P(3,10) - PS15 + PS86;
|
||||
const float PS124 = P(1,1)*PS12 + P(1,10)*PS7 - P(1,11)*PS6 - P(1,12)*PS34 + P(1,3) + PS105 + PS24;
|
||||
const float PS125 = P(0,0)*PS13 + P(0,10)*PS7 - P(0,11)*PS6 - P(0,12)*PS34 + P(0,3) + PS110 - PS81;
|
||||
const float PS126 = P(0,12)*PS13 + P(1,12)*PS12 - P(12,12)*PS34 - P(2,12)*PS11 + P(3,12) - PS107 + PS84;
|
||||
const float PS127 = P(0,11)*PS13 + P(1,11)*PS12 - P(11,11)*PS6 - P(2,11)*PS11 + P(3,11) + PS102 + PS8;
|
||||
const float PS128 = P(2,10)*PS7 - P(2,11)*PS6 - P(2,12)*PS34 - P(2,2)*PS11 + P(2,3) + PS21 + PS78;
|
||||
const float PS129 = P(3,10)*PS7 - P(3,11)*PS6 - P(3,12)*PS34 + P(3,3) - PS112 + PS32 + PS91;
|
||||
const float PS130 = P(0,13)*PS13 + P(1,13)*PS12 + P(10,13)*PS7 - P(11,13)*PS6 - P(12,13)*PS34 - P(2,13)*PS11 + P(3,13);
|
||||
const float PS131 = P(0,15)*PS13 + P(1,15)*PS12 + P(10,15)*PS7 - P(11,15)*PS6 - P(12,15)*PS34 - P(2,15)*PS11 + P(3,15);
|
||||
const float PS132 = 2*PS131;
|
||||
const float PS133 = P(0,14)*PS13 + P(1,14)*PS12 + P(10,14)*PS7 - P(11,14)*PS6 - P(12,14)*PS34 - P(2,14)*PS11 + P(3,14);
|
||||
const float PS134 = 2*PS133;
|
||||
const float PS135 = P(0,4)*PS13 + P(1,4)*PS12 - P(2,4)*PS11 + P(3,4) + P(4,10)*PS7 - P(4,11)*PS6 - P(4,12)*PS34;
|
||||
const float PS136 = 2*PS130;
|
||||
const float PS137 = P(0,5)*PS13 + P(1,5)*PS12 - P(2,5)*PS11 + P(3,5) + P(5,10)*PS7 - P(5,11)*PS6 - P(5,12)*PS34;
|
||||
const float PS138 = P(0,6)*PS13 + P(1,6)*PS12 - P(2,6)*PS11 + P(3,6) + P(6,10)*PS7 - P(6,11)*PS6 - P(6,12)*PS34;
|
||||
const float PS139 = 2*PS46;
|
||||
const float PS140 = 2*PS54;
|
||||
const float PS141 = P(0,13)*PS72 + P(1,13)*PS62 - P(13,13)*PS44 + P(13,14)*PS140 - P(13,15)*PS139 + P(2,13)*PS60 - P(3,13)*PS74 + P(4,13);
|
||||
const float PS142 = P(0,15)*PS72 + P(1,15)*PS62 - P(13,15)*PS44 + P(14,15)*PS140 - P(15,15)*PS139 + P(2,15)*PS60 - P(3,15)*PS74 + P(4,15);
|
||||
const float PS143 = P(1,3)*PS62;
|
||||
const float PS144 = P(0,3)*PS72;
|
||||
const float PS145 = P(2,3)*PS60 - P(3,13)*PS44 + P(3,14)*PS140 - P(3,15)*PS139 - P(3,3)*PS74 + P(3,4) + PS143 + PS144;
|
||||
const float PS146 = P(0,14)*PS72 + P(1,14)*PS62 - P(13,14)*PS44 + P(14,14)*PS140 - P(14,15)*PS139 + P(2,14)*PS60 - P(3,14)*PS74 + P(4,14);
|
||||
const float PS147 = P(0,2)*PS60;
|
||||
const float PS148 = P(0,3)*PS74;
|
||||
const float PS149 = P(0,0)*PS72 + P(0,1)*PS62 - P(0,13)*PS44 + P(0,14)*PS140 - P(0,15)*PS139 + P(0,4) + PS147 - PS148;
|
||||
const float PS150 = P(1,2)*PS62;
|
||||
const float PS151 = P(0,2)*PS72;
|
||||
const float PS152 = -P(2,13)*PS44 + P(2,14)*PS140 - P(2,15)*PS139 + P(2,2)*PS60 - P(2,3)*PS74 + P(2,4) + PS150 + PS151;
|
||||
const float PS153 = P(1,2)*PS60;
|
||||
const float PS154 = P(1,3)*PS74;
|
||||
const float PS155 = P(0,1)*PS72 + P(1,1)*PS62 - P(1,13)*PS44 + P(1,14)*PS140 - P(1,15)*PS139 + P(1,4) + PS153 - PS154;
|
||||
const float PS156 = 4*dvyVar;
|
||||
const float PS157 = 4*dvzVar;
|
||||
const float PS158 = P(0,4)*PS72 + P(1,4)*PS62 + P(2,4)*PS60 - P(3,4)*PS74 - P(4,13)*PS44 + P(4,14)*PS140 - P(4,15)*PS139 + P(4,4);
|
||||
const float PS159 = 2*PS141;
|
||||
const float PS160 = 2*PS68;
|
||||
const float PS161 = PS65*dvyVar;
|
||||
const float PS162 = 2*PS66;
|
||||
const float PS163 = PS44*dvxVar;
|
||||
const float PS164 = P(0,5)*PS72 + P(1,5)*PS62 + P(2,5)*PS60 - P(3,5)*PS74 + P(4,5) - P(5,13)*PS44 + P(5,14)*PS140 - P(5,15)*PS139;
|
||||
const float PS165 = 2*PS71;
|
||||
const float PS166 = 2*PS73;
|
||||
const float PS167 = PS70*dvzVar;
|
||||
const float PS168 = P(0,6)*PS72 + P(1,6)*PS62 + P(2,6)*PS60 - P(3,6)*PS74 + P(4,6) - P(6,13)*PS44 + P(6,14)*PS140 - P(6,15)*PS139;
|
||||
const float PS169 = P(0,14)*PS74 - P(1,14)*PS60 - P(13,14)*PS162 - P(14,14)*PS65 + P(14,15)*PS160 + P(2,14)*PS62 + P(3,14)*PS72 + P(5,14);
|
||||
const float PS170 = P(0,13)*PS74 - P(1,13)*PS60 - P(13,13)*PS162 - P(13,14)*PS65 + P(13,15)*PS160 + P(2,13)*PS62 + P(3,13)*PS72 + P(5,13);
|
||||
const float PS171 = P(0,1)*PS74;
|
||||
const float PS172 = -P(1,1)*PS60 - P(1,13)*PS162 - P(1,14)*PS65 + P(1,15)*PS160 + P(1,3)*PS72 + P(1,5) + PS150 + PS171;
|
||||
const float PS173 = P(0,15)*PS74 - P(1,15)*PS60 - P(13,15)*PS162 - P(14,15)*PS65 + P(15,15)*PS160 + P(2,15)*PS62 + P(3,15)*PS72 + P(5,15);
|
||||
const float PS174 = P(2,3)*PS62;
|
||||
const float PS175 = -P(1,3)*PS60 - P(3,13)*PS162 - P(3,14)*PS65 + P(3,15)*PS160 + P(3,3)*PS72 + P(3,5) + PS148 + PS174;
|
||||
const float PS176 = P(0,1)*PS60;
|
||||
const float PS177 = P(0,0)*PS74 - P(0,13)*PS162 - P(0,14)*PS65 + P(0,15)*PS160 + P(0,2)*PS62 + P(0,5) + PS144 - PS176;
|
||||
const float PS178 = P(2,3)*PS72;
|
||||
const float PS179 = P(0,2)*PS74 - P(2,13)*PS162 - P(2,14)*PS65 + P(2,15)*PS160 + P(2,2)*PS62 + P(2,5) - PS153 + PS178;
|
||||
const float PS180 = 4*dvxVar;
|
||||
const float PS181 = P(0,5)*PS74 - P(1,5)*PS60 + P(2,5)*PS62 + P(3,5)*PS72 - P(5,13)*PS162 - P(5,14)*PS65 + P(5,15)*PS160 + P(5,5);
|
||||
const float PS182 = P(0,6)*PS74 - P(1,6)*PS60 + P(2,6)*PS62 + P(3,6)*PS72 + P(5,6) - P(6,13)*PS162 - P(6,14)*PS65 + P(6,15)*PS160;
|
||||
const float PS183 = P(0,15)*PS60 + P(1,15)*PS74 + P(13,15)*PS166 - P(14,15)*PS165 - P(15,15)*PS70 - P(2,15)*PS72 + P(3,15)*PS62 + P(6,15);
|
||||
const float PS184 = P(0,14)*PS60 + P(1,14)*PS74 + P(13,14)*PS166 - P(14,14)*PS165 - P(14,15)*PS70 - P(2,14)*PS72 + P(3,14)*PS62 + P(6,14);
|
||||
const float PS185 = P(0,13)*PS60 + P(1,13)*PS74 + P(13,13)*PS166 - P(13,14)*PS165 - P(13,15)*PS70 - P(2,13)*PS72 + P(3,13)*PS62 + P(6,13);
|
||||
const float PS186 = P(0,6)*PS60 + P(1,6)*PS74 - P(2,6)*PS72 + P(3,6)*PS62 + P(6,13)*PS166 - P(6,14)*PS165 - P(6,15)*PS70 + P(6,6);
|
||||
|
||||
SquareMatrix24f nextP;
|
||||
|
||||
nextP(0,0) = PS0*PS1 - PS11*PS23 - PS12*PS26 - PS13*PS29 + PS14*PS6 + PS17*PS7 + PS2*PS3 + PS20*PS9 + PS33 + PS4*PS5;
|
||||
nextP(0,1) = -PS1*PS36 + PS11*PS33 - PS12*PS29 + PS13*PS26 - PS14*PS34 + PS17*PS9 - PS20*PS7 + PS23 + PS3*PS35 - PS35*PS5;
|
||||
nextP(1,1) = PS1*PS42 + PS11*PS80 - PS12*PS89 + PS13*PS82 + PS2*PS5 + PS3*PS4 - PS34*PS85 - PS7*PS87 + PS77*PS9 + PS92;
|
||||
nextP(0,2) = -PS1*PS37 + PS11*PS29 + PS12*PS33 - PS13*PS23 - PS14*PS9 - PS17*PS34 + PS20*PS6 + PS26 - PS3*PS38 + PS37*PS5;
|
||||
nextP(1,2) = PS1*PS40 + PS11*PS89 + PS12*PS80 - PS13*PS92 - PS3*PS40 - PS34*PS77 - PS39*PS5 + PS6*PS87 + PS82 - PS85*PS9;
|
||||
nextP(2,2) = PS0*PS5 + PS1*PS4 + PS103*PS6 + PS104*PS11 + PS106*PS12 - PS108*PS34 - PS109*PS9 - PS111*PS13 + PS113 + PS3*PS42;
|
||||
nextP(0,3) = PS1*PS39 - PS11*PS26 + PS12*PS23 + PS13*PS33 + PS14*PS7 - PS17*PS6 - PS20*PS34 + PS29 - PS3*PS39 - PS40*PS5;
|
||||
nextP(1,3) = -PS1*PS38 - PS11*PS82 + PS12*PS92 + PS13*PS80 - PS3*PS37 - PS34*PS87 + PS38*PS5 - PS6*PS77 + PS7*PS85 + PS89;
|
||||
nextP(2,3) = -PS1*PS35 - PS103*PS34 + PS104 + PS106*PS13 - PS108*PS6 + PS109*PS7 - PS11*PS113 + PS111*PS12 + PS3*PS36 - PS36*PS5;
|
||||
nextP(3,3) = PS0*PS3 + PS1*PS2 - PS11*PS128 + PS12*PS124 + PS123*PS7 + PS125*PS13 - PS126*PS34 - PS127*PS6 + PS129 + PS42*PS5;
|
||||
nextP(0,4) = PS23*PS62 + PS26*PS60 - PS44*PS45 - PS46*PS48 - PS52*PS53 + PS54*PS56 + PS57*PS58 + PS63;
|
||||
nextP(1,4) = -PS44*PS93 - PS46*PS95 + PS54*PS97 + PS60*PS82 + PS62*PS92 + PS72*PS80 - PS74*PS89 + PS98;
|
||||
nextP(2,4) = -PS104*PS74 + PS106*PS72 + PS111*PS62 + PS113*PS60 - PS114*PS44 - PS116*PS46 + PS118*PS54 + PS119;
|
||||
nextP(3,4) = PS124*PS62 + PS125*PS72 + PS128*PS60 - PS129*PS74 - PS130*PS44 - PS132*PS46 + PS134*PS54 + PS135;
|
||||
nextP(4,4) = -PS139*PS142 + PS140*PS146 - PS141*PS44 - PS145*PS74 + PS149*PS72 + PS152*PS60 + PS155*PS62 + PS156*ecl::powf(PS54, 2) + PS157*ecl::powf(PS46, 2) + PS158 + ecl::powf(PS44, 2)*dvxVar;
|
||||
nextP(0,5) = -PS23*PS60 + PS26*PS62 + PS48*PS68 + PS52*PS58 + PS53*PS57 - PS55*PS65 - PS66*PS67 + PS69;
|
||||
nextP(1,5) = PS100 - PS60*PS92 + PS62*PS82 - PS65*PS96 - PS66*PS99 + PS68*PS95 + PS72*PS89 + PS74*PS80;
|
||||
nextP(2,5) = PS104*PS72 + PS106*PS74 - PS111*PS60 + PS113*PS62 + PS116*PS68 - PS117*PS65 - PS120*PS66 + PS121;
|
||||
nextP(3,5) = -PS124*PS60 + PS125*PS74 + PS128*PS62 + PS129*PS72 + PS132*PS68 - PS133*PS65 - PS136*PS66 + PS137;
|
||||
nextP(4,5) = -PS140*PS161 + PS142*PS160 + PS145*PS72 - PS146*PS65 + PS149*PS74 + PS152*PS62 - PS155*PS60 - PS157*PS46*PS68 - PS159*PS66 + PS162*PS163 + PS164;
|
||||
nextP(5,5) = PS157*ecl::powf(PS68, 2) + PS160*PS173 - PS162*PS170 - PS169*PS65 - PS172*PS60 + PS175*PS72 + PS177*PS74 + PS179*PS62 + PS180*ecl::powf(PS66, 2) + PS181 + ecl::powf(PS65, 2)*dvyVar;
|
||||
nextP(0,6) = PS23*PS74 - PS26*PS72 - PS47*PS70 + PS53*PS61 - PS56*PS71 + PS58*PS59 + PS67*PS73 + PS75;
|
||||
nextP(1,6) = PS101 + PS60*PS80 + PS62*PS89 - PS70*PS94 - PS71*PS97 - PS72*PS82 + PS73*PS99 + PS74*PS92;
|
||||
nextP(2,6) = PS104*PS62 + PS106*PS60 + PS111*PS74 - PS113*PS72 - PS115*PS70 - PS118*PS71 + PS120*PS73 + PS122;
|
||||
nextP(3,6) = PS124*PS74 + PS125*PS60 - PS128*PS72 + PS129*PS62 - PS131*PS70 - PS134*PS71 + PS136*PS73 + PS138;
|
||||
nextP(4,6) = PS139*PS167 - PS142*PS70 + PS145*PS62 - PS146*PS165 + PS149*PS60 - PS152*PS72 + PS155*PS74 - PS156*PS54*PS71 + PS159*PS73 - PS163*PS166 + PS168;
|
||||
nextP(5,6) = -PS160*PS167 + PS161*PS165 - PS165*PS169 + PS166*PS170 + PS172*PS74 - PS173*PS70 + PS175*PS62 + PS177*PS60 - PS179*PS72 - PS180*PS66*PS73 + PS182;
|
||||
nextP(6,6) = PS156*ecl::powf(PS71, 2) - PS165*PS184 + PS166*PS185 + PS180*ecl::powf(PS73, 2) - PS183*PS70 + PS186 + PS60*(P(0,0)*PS60 + P(0,13)*PS166 - P(0,14)*PS165 - P(0,15)*PS70 + P(0,3)*PS62 + P(0,6) - PS151 + PS171) + PS62*(P(0,3)*PS60 + P(3,13)*PS166 - P(3,14)*PS165 - P(3,15)*PS70 + P(3,3)*PS62 + P(3,6) + PS154 - PS178) + ecl::powf(PS70, 2)*dvzVar - PS72*(P(1,2)*PS74 + P(2,13)*PS166 - P(2,14)*PS165 - P(2,15)*PS70 - P(2,2)*PS72 + P(2,6) + PS147 + PS174) + PS74*(P(1,1)*PS74 + P(1,13)*PS166 - P(1,14)*PS165 - P(1,15)*PS70 - P(1,2)*PS72 + P(1,6) + PS143 + PS176);
|
||||
nextP(0,7) = P(0,7) - P(1,7)*PS11 - P(2,7)*PS12 - P(3,7)*PS13 + P(7,10)*PS6 + P(7,11)*PS7 + P(7,12)*PS9 + PS63*dt;
|
||||
nextP(1,7) = P(0,7)*PS11 + P(1,7) + P(2,7)*PS13 - P(3,7)*PS12 - P(7,10)*PS34 + P(7,11)*PS9 - P(7,12)*PS7 + PS98*dt;
|
||||
nextP(2,7) = P(0,7)*PS12 - P(1,7)*PS13 + P(2,7) + P(3,7)*PS11 - P(7,10)*PS9 - P(7,11)*PS34 + P(7,12)*PS6 + PS119*dt;
|
||||
nextP(3,7) = P(0,7)*PS13 + P(1,7)*PS12 - P(2,7)*PS11 + P(3,7) + P(7,10)*PS7 - P(7,11)*PS6 - P(7,12)*PS34 + PS135*dt;
|
||||
nextP(4,7) = P(0,7)*PS72 + P(1,7)*PS62 + P(2,7)*PS60 - P(3,7)*PS74 + P(4,7) - P(7,13)*PS44 + P(7,14)*PS140 - P(7,15)*PS139 + PS158*dt;
|
||||
nextP(5,7) = P(0,7)*PS74 - P(1,7)*PS60 + P(2,7)*PS62 + P(3,7)*PS72 + P(5,7) - P(7,13)*PS162 - P(7,14)*PS65 + P(7,15)*PS160 + dt*(P(0,4)*PS74 - P(1,4)*PS60 + P(2,4)*PS62 + P(3,4)*PS72 - P(4,13)*PS162 - P(4,14)*PS65 + P(4,15)*PS160 + P(4,5));
|
||||
nextP(6,7) = P(0,7)*PS60 + P(1,7)*PS74 - P(2,7)*PS72 + P(3,7)*PS62 + P(6,7) + P(7,13)*PS166 - P(7,14)*PS165 - P(7,15)*PS70 + dt*(P(0,4)*PS60 + P(1,4)*PS74 - P(2,4)*PS72 + P(3,4)*PS62 + P(4,13)*PS166 - P(4,14)*PS165 - P(4,15)*PS70 + P(4,6));
|
||||
nextP(7,7) = P(4,7)*dt + P(7,7) + dt*(P(4,4)*dt + P(4,7));
|
||||
nextP(0,8) = P(0,8) - P(1,8)*PS11 - P(2,8)*PS12 - P(3,8)*PS13 + P(8,10)*PS6 + P(8,11)*PS7 + P(8,12)*PS9 + PS69*dt;
|
||||
nextP(1,8) = P(0,8)*PS11 + P(1,8) + P(2,8)*PS13 - P(3,8)*PS12 - P(8,10)*PS34 + P(8,11)*PS9 - P(8,12)*PS7 + PS100*dt;
|
||||
nextP(2,8) = P(0,8)*PS12 - P(1,8)*PS13 + P(2,8) + P(3,8)*PS11 - P(8,10)*PS9 - P(8,11)*PS34 + P(8,12)*PS6 + PS121*dt;
|
||||
nextP(3,8) = P(0,8)*PS13 + P(1,8)*PS12 - P(2,8)*PS11 + P(3,8) + P(8,10)*PS7 - P(8,11)*PS6 - P(8,12)*PS34 + PS137*dt;
|
||||
nextP(4,8) = P(0,8)*PS72 + P(1,8)*PS62 + P(2,8)*PS60 - P(3,8)*PS74 + P(4,8) - P(8,13)*PS44 + P(8,14)*PS140 - P(8,15)*PS139 + PS164*dt;
|
||||
nextP(5,8) = P(0,8)*PS74 - P(1,8)*PS60 + P(2,8)*PS62 + P(3,8)*PS72 + P(5,8) - P(8,13)*PS162 - P(8,14)*PS65 + P(8,15)*PS160 + PS181*dt;
|
||||
nextP(6,8) = P(0,8)*PS60 + P(1,8)*PS74 - P(2,8)*PS72 + P(3,8)*PS62 + P(6,8) + P(8,13)*PS166 - P(8,14)*PS165 - P(8,15)*PS70 + dt*(P(0,5)*PS60 + P(1,5)*PS74 - P(2,5)*PS72 + P(3,5)*PS62 + P(5,13)*PS166 - P(5,14)*PS165 - P(5,15)*PS70 + P(5,6));
|
||||
nextP(7,8) = P(4,8)*dt + P(7,8) + dt*(P(4,5)*dt + P(5,7));
|
||||
nextP(8,8) = P(5,8)*dt + P(8,8) + dt*(P(5,5)*dt + P(5,8));
|
||||
nextP(0,9) = P(0,9) - P(1,9)*PS11 - P(2,9)*PS12 - P(3,9)*PS13 + P(9,10)*PS6 + P(9,11)*PS7 + P(9,12)*PS9 + PS75*dt;
|
||||
nextP(1,9) = P(0,9)*PS11 + P(1,9) + P(2,9)*PS13 - P(3,9)*PS12 - P(9,10)*PS34 + P(9,11)*PS9 - P(9,12)*PS7 + PS101*dt;
|
||||
nextP(2,9) = P(0,9)*PS12 - P(1,9)*PS13 + P(2,9) + P(3,9)*PS11 - P(9,10)*PS9 - P(9,11)*PS34 + P(9,12)*PS6 + PS122*dt;
|
||||
nextP(3,9) = P(0,9)*PS13 + P(1,9)*PS12 - P(2,9)*PS11 + P(3,9) + P(9,10)*PS7 - P(9,11)*PS6 - P(9,12)*PS34 + PS138*dt;
|
||||
nextP(4,9) = P(0,9)*PS72 + P(1,9)*PS62 + P(2,9)*PS60 - P(3,9)*PS74 + P(4,9) - P(9,13)*PS44 + P(9,14)*PS140 - P(9,15)*PS139 + PS168*dt;
|
||||
nextP(5,9) = P(0,9)*PS74 - P(1,9)*PS60 + P(2,9)*PS62 + P(3,9)*PS72 + P(5,9) - P(9,13)*PS162 - P(9,14)*PS65 + P(9,15)*PS160 + PS182*dt;
|
||||
nextP(6,9) = P(0,9)*PS60 + P(1,9)*PS74 - P(2,9)*PS72 + P(3,9)*PS62 + P(6,9) + P(9,13)*PS166 - P(9,14)*PS165 - P(9,15)*PS70 + PS186*dt;
|
||||
nextP(7,9) = P(4,9)*dt + P(7,9) + dt*(P(4,6)*dt + P(6,7));
|
||||
nextP(8,9) = P(5,9)*dt + P(8,9) + dt*(P(5,6)*dt + P(6,8));
|
||||
nextP(9,9) = P(6,9)*dt + P(9,9) + dt*(P(6,6)*dt + P(6,9));
|
||||
nextP(0,10) = PS14;
|
||||
nextP(1,10) = PS85;
|
||||
nextP(2,10) = PS109;
|
||||
nextP(3,10) = PS123;
|
||||
nextP(4,10) = P(0,10)*PS72 + P(1,10)*PS62 - P(10,13)*PS44 + P(10,14)*PS140 - P(10,15)*PS139 + P(2,10)*PS60 - P(3,10)*PS74 + P(4,10);
|
||||
nextP(5,10) = P(0,10)*PS74 - P(1,10)*PS60 - P(10,13)*PS162 - P(10,14)*PS65 + P(10,15)*PS160 + P(2,10)*PS62 + P(3,10)*PS72 + P(5,10);
|
||||
nextP(6,10) = P(0,10)*PS60 + P(1,10)*PS74 + P(10,13)*PS166 - P(10,14)*PS165 - P(10,15)*PS70 - P(2,10)*PS72 + P(3,10)*PS62 + P(6,10);
|
||||
nextP(7,10) = P(4,10)*dt + P(7,10);
|
||||
nextP(8,10) = P(5,10)*dt + P(8,10);
|
||||
nextP(9,10) = P(6,10)*dt + P(9,10);
|
||||
nextP(10,10) = P(10,10);
|
||||
nextP(0,11) = PS17;
|
||||
nextP(1,11) = PS77;
|
||||
nextP(2,11) = PS108;
|
||||
nextP(3,11) = PS127;
|
||||
nextP(4,11) = P(0,11)*PS72 + P(1,11)*PS62 - P(11,13)*PS44 + P(11,14)*PS140 - P(11,15)*PS139 + P(2,11)*PS60 - P(3,11)*PS74 + P(4,11);
|
||||
nextP(5,11) = P(0,11)*PS74 - P(1,11)*PS60 - P(11,13)*PS162 - P(11,14)*PS65 + P(11,15)*PS160 + P(2,11)*PS62 + P(3,11)*PS72 + P(5,11);
|
||||
nextP(6,11) = P(0,11)*PS60 + P(1,11)*PS74 + P(11,13)*PS166 - P(11,14)*PS165 - P(11,15)*PS70 - P(2,11)*PS72 + P(3,11)*PS62 + P(6,11);
|
||||
nextP(7,11) = P(4,11)*dt + P(7,11);
|
||||
nextP(8,11) = P(5,11)*dt + P(8,11);
|
||||
nextP(9,11) = P(6,11)*dt + P(9,11);
|
||||
nextP(10,11) = P(10,11);
|
||||
nextP(11,11) = P(11,11);
|
||||
nextP(0,12) = PS20;
|
||||
nextP(1,12) = PS87;
|
||||
nextP(2,12) = PS103;
|
||||
nextP(3,12) = PS126;
|
||||
nextP(4,12) = P(0,12)*PS72 + P(1,12)*PS62 - P(12,13)*PS44 + P(12,14)*PS140 - P(12,15)*PS139 + P(2,12)*PS60 - P(3,12)*PS74 + P(4,12);
|
||||
nextP(5,12) = P(0,12)*PS74 - P(1,12)*PS60 - P(12,13)*PS162 - P(12,14)*PS65 + P(12,15)*PS160 + P(2,12)*PS62 + P(3,12)*PS72 + P(5,12);
|
||||
nextP(6,12) = P(0,12)*PS60 + P(1,12)*PS74 + P(12,13)*PS166 - P(12,14)*PS165 - P(12,15)*PS70 - P(2,12)*PS72 + P(3,12)*PS62 + P(6,12);
|
||||
nextP(7,12) = P(4,12)*dt + P(7,12);
|
||||
nextP(8,12) = P(5,12)*dt + P(8,12);
|
||||
nextP(9,12) = P(6,12)*dt + P(9,12);
|
||||
nextP(10,12) = P(10,12);
|
||||
nextP(11,12) = P(11,12);
|
||||
nextP(12,12) = P(12,12);
|
||||
nextP(0,13) = PS45;
|
||||
nextP(1,13) = PS93;
|
||||
nextP(2,13) = PS114;
|
||||
nextP(3,13) = PS130;
|
||||
nextP(4,13) = PS141;
|
||||
nextP(5,13) = PS170;
|
||||
nextP(6,13) = PS185;
|
||||
nextP(7,13) = P(4,13)*dt + P(7,13);
|
||||
nextP(8,13) = P(5,13)*dt + P(8,13);
|
||||
nextP(9,13) = P(6,13)*dt + P(9,13);
|
||||
nextP(10,13) = P(10,13);
|
||||
nextP(11,13) = P(11,13);
|
||||
nextP(12,13) = P(12,13);
|
||||
nextP(13,13) = P(13,13);
|
||||
nextP(0,14) = PS55;
|
||||
nextP(1,14) = PS96;
|
||||
nextP(2,14) = PS117;
|
||||
nextP(3,14) = PS133;
|
||||
nextP(4,14) = PS146;
|
||||
nextP(5,14) = PS169;
|
||||
nextP(6,14) = PS184;
|
||||
nextP(7,14) = P(4,14)*dt + P(7,14);
|
||||
nextP(8,14) = P(5,14)*dt + P(8,14);
|
||||
nextP(9,14) = P(6,14)*dt + P(9,14);
|
||||
nextP(10,14) = P(10,14);
|
||||
nextP(11,14) = P(11,14);
|
||||
nextP(12,14) = P(12,14);
|
||||
nextP(13,14) = P(13,14);
|
||||
nextP(14,14) = P(14,14);
|
||||
nextP(0,15) = PS47;
|
||||
nextP(1,15) = PS94;
|
||||
nextP(2,15) = PS115;
|
||||
nextP(3,15) = PS131;
|
||||
nextP(4,15) = PS142;
|
||||
nextP(5,15) = PS173;
|
||||
nextP(6,15) = PS183;
|
||||
nextP(7,15) = P(4,15)*dt + P(7,15);
|
||||
nextP(8,15) = P(5,15)*dt + P(8,15);
|
||||
nextP(9,15) = P(6,15)*dt + P(9,15);
|
||||
nextP(10,15) = P(10,15);
|
||||
nextP(11,15) = P(11,15);
|
||||
nextP(12,15) = P(12,15);
|
||||
nextP(13,15) = P(13,15);
|
||||
nextP(14,15) = P(14,15);
|
||||
nextP(15,15) = P(15,15);
|
||||
nextP(0,16) = P(0,16) - P(1,16)*PS11 + P(10,16)*PS6 + P(11,16)*PS7 + P(12,16)*PS9 - P(2,16)*PS12 - P(3,16)*PS13;
|
||||
nextP(1,16) = P(0,16)*PS11 + P(1,16) - P(10,16)*PS34 + P(11,16)*PS9 - P(12,16)*PS7 + P(2,16)*PS13 - P(3,16)*PS12;
|
||||
nextP(2,16) = P(0,16)*PS12 - P(1,16)*PS13 - P(10,16)*PS9 - P(11,16)*PS34 + P(12,16)*PS6 + P(2,16) + P(3,16)*PS11;
|
||||
nextP(3,16) = P(0,16)*PS13 + P(1,16)*PS12 + P(10,16)*PS7 - P(11,16)*PS6 - P(12,16)*PS34 - P(2,16)*PS11 + P(3,16);
|
||||
nextP(4,16) = P(0,16)*PS72 + P(1,16)*PS62 - P(13,16)*PS44 + P(14,16)*PS140 - P(15,16)*PS139 + P(2,16)*PS60 - P(3,16)*PS74 + P(4,16);
|
||||
nextP(5,16) = P(0,16)*PS74 - P(1,16)*PS60 - P(13,16)*PS162 - P(14,16)*PS65 + P(15,16)*PS160 + P(2,16)*PS62 + P(3,16)*PS72 + P(5,16);
|
||||
nextP(6,16) = P(0,16)*PS60 + P(1,16)*PS74 + P(13,16)*PS166 - P(14,16)*PS165 - P(15,16)*PS70 - P(2,16)*PS72 + P(3,16)*PS62 + P(6,16);
|
||||
nextP(7,16) = P(4,16)*dt + P(7,16);
|
||||
nextP(8,16) = P(5,16)*dt + P(8,16);
|
||||
nextP(9,16) = P(6,16)*dt + P(9,16);
|
||||
nextP(10,16) = P(10,16);
|
||||
nextP(11,16) = P(11,16);
|
||||
nextP(12,16) = P(12,16);
|
||||
nextP(13,16) = P(13,16);
|
||||
nextP(14,16) = P(14,16);
|
||||
nextP(15,16) = P(15,16);
|
||||
nextP(16,16) = P(16,16);
|
||||
nextP(0,17) = P(0,17) - P(1,17)*PS11 + P(10,17)*PS6 + P(11,17)*PS7 + P(12,17)*PS9 - P(2,17)*PS12 - P(3,17)*PS13;
|
||||
nextP(1,17) = P(0,17)*PS11 + P(1,17) - P(10,17)*PS34 + P(11,17)*PS9 - P(12,17)*PS7 + P(2,17)*PS13 - P(3,17)*PS12;
|
||||
nextP(2,17) = P(0,17)*PS12 - P(1,17)*PS13 - P(10,17)*PS9 - P(11,17)*PS34 + P(12,17)*PS6 + P(2,17) + P(3,17)*PS11;
|
||||
nextP(3,17) = P(0,17)*PS13 + P(1,17)*PS12 + P(10,17)*PS7 - P(11,17)*PS6 - P(12,17)*PS34 - P(2,17)*PS11 + P(3,17);
|
||||
nextP(4,17) = P(0,17)*PS72 + P(1,17)*PS62 - P(13,17)*PS44 + P(14,17)*PS140 - P(15,17)*PS139 + P(2,17)*PS60 - P(3,17)*PS74 + P(4,17);
|
||||
nextP(5,17) = P(0,17)*PS74 - P(1,17)*PS60 - P(13,17)*PS162 - P(14,17)*PS65 + P(15,17)*PS160 + P(2,17)*PS62 + P(3,17)*PS72 + P(5,17);
|
||||
nextP(6,17) = P(0,17)*PS60 + P(1,17)*PS74 + P(13,17)*PS166 - P(14,17)*PS165 - P(15,17)*PS70 - P(2,17)*PS72 + P(3,17)*PS62 + P(6,17);
|
||||
nextP(7,17) = P(4,17)*dt + P(7,17);
|
||||
nextP(8,17) = P(5,17)*dt + P(8,17);
|
||||
nextP(9,17) = P(6,17)*dt + P(9,17);
|
||||
nextP(10,17) = P(10,17);
|
||||
nextP(11,17) = P(11,17);
|
||||
nextP(12,17) = P(12,17);
|
||||
nextP(13,17) = P(13,17);
|
||||
nextP(14,17) = P(14,17);
|
||||
nextP(15,17) = P(15,17);
|
||||
nextP(16,17) = P(16,17);
|
||||
nextP(17,17) = P(17,17);
|
||||
nextP(0,18) = P(0,18) - P(1,18)*PS11 + P(10,18)*PS6 + P(11,18)*PS7 + P(12,18)*PS9 - P(2,18)*PS12 - P(3,18)*PS13;
|
||||
nextP(1,18) = P(0,18)*PS11 + P(1,18) - P(10,18)*PS34 + P(11,18)*PS9 - P(12,18)*PS7 + P(2,18)*PS13 - P(3,18)*PS12;
|
||||
nextP(2,18) = P(0,18)*PS12 - P(1,18)*PS13 - P(10,18)*PS9 - P(11,18)*PS34 + P(12,18)*PS6 + P(2,18) + P(3,18)*PS11;
|
||||
nextP(3,18) = P(0,18)*PS13 + P(1,18)*PS12 + P(10,18)*PS7 - P(11,18)*PS6 - P(12,18)*PS34 - P(2,18)*PS11 + P(3,18);
|
||||
nextP(4,18) = P(0,18)*PS72 + P(1,18)*PS62 - P(13,18)*PS44 + P(14,18)*PS140 - P(15,18)*PS139 + P(2,18)*PS60 - P(3,18)*PS74 + P(4,18);
|
||||
nextP(5,18) = P(0,18)*PS74 - P(1,18)*PS60 - P(13,18)*PS162 - P(14,18)*PS65 + P(15,18)*PS160 + P(2,18)*PS62 + P(3,18)*PS72 + P(5,18);
|
||||
nextP(6,18) = P(0,18)*PS60 + P(1,18)*PS74 + P(13,18)*PS166 - P(14,18)*PS165 - P(15,18)*PS70 - P(2,18)*PS72 + P(3,18)*PS62 + P(6,18);
|
||||
nextP(7,18) = P(4,18)*dt + P(7,18);
|
||||
nextP(8,18) = P(5,18)*dt + P(8,18);
|
||||
nextP(9,18) = P(6,18)*dt + P(9,18);
|
||||
nextP(10,18) = P(10,18);
|
||||
nextP(11,18) = P(11,18);
|
||||
nextP(12,18) = P(12,18);
|
||||
nextP(13,18) = P(13,18);
|
||||
nextP(14,18) = P(14,18);
|
||||
nextP(15,18) = P(15,18);
|
||||
nextP(16,18) = P(16,18);
|
||||
nextP(17,18) = P(17,18);
|
||||
nextP(18,18) = P(18,18);
|
||||
nextP(0,19) = P(0,19) - P(1,19)*PS11 + P(10,19)*PS6 + P(11,19)*PS7 + P(12,19)*PS9 - P(2,19)*PS12 - P(3,19)*PS13;
|
||||
nextP(1,19) = P(0,19)*PS11 + P(1,19) - P(10,19)*PS34 + P(11,19)*PS9 - P(12,19)*PS7 + P(2,19)*PS13 - P(3,19)*PS12;
|
||||
nextP(2,19) = P(0,19)*PS12 - P(1,19)*PS13 - P(10,19)*PS9 - P(11,19)*PS34 + P(12,19)*PS6 + P(2,19) + P(3,19)*PS11;
|
||||
nextP(3,19) = P(0,19)*PS13 + P(1,19)*PS12 + P(10,19)*PS7 - P(11,19)*PS6 - P(12,19)*PS34 - P(2,19)*PS11 + P(3,19);
|
||||
nextP(4,19) = P(0,19)*PS72 + P(1,19)*PS62 - P(13,19)*PS44 + P(14,19)*PS140 - P(15,19)*PS139 + P(2,19)*PS60 - P(3,19)*PS74 + P(4,19);
|
||||
nextP(5,19) = P(0,19)*PS74 - P(1,19)*PS60 - P(13,19)*PS162 - P(14,19)*PS65 + P(15,19)*PS160 + P(2,19)*PS62 + P(3,19)*PS72 + P(5,19);
|
||||
nextP(6,19) = P(0,19)*PS60 + P(1,19)*PS74 + P(13,19)*PS166 - P(14,19)*PS165 - P(15,19)*PS70 - P(2,19)*PS72 + P(3,19)*PS62 + P(6,19);
|
||||
nextP(7,19) = P(4,19)*dt + P(7,19);
|
||||
nextP(8,19) = P(5,19)*dt + P(8,19);
|
||||
nextP(9,19) = P(6,19)*dt + P(9,19);
|
||||
nextP(10,19) = P(10,19);
|
||||
nextP(11,19) = P(11,19);
|
||||
nextP(12,19) = P(12,19);
|
||||
nextP(13,19) = P(13,19);
|
||||
nextP(14,19) = P(14,19);
|
||||
nextP(15,19) = P(15,19);
|
||||
nextP(16,19) = P(16,19);
|
||||
nextP(17,19) = P(17,19);
|
||||
nextP(18,19) = P(18,19);
|
||||
nextP(19,19) = P(19,19);
|
||||
nextP(0,20) = P(0,20) - P(1,20)*PS11 + P(10,20)*PS6 + P(11,20)*PS7 + P(12,20)*PS9 - P(2,20)*PS12 - P(3,20)*PS13;
|
||||
nextP(1,20) = P(0,20)*PS11 + P(1,20) - P(10,20)*PS34 + P(11,20)*PS9 - P(12,20)*PS7 + P(2,20)*PS13 - P(3,20)*PS12;
|
||||
nextP(2,20) = P(0,20)*PS12 - P(1,20)*PS13 - P(10,20)*PS9 - P(11,20)*PS34 + P(12,20)*PS6 + P(2,20) + P(3,20)*PS11;
|
||||
nextP(3,20) = P(0,20)*PS13 + P(1,20)*PS12 + P(10,20)*PS7 - P(11,20)*PS6 - P(12,20)*PS34 - P(2,20)*PS11 + P(3,20);
|
||||
nextP(4,20) = P(0,20)*PS72 + P(1,20)*PS62 - P(13,20)*PS44 + P(14,20)*PS140 - P(15,20)*PS139 + P(2,20)*PS60 - P(3,20)*PS74 + P(4,20);
|
||||
nextP(5,20) = P(0,20)*PS74 - P(1,20)*PS60 - P(13,20)*PS162 - P(14,20)*PS65 + P(15,20)*PS160 + P(2,20)*PS62 + P(3,20)*PS72 + P(5,20);
|
||||
nextP(6,20) = P(0,20)*PS60 + P(1,20)*PS74 + P(13,20)*PS166 - P(14,20)*PS165 - P(15,20)*PS70 - P(2,20)*PS72 + P(3,20)*PS62 + P(6,20);
|
||||
nextP(7,20) = P(4,20)*dt + P(7,20);
|
||||
nextP(8,20) = P(5,20)*dt + P(8,20);
|
||||
nextP(9,20) = P(6,20)*dt + P(9,20);
|
||||
nextP(10,20) = P(10,20);
|
||||
nextP(11,20) = P(11,20);
|
||||
nextP(12,20) = P(12,20);
|
||||
nextP(13,20) = P(13,20);
|
||||
nextP(14,20) = P(14,20);
|
||||
nextP(15,20) = P(15,20);
|
||||
nextP(16,20) = P(16,20);
|
||||
nextP(17,20) = P(17,20);
|
||||
nextP(18,20) = P(18,20);
|
||||
nextP(19,20) = P(19,20);
|
||||
nextP(20,20) = P(20,20);
|
||||
nextP(0,21) = P(0,21) - P(1,21)*PS11 + P(10,21)*PS6 + P(11,21)*PS7 + P(12,21)*PS9 - P(2,21)*PS12 - P(3,21)*PS13;
|
||||
nextP(1,21) = P(0,21)*PS11 + P(1,21) - P(10,21)*PS34 + P(11,21)*PS9 - P(12,21)*PS7 + P(2,21)*PS13 - P(3,21)*PS12;
|
||||
nextP(2,21) = P(0,21)*PS12 - P(1,21)*PS13 - P(10,21)*PS9 - P(11,21)*PS34 + P(12,21)*PS6 + P(2,21) + P(3,21)*PS11;
|
||||
nextP(3,21) = P(0,21)*PS13 + P(1,21)*PS12 + P(10,21)*PS7 - P(11,21)*PS6 - P(12,21)*PS34 - P(2,21)*PS11 + P(3,21);
|
||||
nextP(4,21) = P(0,21)*PS72 + P(1,21)*PS62 - P(13,21)*PS44 + P(14,21)*PS140 - P(15,21)*PS139 + P(2,21)*PS60 - P(3,21)*PS74 + P(4,21);
|
||||
nextP(5,21) = P(0,21)*PS74 - P(1,21)*PS60 - P(13,21)*PS162 - P(14,21)*PS65 + P(15,21)*PS160 + P(2,21)*PS62 + P(3,21)*PS72 + P(5,21);
|
||||
nextP(6,21) = P(0,21)*PS60 + P(1,21)*PS74 + P(13,21)*PS166 - P(14,21)*PS165 - P(15,21)*PS70 - P(2,21)*PS72 + P(3,21)*PS62 + P(6,21);
|
||||
nextP(7,21) = P(4,21)*dt + P(7,21);
|
||||
nextP(8,21) = P(5,21)*dt + P(8,21);
|
||||
nextP(9,21) = P(6,21)*dt + P(9,21);
|
||||
nextP(10,21) = P(10,21);
|
||||
nextP(11,21) = P(11,21);
|
||||
nextP(12,21) = P(12,21);
|
||||
nextP(13,21) = P(13,21);
|
||||
nextP(14,21) = P(14,21);
|
||||
nextP(15,21) = P(15,21);
|
||||
nextP(16,21) = P(16,21);
|
||||
nextP(17,21) = P(17,21);
|
||||
nextP(18,21) = P(18,21);
|
||||
nextP(19,21) = P(19,21);
|
||||
nextP(20,21) = P(20,21);
|
||||
nextP(21,21) = P(21,21);
|
||||
nextP(0,22) = P(0,22) - P(1,22)*PS11 + P(10,22)*PS6 + P(11,22)*PS7 + P(12,22)*PS9 - P(2,22)*PS12 - P(3,22)*PS13;
|
||||
nextP(1,22) = P(0,22)*PS11 + P(1,22) - P(10,22)*PS34 + P(11,22)*PS9 - P(12,22)*PS7 + P(2,22)*PS13 - P(3,22)*PS12;
|
||||
nextP(2,22) = P(0,22)*PS12 - P(1,22)*PS13 - P(10,22)*PS9 - P(11,22)*PS34 + P(12,22)*PS6 + P(2,22) + P(3,22)*PS11;
|
||||
nextP(3,22) = P(0,22)*PS13 + P(1,22)*PS12 + P(10,22)*PS7 - P(11,22)*PS6 - P(12,22)*PS34 - P(2,22)*PS11 + P(3,22);
|
||||
nextP(4,22) = P(0,22)*PS72 + P(1,22)*PS62 - P(13,22)*PS44 + P(14,22)*PS140 - P(15,22)*PS139 + P(2,22)*PS60 - P(3,22)*PS74 + P(4,22);
|
||||
nextP(5,22) = P(0,22)*PS74 - P(1,22)*PS60 - P(13,22)*PS162 - P(14,22)*PS65 + P(15,22)*PS160 + P(2,22)*PS62 + P(3,22)*PS72 + P(5,22);
|
||||
nextP(6,22) = P(0,22)*PS60 + P(1,22)*PS74 + P(13,22)*PS166 - P(14,22)*PS165 - P(15,22)*PS70 - P(2,22)*PS72 + P(3,22)*PS62 + P(6,22);
|
||||
nextP(7,22) = P(4,22)*dt + P(7,22);
|
||||
nextP(8,22) = P(5,22)*dt + P(8,22);
|
||||
nextP(9,22) = P(6,22)*dt + P(9,22);
|
||||
nextP(10,22) = P(10,22);
|
||||
nextP(11,22) = P(11,22);
|
||||
nextP(12,22) = P(12,22);
|
||||
nextP(13,22) = P(13,22);
|
||||
nextP(14,22) = P(14,22);
|
||||
nextP(15,22) = P(15,22);
|
||||
nextP(16,22) = P(16,22);
|
||||
nextP(17,22) = P(17,22);
|
||||
nextP(18,22) = P(18,22);
|
||||
nextP(19,22) = P(19,22);
|
||||
nextP(20,22) = P(20,22);
|
||||
nextP(21,22) = P(21,22);
|
||||
nextP(22,22) = P(22,22);
|
||||
nextP(0,23) = P(0,23) - P(1,23)*PS11 + P(10,23)*PS6 + P(11,23)*PS7 + P(12,23)*PS9 - P(2,23)*PS12 - P(3,23)*PS13;
|
||||
nextP(1,23) = P(0,23)*PS11 + P(1,23) - P(10,23)*PS34 + P(11,23)*PS9 - P(12,23)*PS7 + P(2,23)*PS13 - P(3,23)*PS12;
|
||||
nextP(2,23) = P(0,23)*PS12 - P(1,23)*PS13 - P(10,23)*PS9 - P(11,23)*PS34 + P(12,23)*PS6 + P(2,23) + P(3,23)*PS11;
|
||||
nextP(3,23) = P(0,23)*PS13 + P(1,23)*PS12 + P(10,23)*PS7 - P(11,23)*PS6 - P(12,23)*PS34 - P(2,23)*PS11 + P(3,23);
|
||||
nextP(4,23) = P(0,23)*PS72 + P(1,23)*PS62 - P(13,23)*PS44 + P(14,23)*PS140 - P(15,23)*PS139 + P(2,23)*PS60 - P(3,23)*PS74 + P(4,23);
|
||||
nextP(5,23) = P(0,23)*PS74 - P(1,23)*PS60 - P(13,23)*PS162 - P(14,23)*PS65 + P(15,23)*PS160 + P(2,23)*PS62 + P(3,23)*PS72 + P(5,23);
|
||||
nextP(6,23) = P(0,23)*PS60 + P(1,23)*PS74 + P(13,23)*PS166 - P(14,23)*PS165 - P(15,23)*PS70 - P(2,23)*PS72 + P(3,23)*PS62 + P(6,23);
|
||||
nextP(7,23) = P(4,23)*dt + P(7,23);
|
||||
nextP(8,23) = P(5,23)*dt + P(8,23);
|
||||
nextP(9,23) = P(6,23)*dt + P(9,23);
|
||||
nextP(10,23) = P(10,23);
|
||||
nextP(11,23) = P(11,23);
|
||||
nextP(12,23) = P(12,23);
|
||||
nextP(13,23) = P(13,23);
|
||||
nextP(14,23) = P(14,23);
|
||||
nextP(15,23) = P(15,23);
|
||||
nextP(16,23) = P(16,23);
|
||||
nextP(17,23) = P(17,23);
|
||||
nextP(18,23) = P(18,23);
|
||||
nextP(19,23) = P(19,23);
|
||||
nextP(20,23) = P(20,23);
|
||||
nextP(21,23) = P(21,23);
|
||||
nextP(22,23) = P(22,23);
|
||||
nextP(23,23) = P(23,23);
|
||||
|
||||
// save output and repeat calculation using legacy matlab generated code
|
||||
SquareMatrix24f nextP_sympy;
|
||||
for (int col=0; col<=23; col++) {
|
||||
for (int row=0; row<=col; row++) {
|
||||
nextP_sympy(row,col) = nextP(row,col);
|
||||
}
|
||||
}
|
||||
|
||||
// intermediate calculations
|
||||
float SF[21];
|
||||
SF[0] = dvz - dvz_b;
|
||||
SF[1] = dvy - dvy_b;
|
||||
SF[2] = dvx - dvx_b;
|
||||
SF[3] = 2*q1*SF[2] + 2*q2*SF[1] + 2*q3*SF[0];
|
||||
SF[4] = 2*q0*SF[1] - 2*q1*SF[0] + 2*q3*SF[2];
|
||||
SF[5] = 2*q0*SF[2] + 2*q2*SF[0] - 2*q3*SF[1];
|
||||
SF[6] = day*0.5f - day_b*0.5f;
|
||||
SF[7] = daz*0.5f - daz_b*0.5f;
|
||||
SF[8] = dax*0.5f - dax_b*0.5f;
|
||||
SF[9] = dax_b*0.5f - dax*0.5f;
|
||||
SF[10] = daz_b*0.5f - daz*0.5f;
|
||||
SF[11] = day_b*0.5f - day*0.5f;
|
||||
SF[12] = 2*q1*SF[1];
|
||||
SF[13] = 2*q0*SF[0];
|
||||
SF[14] = q1*0.5f;
|
||||
SF[15] = q2*0.5f;
|
||||
SF[16] = q3*0.5f;
|
||||
SF[17] = sq(q3);
|
||||
SF[18] = sq(q2);
|
||||
SF[19] = sq(q1);
|
||||
SF[20] = sq(q0);
|
||||
|
||||
float SG[8];
|
||||
SG[0] = q0*0.5f;
|
||||
SG[1] = sq(q3);
|
||||
SG[2] = sq(q2);
|
||||
SG[3] = sq(q1);
|
||||
SG[4] = sq(q0);
|
||||
SG[5] = 2*q2*q3;
|
||||
SG[6] = 2*q1*q3;
|
||||
SG[7] = 2*q1*q2;
|
||||
|
||||
float SQ[11];
|
||||
SQ[0] = dvzVar*(SG[5] - 2*q0*q1)*(SG[1] - SG[2] - SG[3] + SG[4]) - dvyVar*(SG[5] + 2*q0*q1)*(SG[1] - SG[2] + SG[3] - SG[4]) + dvxVar*(SG[6] - 2*q0*q2)*(SG[7] + 2*q0*q3);
|
||||
SQ[1] = dvzVar*(SG[6] + 2*q0*q2)*(SG[1] - SG[2] - SG[3] + SG[4]) - dvxVar*(SG[6] - 2*q0*q2)*(SG[1] + SG[2] - SG[3] - SG[4]) + dvyVar*(SG[5] + 2*q0*q1)*(SG[7] - 2*q0*q3);
|
||||
SQ[2] = dvzVar*(SG[5] - 2*q0*q1)*(SG[6] + 2*q0*q2) - dvyVar*(SG[7] - 2*q0*q3)*(SG[1] - SG[2] + SG[3] - SG[4]) - dvxVar*(SG[7] + 2*q0*q3)*(SG[1] + SG[2] - SG[3] - SG[4]);
|
||||
SQ[3] = (dayVar*q1*SG[0])*0.5f - (dazVar*q1*SG[0])*0.5f - (daxVar*q2*q3)*0.25f;
|
||||
SQ[4] = (dazVar*q2*SG[0])*0.5f - (daxVar*q2*SG[0])*0.5f - (dayVar*q1*q3)*0.25f;
|
||||
SQ[5] = (daxVar*q3*SG[0])*0.5f - (dayVar*q3*SG[0])*0.5f - (dazVar*q1*q2)*0.25f;
|
||||
SQ[6] = (daxVar*q1*q2)*0.25f - (dazVar*q3*SG[0])*0.5f - (dayVar*q1*q2)*0.25f;
|
||||
SQ[7] = (dazVar*q1*q3)*0.25f - (daxVar*q1*q3)*0.25f - (dayVar*q2*SG[0])*0.5f;
|
||||
SQ[8] = (dayVar*q2*q3)*0.25f - (daxVar*q1*SG[0])*0.5f - (dazVar*q2*q3)*0.25f;
|
||||
SQ[9] = sq(SG[0]);
|
||||
SQ[10] = sq(q1);
|
||||
|
||||
float SPP[11];
|
||||
SPP[0] = SF[12] + SF[13] - 2*q2*SF[2];
|
||||
SPP[1] = SF[17] - SF[18] - SF[19] + SF[20];
|
||||
SPP[2] = SF[17] - SF[18] + SF[19] - SF[20];
|
||||
SPP[3] = SF[17] + SF[18] - SF[19] - SF[20];
|
||||
SPP[4] = 2*q0*q2 - 2*q1*q3;
|
||||
SPP[5] = 2*q0*q1 - 2*q2*q3;
|
||||
SPP[6] = 2*q0*q3 - 2*q1*q2;
|
||||
SPP[7] = 2*q0*q1 + 2*q2*q3;
|
||||
SPP[8] = 2*q0*q3 + 2*q1*q2;
|
||||
SPP[9] = 2*q0*q2 + 2*q1*q3;
|
||||
SPP[10] = SF[16];
|
||||
|
||||
// calculate variances and upper diagonal covariances for quaternion, velocity, position and gyro bias states
|
||||
nextP(0,0) = P(0,0) + P(1,0)*SF[9] + P(2,0)*SF[11] + P(3,0)*SF[10] + P(10,0)*SF[14] + P(11,0)*SF[15] + P(12,0)*SPP[10] + (daxVar*SQ[10])*0.25f + SF[9]*(P(0,1) + P(1,1)*SF[9] + P(2,1)*SF[11] + P(3,1)*SF[10] + P(10,1)*SF[14] + P(11,1)*SF[15] + P(12,1)*SPP[10]) + SF[11]*(P(0,2) + P(1,2)*SF[9] + P(2,2)*SF[11] + P(3,2)*SF[10] + P(10,2)*SF[14] + P(11,2)*SF[15] + P(12,2)*SPP[10]) + SF[10]*(P(0,3) + P(1,3)*SF[9] + P(2,3)*SF[11] + P(3,3)*SF[10] + P(10,3)*SF[14] + P(11,3)*SF[15] + P(12,3)*SPP[10]) + SF[14]*(P(0,10) + P(1,10)*SF[9] + P(2,10)*SF[11] + P(3,10)*SF[10] + P(10,10)*SF[14] + P(11,10)*SF[15] + P(12,10)*SPP[10]) + SF[15]*(P(0,11) + P(1,11)*SF[9] + P(2,11)*SF[11] + P(3,11)*SF[10] + P(10,11)*SF[14] + P(11,11)*SF[15] + P(12,11)*SPP[10]) + SPP[10]*(P(0,12) + P(1,12)*SF[9] + P(2,12)*SF[11] + P(3,12)*SF[10] + P(10,12)*SF[14] + P(11,12)*SF[15] + P(12,12)*SPP[10]) + (dayVar*sq(q2))*0.25f + (dazVar*sq(q3))*0.25f;
|
||||
nextP(0,1) = P(0,1) + SQ[8] + P(1,1)*SF[9] + P(2,1)*SF[11] + P(3,1)*SF[10] + P(10,1)*SF[14] + P(11,1)*SF[15] + P(12,1)*SPP[10] + SF[8]*(P(0,0) + P(1,0)*SF[9] + P(2,0)*SF[11] + P(3,0)*SF[10] + P(10,0)*SF[14] + P(11,0)*SF[15] + P(12,0)*SPP[10]) + SF[7]*(P(0,2) + P(1,2)*SF[9] + P(2,2)*SF[11] + P(3,2)*SF[10] + P(10,2)*SF[14] + P(11,2)*SF[15] + P(12,2)*SPP[10]) + SF[11]*(P(0,3) + P(1,3)*SF[9] + P(2,3)*SF[11] + P(3,3)*SF[10] + P(10,3)*SF[14] + P(11,3)*SF[15] + P(12,3)*SPP[10]) - SF[15]*(P(0,12) + P(1,12)*SF[9] + P(2,12)*SF[11] + P(3,12)*SF[10] + P(10,12)*SF[14] + P(11,12)*SF[15] + P(12,12)*SPP[10]) + SPP[10]*(P(0,11) + P(1,11)*SF[9] + P(2,11)*SF[11] + P(3,11)*SF[10] + P(10,11)*SF[14] + P(11,11)*SF[15] + P(12,11)*SPP[10]) - (q0*(P(0,10) + P(1,10)*SF[9] + P(2,10)*SF[11] + P(3,10)*SF[10] + P(10,10)*SF[14] + P(11,10)*SF[15] + P(12,10)*SPP[10]))*0.5f;
|
||||
nextP(1,1) = P(1,1) + P(0,1)*SF[8] + P(2,1)*SF[7] + P(3,1)*SF[11] - P(12,1)*SF[15] + P(11,1)*SPP[10] + daxVar*SQ[9] - (P(10,1)*q0)*0.5f + SF[8]*(P(1,0) + P(0,0)*SF[8] + P(2,0)*SF[7] + P(3,0)*SF[11] - P(12,0)*SF[15] + P(11,0)*SPP[10] - (P(10,0)*q0)*0.5f) + SF[7]*(P(1,2) + P(0,2)*SF[8] + P(2,2)*SF[7] + P(3,2)*SF[11] - P(12,2)*SF[15] + P(11,2)*SPP[10] - (P(10,2)*q0)*0.5f) + SF[11]*(P(1,3) + P(0,3)*SF[8] + P(2,3)*SF[7] + P(3,3)*SF[11] - P(12,3)*SF[15] + P(11,3)*SPP[10] - (P(10,3)*q0)*0.5f) - SF[15]*(P(1,12) + P(0,12)*SF[8] + P(2,12)*SF[7] + P(3,12)*SF[11] - P(12,12)*SF[15] + P(11,12)*SPP[10] - (P(10,12)*q0)*0.5f) + SPP[10]*(P(1,11) + P(0,11)*SF[8] + P(2,11)*SF[7] + P(3,11)*SF[11] - P(12,11)*SF[15] + P(11,11)*SPP[10] - (P(10,11)*q0)*0.5f) + (dayVar*sq(q3))*0.25f + (dazVar*sq(q2))*0.25f - (q0*(P(1,10) + P(0,10)*SF[8] + P(2,10)*SF[7] + P(3,10)*SF[11] - P(12,10)*SF[15] + P(11,10)*SPP[10] - (P(10,10)*q0)*0.5f))*0.5f;
|
||||
nextP(0,2) = P(0,2) + SQ[7] + P(1,2)*SF[9] + P(2,2)*SF[11] + P(3,2)*SF[10] + P(10,2)*SF[14] + P(11,2)*SF[15] + P(12,2)*SPP[10] + SF[6]*(P(0,0) + P(1,0)*SF[9] + P(2,0)*SF[11] + P(3,0)*SF[10] + P(10,0)*SF[14] + P(11,0)*SF[15] + P(12,0)*SPP[10]) + SF[10]*(P(0,1) + P(1,1)*SF[9] + P(2,1)*SF[11] + P(3,1)*SF[10] + P(10,1)*SF[14] + P(11,1)*SF[15] + P(12,1)*SPP[10]) + SF[8]*(P(0,3) + P(1,3)*SF[9] + P(2,3)*SF[11] + P(3,3)*SF[10] + P(10,3)*SF[14] + P(11,3)*SF[15] + P(12,3)*SPP[10]) + SF[14]*(P(0,12) + P(1,12)*SF[9] + P(2,12)*SF[11] + P(3,12)*SF[10] + P(10,12)*SF[14] + P(11,12)*SF[15] + P(12,12)*SPP[10]) - SPP[10]*(P(0,10) + P(1,10)*SF[9] + P(2,10)*SF[11] + P(3,10)*SF[10] + P(10,10)*SF[14] + P(11,10)*SF[15] + P(12,10)*SPP[10]) - (q0*(P(0,11) + P(1,11)*SF[9] + P(2,11)*SF[11] + P(3,11)*SF[10] + P(10,11)*SF[14] + P(11,11)*SF[15] + P(12,11)*SPP[10]))*0.5f;
|
||||
nextP(1,2) = P(1,2) + SQ[5] + P(0,2)*SF[8] + P(2,2)*SF[7] + P(3,2)*SF[11] - P(12,2)*SF[15] + P(11,2)*SPP[10] - (P(10,2)*q0)*0.5f + SF[6]*(P(1,0) + P(0,0)*SF[8] + P(2,0)*SF[7] + P(3,0)*SF[11] - P(12,0)*SF[15] + P(11,0)*SPP[10] - (P(10,0)*q0)*0.5f) + SF[10]*(P(1,1) + P(0,1)*SF[8] + P(2,1)*SF[7] + P(3,1)*SF[11] - P(12,1)*SF[15] + P(11,1)*SPP[10] - (P(10,1)*q0)*0.5f) + SF[8]*(P(1,3) + P(0,3)*SF[8] + P(2,3)*SF[7] + P(3,3)*SF[11] - P(12,3)*SF[15] + P(11,3)*SPP[10] - (P(10,3)*q0)*0.5f) + SF[14]*(P(1,12) + P(0,12)*SF[8] + P(2,12)*SF[7] + P(3,12)*SF[11] - P(12,12)*SF[15] + P(11,12)*SPP[10] - (P(10,12)*q0)*0.5f) - SPP[10]*(P(1,10) + P(0,10)*SF[8] + P(2,10)*SF[7] + P(3,10)*SF[11] - P(12,10)*SF[15] + P(11,10)*SPP[10] - (P(10,10)*q0)*0.5f) - (q0*(P(1,11) + P(0,11)*SF[8] + P(2,11)*SF[7] + P(3,11)*SF[11] - P(12,11)*SF[15] + P(11,11)*SPP[10] - (P(10,11)*q0)*0.5f))*0.5f;
|
||||
nextP(2,2) = P(2,2) + P(0,2)*SF[6] + P(1,2)*SF[10] + P(3,2)*SF[8] + P(12,2)*SF[14] - P(10,2)*SPP[10] + dayVar*SQ[9] + (dazVar*SQ[10])*0.25f - (P(11,2)*q0)*0.5f + SF[6]*(P(2,0) + P(0,0)*SF[6] + P(1,0)*SF[10] + P(3,0)*SF[8] + P(12,0)*SF[14] - P(10,0)*SPP[10] - (P(11,0)*q0)*0.5f) + SF[10]*(P(2,1) + P(0,1)*SF[6] + P(1,1)*SF[10] + P(3,1)*SF[8] + P(12,1)*SF[14] - P(10,1)*SPP[10] - (P(11,1)*q0)*0.5f) + SF[8]*(P(2,3) + P(0,3)*SF[6] + P(1,3)*SF[10] + P(3,3)*SF[8] + P(12,3)*SF[14] - P(10,3)*SPP[10] - (P(11,3)*q0)*0.5f) + SF[14]*(P(2,12) + P(0,12)*SF[6] + P(1,12)*SF[10] + P(3,12)*SF[8] + P(12,12)*SF[14] - P(10,12)*SPP[10] - (P(11,12)*q0)*0.5f) - SPP[10]*(P(2,10) + P(0,10)*SF[6] + P(1,10)*SF[10] + P(3,10)*SF[8] + P(12,10)*SF[14] - P(10,10)*SPP[10] - (P(11,10)*q0)*0.5f) + (daxVar*sq(q3))*0.25f - (q0*(P(2,11) + P(0,11)*SF[6] + P(1,11)*SF[10] + P(3,11)*SF[8] + P(12,11)*SF[14] - P(10,11)*SPP[10] - (P(11,11)*q0)*0.5f))*0.5f;
|
||||
nextP(0,3) = P(0,3) + SQ[6] + P(1,3)*SF[9] + P(2,3)*SF[11] + P(3,3)*SF[10] + P(10,3)*SF[14] + P(11,3)*SF[15] + P(12,3)*SPP[10] + SF[7]*(P(0,0) + P(1,0)*SF[9] + P(2,0)*SF[11] + P(3,0)*SF[10] + P(10,0)*SF[14] + P(11,0)*SF[15] + P(12,0)*SPP[10]) + SF[6]*(P(0,1) + P(1,1)*SF[9] + P(2,1)*SF[11] + P(3,1)*SF[10] + P(10,1)*SF[14] + P(11,1)*SF[15] + P(12,1)*SPP[10]) + SF[9]*(P(0,2) + P(1,2)*SF[9] + P(2,2)*SF[11] + P(3,2)*SF[10] + P(10,2)*SF[14] + P(11,2)*SF[15] + P(12,2)*SPP[10]) + SF[15]*(P(0,10) + P(1,10)*SF[9] + P(2,10)*SF[11] + P(3,10)*SF[10] + P(10,10)*SF[14] + P(11,10)*SF[15] + P(12,10)*SPP[10]) - SF[14]*(P(0,11) + P(1,11)*SF[9] + P(2,11)*SF[11] + P(3,11)*SF[10] + P(10,11)*SF[14] + P(11,11)*SF[15] + P(12,11)*SPP[10]) - (q0*(P(0,12) + P(1,12)*SF[9] + P(2,12)*SF[11] + P(3,12)*SF[10] + P(10,12)*SF[14] + P(11,12)*SF[15] + P(12,12)*SPP[10]))*0.5f;
|
||||
nextP(1,3) = P(1,3) + SQ[4] + P(0,3)*SF[8] + P(2,3)*SF[7] + P(3,3)*SF[11] - P(12,3)*SF[15] + P(11,3)*SPP[10] - (P(10,3)*q0)*0.5f + SF[7]*(P(1,0) + P(0,0)*SF[8] + P(2,0)*SF[7] + P(3,0)*SF[11] - P(12,0)*SF[15] + P(11,0)*SPP[10] - (P(10,0)*q0)*0.5f) + SF[6]*(P(1,1) + P(0,1)*SF[8] + P(2,1)*SF[7] + P(3,1)*SF[11] - P(12,1)*SF[15] + P(11,1)*SPP[10] - (P(10,1)*q0)*0.5f) + SF[9]*(P(1,2) + P(0,2)*SF[8] + P(2,2)*SF[7] + P(3,2)*SF[11] - P(12,2)*SF[15] + P(11,2)*SPP[10] - (P(10,2)*q0)*0.5f) + SF[15]*(P(1,10) + P(0,10)*SF[8] + P(2,10)*SF[7] + P(3,10)*SF[11] - P(12,10)*SF[15] + P(11,10)*SPP[10] - (P(10,10)*q0)*0.5f) - SF[14]*(P(1,11) + P(0,11)*SF[8] + P(2,11)*SF[7] + P(3,11)*SF[11] - P(12,11)*SF[15] + P(11,11)*SPP[10] - (P(10,11)*q0)*0.5f) - (q0*(P(1,12) + P(0,12)*SF[8] + P(2,12)*SF[7] + P(3,12)*SF[11] - P(12,12)*SF[15] + P(11,12)*SPP[10] - (P(10,12)*q0)*0.5f))*0.5f;
|
||||
nextP(2,3) = P(2,3) + SQ[3] + P(0,3)*SF[6] + P(1,3)*SF[10] + P(3,3)*SF[8] + P(12,3)*SF[14] - P(10,3)*SPP[10] - (P(11,3)*q0)*0.5f + SF[7]*(P(2,0) + P(0,0)*SF[6] + P(1,0)*SF[10] + P(3,0)*SF[8] + P(12,0)*SF[14] - P(10,0)*SPP[10] - (P(11,0)*q0)*0.5f) + SF[6]*(P(2,1) + P(0,1)*SF[6] + P(1,1)*SF[10] + P(3,1)*SF[8] + P(12,1)*SF[14] - P(10,1)*SPP[10] - (P(11,1)*q0)*0.5f) + SF[9]*(P(2,2) + P(0,2)*SF[6] + P(1,2)*SF[10] + P(3,2)*SF[8] + P(12,2)*SF[14] - P(10,2)*SPP[10] - (P(11,2)*q0)*0.5f) + SF[15]*(P(2,10) + P(0,10)*SF[6] + P(1,10)*SF[10] + P(3,10)*SF[8] + P(12,10)*SF[14] - P(10,10)*SPP[10] - (P(11,10)*q0)*0.5f) - SF[14]*(P(2,11) + P(0,11)*SF[6] + P(1,11)*SF[10] + P(3,11)*SF[8] + P(12,11)*SF[14] - P(10,11)*SPP[10] - (P(11,11)*q0)*0.5f) - (q0*(P(2,12) + P(0,12)*SF[6] + P(1,12)*SF[10] + P(3,12)*SF[8] + P(12,12)*SF[14] - P(10,12)*SPP[10] - (P(11,12)*q0)*0.5f))*0.5f;
|
||||
nextP(3,3) = P(3,3) + P(0,3)*SF[7] + P(1,3)*SF[6] + P(2,3)*SF[9] + P(10,3)*SF[15] - P(11,3)*SF[14] + (dayVar*SQ[10])*0.25f + dazVar*SQ[9] - (P(12,3)*q0)*0.5f + SF[7]*(P(3,0) + P(0,0)*SF[7] + P(1,0)*SF[6] + P(2,0)*SF[9] + P(10,0)*SF[15] - P(11,0)*SF[14] - (P(12,0)*q0)*0.5f) + SF[6]*(P(3,1) + P(0,1)*SF[7] + P(1,1)*SF[6] + P(2,1)*SF[9] + P(10,1)*SF[15] - P(11,1)*SF[14] - (P(12,1)*q0)*0.5f) + SF[9]*(P(3,2) + P(0,2)*SF[7] + P(1,2)*SF[6] + P(2,2)*SF[9] + P(10,2)*SF[15] - P(11,2)*SF[14] - (P(12,2)*q0)*0.5f) + SF[15]*(P(3,10) + P(0,10)*SF[7] + P(1,10)*SF[6] + P(2,10)*SF[9] + P(10,10)*SF[15] - P(11,10)*SF[14] - (P(12,10)*q0)*0.5f) - SF[14]*(P(3,11) + P(0,11)*SF[7] + P(1,11)*SF[6] + P(2,11)*SF[9] + P(10,11)*SF[15] - P(11,11)*SF[14] - (P(12,11)*q0)*0.5f) + (daxVar*sq(q2))*0.25f - (q0*(P(3,12) + P(0,12)*SF[7] + P(1,12)*SF[6] + P(2,12)*SF[9] + P(10,12)*SF[15] - P(11,12)*SF[14] - (P(12,12)*q0)*0.5f))*0.5f;
|
||||
nextP(0,4) = P(0,4) + P(1,4)*SF[9] + P(2,4)*SF[11] + P(3,4)*SF[10] + P(10,4)*SF[14] + P(11,4)*SF[15] + P(12,4)*SPP[10] + SF[5]*(P(0,0) + P(1,0)*SF[9] + P(2,0)*SF[11] + P(3,0)*SF[10] + P(10,0)*SF[14] + P(11,0)*SF[15] + P(12,0)*SPP[10]) + SF[3]*(P(0,1) + P(1,1)*SF[9] + P(2,1)*SF[11] + P(3,1)*SF[10] + P(10,1)*SF[14] + P(11,1)*SF[15] + P(12,1)*SPP[10]) - SF[4]*(P(0,3) + P(1,3)*SF[9] + P(2,3)*SF[11] + P(3,3)*SF[10] + P(10,3)*SF[14] + P(11,3)*SF[15] + P(12,3)*SPP[10]) + SPP[0]*(P(0,2) + P(1,2)*SF[9] + P(2,2)*SF[11] + P(3,2)*SF[10] + P(10,2)*SF[14] + P(11,2)*SF[15] + P(12,2)*SPP[10]) + SPP[3]*(P(0,13) + P(1,13)*SF[9] + P(2,13)*SF[11] + P(3,13)*SF[10] + P(10,13)*SF[14] + P(11,13)*SF[15] + P(12,13)*SPP[10]) + SPP[6]*(P(0,14) + P(1,14)*SF[9] + P(2,14)*SF[11] + P(3,14)*SF[10] + P(10,14)*SF[14] + P(11,14)*SF[15] + P(12,14)*SPP[10]) - SPP[9]*(P(0,15) + P(1,15)*SF[9] + P(2,15)*SF[11] + P(3,15)*SF[10] + P(10,15)*SF[14] + P(11,15)*SF[15] + P(12,15)*SPP[10]);
|
||||
nextP(1,4) = P(1,4) + P(0,4)*SF[8] + P(2,4)*SF[7] + P(3,4)*SF[11] - P(12,4)*SF[15] + P(11,4)*SPP[10] - (P(10,4)*q0)*0.5f + SF[5]*(P(1,0) + P(0,0)*SF[8] + P(2,0)*SF[7] + P(3,0)*SF[11] - P(12,0)*SF[15] + P(11,0)*SPP[10] - (P(10,0)*q0)*0.5f) + SF[3]*(P(1,1) + P(0,1)*SF[8] + P(2,1)*SF[7] + P(3,1)*SF[11] - P(12,1)*SF[15] + P(11,1)*SPP[10] - (P(10,1)*q0)*0.5f) - SF[4]*(P(1,3) + P(0,3)*SF[8] + P(2,3)*SF[7] + P(3,3)*SF[11] - P(12,3)*SF[15] + P(11,3)*SPP[10] - (P(10,3)*q0)*0.5f) + SPP[0]*(P(1,2) + P(0,2)*SF[8] + P(2,2)*SF[7] + P(3,2)*SF[11] - P(12,2)*SF[15] + P(11,2)*SPP[10] - (P(10,2)*q0)*0.5f) + SPP[3]*(P(1,13) + P(0,13)*SF[8] + P(2,13)*SF[7] + P(3,13)*SF[11] - P(12,13)*SF[15] + P(11,13)*SPP[10] - (P(10,13)*q0)*0.5f) + SPP[6]*(P(1,14) + P(0,14)*SF[8] + P(2,14)*SF[7] + P(3,14)*SF[11] - P(12,14)*SF[15] + P(11,14)*SPP[10] - (P(10,14)*q0)*0.5f) - SPP[9]*(P(1,15) + P(0,15)*SF[8] + P(2,15)*SF[7] + P(3,15)*SF[11] - P(12,15)*SF[15] + P(11,15)*SPP[10] - (P(10,15)*q0)*0.5f);
|
||||
nextP(2,4) = P(2,4) + P(0,4)*SF[6] + P(1,4)*SF[10] + P(3,4)*SF[8] + P(12,4)*SF[14] - P(10,4)*SPP[10] - (P(11,4)*q0)*0.5f + SF[5]*(P(2,0) + P(0,0)*SF[6] + P(1,0)*SF[10] + P(3,0)*SF[8] + P(12,0)*SF[14] - P(10,0)*SPP[10] - (P(11,0)*q0)*0.5f) + SF[3]*(P(2,1) + P(0,1)*SF[6] + P(1,1)*SF[10] + P(3,1)*SF[8] + P(12,1)*SF[14] - P(10,1)*SPP[10] - (P(11,1)*q0)*0.5f) - SF[4]*(P(2,3) + P(0,3)*SF[6] + P(1,3)*SF[10] + P(3,3)*SF[8] + P(12,3)*SF[14] - P(10,3)*SPP[10] - (P(11,3)*q0)*0.5f) + SPP[0]*(P(2,2) + P(0,2)*SF[6] + P(1,2)*SF[10] + P(3,2)*SF[8] + P(12,2)*SF[14] - P(10,2)*SPP[10] - (P(11,2)*q0)*0.5f) + SPP[3]*(P(2,13) + P(0,13)*SF[6] + P(1,13)*SF[10] + P(3,13)*SF[8] + P(12,13)*SF[14] - P(10,13)*SPP[10] - (P(11,13)*q0)*0.5f) + SPP[6]*(P(2,14) + P(0,14)*SF[6] + P(1,14)*SF[10] + P(3,14)*SF[8] + P(12,14)*SF[14] - P(10,14)*SPP[10] - (P(11,14)*q0)*0.5f) - SPP[9]*(P(2,15) + P(0,15)*SF[6] + P(1,15)*SF[10] + P(3,15)*SF[8] + P(12,15)*SF[14] - P(10,15)*SPP[10] - (P(11,15)*q0)*0.5f);
|
||||
nextP(3,4) = P(3,4) + P(0,4)*SF[7] + P(1,4)*SF[6] + P(2,4)*SF[9] + P(10,4)*SF[15] - P(11,4)*SF[14] - (P(12,4)*q0)*0.5f + SF[5]*(P(3,0) + P(0,0)*SF[7] + P(1,0)*SF[6] + P(2,0)*SF[9] + P(10,0)*SF[15] - P(11,0)*SF[14] - (P(12,0)*q0)*0.5f) + SF[3]*(P(3,1) + P(0,1)*SF[7] + P(1,1)*SF[6] + P(2,1)*SF[9] + P(10,1)*SF[15] - P(11,1)*SF[14] - (P(12,1)*q0)*0.5f) - SF[4]*(P(3,3) + P(0,3)*SF[7] + P(1,3)*SF[6] + P(2,3)*SF[9] + P(10,3)*SF[15] - P(11,3)*SF[14] - (P(12,3)*q0)*0.5f) + SPP[0]*(P(3,2) + P(0,2)*SF[7] + P(1,2)*SF[6] + P(2,2)*SF[9] + P(10,2)*SF[15] - P(11,2)*SF[14] - (P(12,2)*q0)*0.5f) + SPP[3]*(P(3,13) + P(0,13)*SF[7] + P(1,13)*SF[6] + P(2,13)*SF[9] + P(10,13)*SF[15] - P(11,13)*SF[14] - (P(12,13)*q0)*0.5f) + SPP[6]*(P(3,14) + P(0,14)*SF[7] + P(1,14)*SF[6] + P(2,14)*SF[9] + P(10,14)*SF[15] - P(11,14)*SF[14] - (P(12,14)*q0)*0.5f) - SPP[9]*(P(3,15) + P(0,15)*SF[7] + P(1,15)*SF[6] + P(2,15)*SF[9] + P(10,15)*SF[15] - P(11,15)*SF[14] - (P(12,15)*q0)*0.5f);
|
||||
nextP(4,4) = P(4,4) + P(0,4)*SF[5] + P(1,4)*SF[3] - P(3,4)*SF[4] + P(2,4)*SPP[0] + P(13,4)*SPP[3] + P(14,4)*SPP[6] - P(15,4)*SPP[9] + dvyVar*sq(SG[7] - 2*q0*q3) + dvzVar*sq(SG[6] + 2*q0*q2) + SF[5]*(P(4,0) + P(0,0)*SF[5] + P(1,0)*SF[3] - P(3,0)*SF[4] + P(2,0)*SPP[0] + P(13,0)*SPP[3] + P(14,0)*SPP[6] - P(15,0)*SPP[9]) + SF[3]*(P(4,1) + P(0,1)*SF[5] + P(1,1)*SF[3] - P(3,1)*SF[4] + P(2,1)*SPP[0] + P(13,1)*SPP[3] + P(14,1)*SPP[6] - P(15,1)*SPP[9]) - SF[4]*(P(4,3) + P(0,3)*SF[5] + P(1,3)*SF[3] - P(3,3)*SF[4] + P(2,3)*SPP[0] + P(13,3)*SPP[3] + P(14,3)*SPP[6] - P(15,3)*SPP[9]) + SPP[0]*(P(4,2) + P(0,2)*SF[5] + P(1,2)*SF[3] - P(3,2)*SF[4] + P(2,2)*SPP[0] + P(13,2)*SPP[3] + P(14,2)*SPP[6] - P(15,2)*SPP[9]) + SPP[3]*(P(4,13) + P(0,13)*SF[5] + P(1,13)*SF[3] - P(3,13)*SF[4] + P(2,13)*SPP[0] + P(13,13)*SPP[3] + P(14,13)*SPP[6] - P(15,13)*SPP[9]) + SPP[6]*(P(4,14) + P(0,14)*SF[5] + P(1,14)*SF[3] - P(3,14)*SF[4] + P(2,14)*SPP[0] + P(13,14)*SPP[3] + P(14,14)*SPP[6] - P(15,14)*SPP[9]) - SPP[9]*(P(4,15) + P(0,15)*SF[5] + P(1,15)*SF[3] - P(3,15)*SF[4] + P(2,15)*SPP[0] + P(13,15)*SPP[3] + P(14,15)*SPP[6] - P(15,15)*SPP[9]) + dvxVar*sq(SG[1] + SG[2] - SG[3] - SG[4]);
|
||||
nextP(0,5) = P(0,5) + P(1,5)*SF[9] + P(2,5)*SF[11] + P(3,5)*SF[10] + P(10,5)*SF[14] + P(11,5)*SF[15] + P(12,5)*SPP[10] + SF[4]*(P(0,0) + P(1,0)*SF[9] + P(2,0)*SF[11] + P(3,0)*SF[10] + P(10,0)*SF[14] + P(11,0)*SF[15] + P(12,0)*SPP[10]) + SF[3]*(P(0,2) + P(1,2)*SF[9] + P(2,2)*SF[11] + P(3,2)*SF[10] + P(10,2)*SF[14] + P(11,2)*SF[15] + P(12,2)*SPP[10]) + SF[5]*(P(0,3) + P(1,3)*SF[9] + P(2,3)*SF[11] + P(3,3)*SF[10] + P(10,3)*SF[14] + P(11,3)*SF[15] + P(12,3)*SPP[10]) - SPP[0]*(P(0,1) + P(1,1)*SF[9] + P(2,1)*SF[11] + P(3,1)*SF[10] + P(10,1)*SF[14] + P(11,1)*SF[15] + P(12,1)*SPP[10]) - SPP[8]*(P(0,13) + P(1,13)*SF[9] + P(2,13)*SF[11] + P(3,13)*SF[10] + P(10,13)*SF[14] + P(11,13)*SF[15] + P(12,13)*SPP[10]) + SPP[2]*(P(0,14) + P(1,14)*SF[9] + P(2,14)*SF[11] + P(3,14)*SF[10] + P(10,14)*SF[14] + P(11,14)*SF[15] + P(12,14)*SPP[10]) + SPP[5]*(P(0,15) + P(1,15)*SF[9] + P(2,15)*SF[11] + P(3,15)*SF[10] + P(10,15)*SF[14] + P(11,15)*SF[15] + P(12,15)*SPP[10]);
|
||||
nextP(1,5) = P(1,5) + P(0,5)*SF[8] + P(2,5)*SF[7] + P(3,5)*SF[11] - P(12,5)*SF[15] + P(11,5)*SPP[10] - (P(10,5)*q0)*0.5f + SF[4]*(P(1,0) + P(0,0)*SF[8] + P(2,0)*SF[7] + P(3,0)*SF[11] - P(12,0)*SF[15] + P(11,0)*SPP[10] - (P(10,0)*q0)*0.5f) + SF[3]*(P(1,2) + P(0,2)*SF[8] + P(2,2)*SF[7] + P(3,2)*SF[11] - P(12,2)*SF[15] + P(11,2)*SPP[10] - (P(10,2)*q0)*0.5f) + SF[5]*(P(1,3) + P(0,3)*SF[8] + P(2,3)*SF[7] + P(3,3)*SF[11] - P(12,3)*SF[15] + P(11,3)*SPP[10] - (P(10,3)*q0)*0.5f) - SPP[0]*(P(1,1) + P(0,1)*SF[8] + P(2,1)*SF[7] + P(3,1)*SF[11] - P(12,1)*SF[15] + P(11,1)*SPP[10] - (P(10,1)*q0)*0.5f) - SPP[8]*(P(1,13) + P(0,13)*SF[8] + P(2,13)*SF[7] + P(3,13)*SF[11] - P(12,13)*SF[15] + P(11,13)*SPP[10] - (P(10,13)*q0)*0.5f) + SPP[2]*(P(1,14) + P(0,14)*SF[8] + P(2,14)*SF[7] + P(3,14)*SF[11] - P(12,14)*SF[15] + P(11,14)*SPP[10] - (P(10,14)*q0)*0.5f) + SPP[5]*(P(1,15) + P(0,15)*SF[8] + P(2,15)*SF[7] + P(3,15)*SF[11] - P(12,15)*SF[15] + P(11,15)*SPP[10] - (P(10,15)*q0)*0.5f);
|
||||
nextP(2,5) = P(2,5) + P(0,5)*SF[6] + P(1,5)*SF[10] + P(3,5)*SF[8] + P(12,5)*SF[14] - P(10,5)*SPP[10] - (P(11,5)*q0)*0.5f + SF[4]*(P(2,0) + P(0,0)*SF[6] + P(1,0)*SF[10] + P(3,0)*SF[8] + P(12,0)*SF[14] - P(10,0)*SPP[10] - (P(11,0)*q0)*0.5f) + SF[3]*(P(2,2) + P(0,2)*SF[6] + P(1,2)*SF[10] + P(3,2)*SF[8] + P(12,2)*SF[14] - P(10,2)*SPP[10] - (P(11,2)*q0)*0.5f) + SF[5]*(P(2,3) + P(0,3)*SF[6] + P(1,3)*SF[10] + P(3,3)*SF[8] + P(12,3)*SF[14] - P(10,3)*SPP[10] - (P(11,3)*q0)*0.5f) - SPP[0]*(P(2,1) + P(0,1)*SF[6] + P(1,1)*SF[10] + P(3,1)*SF[8] + P(12,1)*SF[14] - P(10,1)*SPP[10] - (P(11,1)*q0)*0.5f) - SPP[8]*(P(2,13) + P(0,13)*SF[6] + P(1,13)*SF[10] + P(3,13)*SF[8] + P(12,13)*SF[14] - P(10,13)*SPP[10] - (P(11,13)*q0)*0.5f) + SPP[2]*(P(2,14) + P(0,14)*SF[6] + P(1,14)*SF[10] + P(3,14)*SF[8] + P(12,14)*SF[14] - P(10,14)*SPP[10] - (P(11,14)*q0)*0.5f) + SPP[5]*(P(2,15) + P(0,15)*SF[6] + P(1,15)*SF[10] + P(3,15)*SF[8] + P(12,15)*SF[14] - P(10,15)*SPP[10] - (P(11,15)*q0)*0.5f);
|
||||
nextP(3,5) = P(3,5) + P(0,5)*SF[7] + P(1,5)*SF[6] + P(2,5)*SF[9] + P(10,5)*SF[15] - P(11,5)*SF[14] - (P(12,5)*q0)*0.5f + SF[4]*(P(3,0) + P(0,0)*SF[7] + P(1,0)*SF[6] + P(2,0)*SF[9] + P(10,0)*SF[15] - P(11,0)*SF[14] - (P(12,0)*q0)*0.5f) + SF[3]*(P(3,2) + P(0,2)*SF[7] + P(1,2)*SF[6] + P(2,2)*SF[9] + P(10,2)*SF[15] - P(11,2)*SF[14] - (P(12,2)*q0)*0.5f) + SF[5]*(P(3,3) + P(0,3)*SF[7] + P(1,3)*SF[6] + P(2,3)*SF[9] + P(10,3)*SF[15] - P(11,3)*SF[14] - (P(12,3)*q0)*0.5f) - SPP[0]*(P(3,1) + P(0,1)*SF[7] + P(1,1)*SF[6] + P(2,1)*SF[9] + P(10,1)*SF[15] - P(11,1)*SF[14] - (P(12,1)*q0)*0.5f) - SPP[8]*(P(3,13) + P(0,13)*SF[7] + P(1,13)*SF[6] + P(2,13)*SF[9] + P(10,13)*SF[15] - P(11,13)*SF[14] - (P(12,13)*q0)*0.5f) + SPP[2]*(P(3,14) + P(0,14)*SF[7] + P(1,14)*SF[6] + P(2,14)*SF[9] + P(10,14)*SF[15] - P(11,14)*SF[14] - (P(12,14)*q0)*0.5f) + SPP[5]*(P(3,15) + P(0,15)*SF[7] + P(1,15)*SF[6] + P(2,15)*SF[9] + P(10,15)*SF[15] - P(11,15)*SF[14] - (P(12,15)*q0)*0.5f);
|
||||
nextP(4,5) = P(4,5) + SQ[2] + P(0,5)*SF[5] + P(1,5)*SF[3] - P(3,5)*SF[4] + P(2,5)*SPP[0] + P(13,5)*SPP[3] + P(14,5)*SPP[6] - P(15,5)*SPP[9] + SF[4]*(P(4,0) + P(0,0)*SF[5] + P(1,0)*SF[3] - P(3,0)*SF[4] + P(2,0)*SPP[0] + P(13,0)*SPP[3] + P(14,0)*SPP[6] - P(15,0)*SPP[9]) + SF[3]*(P(4,2) + P(0,2)*SF[5] + P(1,2)*SF[3] - P(3,2)*SF[4] + P(2,2)*SPP[0] + P(13,2)*SPP[3] + P(14,2)*SPP[6] - P(15,2)*SPP[9]) + SF[5]*(P(4,3) + P(0,3)*SF[5] + P(1,3)*SF[3] - P(3,3)*SF[4] + P(2,3)*SPP[0] + P(13,3)*SPP[3] + P(14,3)*SPP[6] - P(15,3)*SPP[9]) - SPP[0]*(P(4,1) + P(0,1)*SF[5] + P(1,1)*SF[3] - P(3,1)*SF[4] + P(2,1)*SPP[0] + P(13,1)*SPP[3] + P(14,1)*SPP[6] - P(15,1)*SPP[9]) - SPP[8]*(P(4,13) + P(0,13)*SF[5] + P(1,13)*SF[3] - P(3,13)*SF[4] + P(2,13)*SPP[0] + P(13,13)*SPP[3] + P(14,13)*SPP[6] - P(15,13)*SPP[9]) + SPP[2]*(P(4,14) + P(0,14)*SF[5] + P(1,14)*SF[3] - P(3,14)*SF[4] + P(2,14)*SPP[0] + P(13,14)*SPP[3] + P(14,14)*SPP[6] - P(15,14)*SPP[9]) + SPP[5]*(P(4,15) + P(0,15)*SF[5] + P(1,15)*SF[3] - P(3,15)*SF[4] + P(2,15)*SPP[0] + P(13,15)*SPP[3] + P(14,15)*SPP[6] - P(15,15)*SPP[9]);
|
||||
nextP(5,5) = P(5,5) + P(0,5)*SF[4] + P(2,5)*SF[3] + P(3,5)*SF[5] - P(1,5)*SPP[0] - P(13,5)*SPP[8] + P(14,5)*SPP[2] + P(15,5)*SPP[5] + dvxVar*sq(SG[7] + 2*q0*q3) + dvzVar*sq(SG[5] - 2*q0*q1) + SF[4]*(P(5,0) + P(0,0)*SF[4] + P(2,0)*SF[3] + P(3,0)*SF[5] - P(1,0)*SPP[0] - P(13,0)*SPP[8] + P(14,0)*SPP[2] + P(15,0)*SPP[5]) + SF[3]*(P(5,2) + P(0,2)*SF[4] + P(2,2)*SF[3] + P(3,2)*SF[5] - P(1,2)*SPP[0] - P(13,2)*SPP[8] + P(14,2)*SPP[2] + P(15,2)*SPP[5]) + SF[5]*(P(5,3) + P(0,3)*SF[4] + P(2,3)*SF[3] + P(3,3)*SF[5] - P(1,3)*SPP[0] - P(13,3)*SPP[8] + P(14,3)*SPP[2] + P(15,3)*SPP[5]) - SPP[0]*(P(5,1) + P(0,1)*SF[4] + P(2,1)*SF[3] + P(3,1)*SF[5] - P(1,1)*SPP[0] - P(13,1)*SPP[8] + P(14,1)*SPP[2] + P(15,1)*SPP[5]) - SPP[8]*(P(5,13) + P(0,13)*SF[4] + P(2,13)*SF[3] + P(3,13)*SF[5] - P(1,13)*SPP[0] - P(13,13)*SPP[8] + P(14,13)*SPP[2] + P(15,13)*SPP[5]) + SPP[2]*(P(5,14) + P(0,14)*SF[4] + P(2,14)*SF[3] + P(3,14)*SF[5] - P(1,14)*SPP[0] - P(13,14)*SPP[8] + P(14,14)*SPP[2] + P(15,14)*SPP[5]) + SPP[5]*(P(5,15) + P(0,15)*SF[4] + P(2,15)*SF[3] + P(3,15)*SF[5] - P(1,15)*SPP[0] - P(13,15)*SPP[8] + P(14,15)*SPP[2] + P(15,15)*SPP[5]) + dvyVar*sq(SG[1] - SG[2] + SG[3] - SG[4]);
|
||||
nextP(0,6) = P(0,6) + P(1,6)*SF[9] + P(2,6)*SF[11] + P(3,6)*SF[10] + P(10,6)*SF[14] + P(11,6)*SF[15] + P(12,6)*SPP[10] + SF[4]*(P(0,1) + P(1,1)*SF[9] + P(2,1)*SF[11] + P(3,1)*SF[10] + P(10,1)*SF[14] + P(11,1)*SF[15] + P(12,1)*SPP[10]) - SF[5]*(P(0,2) + P(1,2)*SF[9] + P(2,2)*SF[11] + P(3,2)*SF[10] + P(10,2)*SF[14] + P(11,2)*SF[15] + P(12,2)*SPP[10]) + SF[3]*(P(0,3) + P(1,3)*SF[9] + P(2,3)*SF[11] + P(3,3)*SF[10] + P(10,3)*SF[14] + P(11,3)*SF[15] + P(12,3)*SPP[10]) + SPP[0]*(P(0,0) + P(1,0)*SF[9] + P(2,0)*SF[11] + P(3,0)*SF[10] + P(10,0)*SF[14] + P(11,0)*SF[15] + P(12,0)*SPP[10]) + SPP[4]*(P(0,13) + P(1,13)*SF[9] + P(2,13)*SF[11] + P(3,13)*SF[10] + P(10,13)*SF[14] + P(11,13)*SF[15] + P(12,13)*SPP[10]) - SPP[7]*(P(0,14) + P(1,14)*SF[9] + P(2,14)*SF[11] + P(3,14)*SF[10] + P(10,14)*SF[14] + P(11,14)*SF[15] + P(12,14)*SPP[10]) - SPP[1]*(P(0,15) + P(1,15)*SF[9] + P(2,15)*SF[11] + P(3,15)*SF[10] + P(10,15)*SF[14] + P(11,15)*SF[15] + P(12,15)*SPP[10]);
|
||||
nextP(1,6) = P(1,6) + P(0,6)*SF[8] + P(2,6)*SF[7] + P(3,6)*SF[11] - P(12,6)*SF[15] + P(11,6)*SPP[10] - (P(10,6)*q0)*0.5f + SF[4]*(P(1,1) + P(0,1)*SF[8] + P(2,1)*SF[7] + P(3,1)*SF[11] - P(12,1)*SF[15] + P(11,1)*SPP[10] - (P(10,1)*q0)*0.5f) - SF[5]*(P(1,2) + P(0,2)*SF[8] + P(2,2)*SF[7] + P(3,2)*SF[11] - P(12,2)*SF[15] + P(11,2)*SPP[10] - (P(10,2)*q0)*0.5f) + SF[3]*(P(1,3) + P(0,3)*SF[8] + P(2,3)*SF[7] + P(3,3)*SF[11] - P(12,3)*SF[15] + P(11,3)*SPP[10] - (P(10,3)*q0)*0.5f) + SPP[0]*(P(1,0) + P(0,0)*SF[8] + P(2,0)*SF[7] + P(3,0)*SF[11] - P(12,0)*SF[15] + P(11,0)*SPP[10] - (P(10,0)*q0)*0.5f) + SPP[4]*(P(1,13) + P(0,13)*SF[8] + P(2,13)*SF[7] + P(3,13)*SF[11] - P(12,13)*SF[15] + P(11,13)*SPP[10] - (P(10,13)*q0)*0.5f) - SPP[7]*(P(1,14) + P(0,14)*SF[8] + P(2,14)*SF[7] + P(3,14)*SF[11] - P(12,14)*SF[15] + P(11,14)*SPP[10] - (P(10,14)*q0)*0.5f) - SPP[1]*(P(1,15) + P(0,15)*SF[8] + P(2,15)*SF[7] + P(3,15)*SF[11] - P(12,15)*SF[15] + P(11,15)*SPP[10] - (P(10,15)*q0)*0.5f);
|
||||
nextP(2,6) = P(2,6) + P(0,6)*SF[6] + P(1,6)*SF[10] + P(3,6)*SF[8] + P(12,6)*SF[14] - P(10,6)*SPP[10] - (P(11,6)*q0)*0.5f + SF[4]*(P(2,1) + P(0,1)*SF[6] + P(1,1)*SF[10] + P(3,1)*SF[8] + P(12,1)*SF[14] - P(10,1)*SPP[10] - (P(11,1)*q0)*0.5f) - SF[5]*(P(2,2) + P(0,2)*SF[6] + P(1,2)*SF[10] + P(3,2)*SF[8] + P(12,2)*SF[14] - P(10,2)*SPP[10] - (P(11,2)*q0)*0.5f) + SF[3]*(P(2,3) + P(0,3)*SF[6] + P(1,3)*SF[10] + P(3,3)*SF[8] + P(12,3)*SF[14] - P(10,3)*SPP[10] - (P(11,3)*q0)*0.5f) + SPP[0]*(P(2,0) + P(0,0)*SF[6] + P(1,0)*SF[10] + P(3,0)*SF[8] + P(12,0)*SF[14] - P(10,0)*SPP[10] - (P(11,0)*q0)*0.5f) + SPP[4]*(P(2,13) + P(0,13)*SF[6] + P(1,13)*SF[10] + P(3,13)*SF[8] + P(12,13)*SF[14] - P(10,13)*SPP[10] - (P(11,13)*q0)*0.5f) - SPP[7]*(P(2,14) + P(0,14)*SF[6] + P(1,14)*SF[10] + P(3,14)*SF[8] + P(12,14)*SF[14] - P(10,14)*SPP[10] - (P(11,14)*q0)*0.5f) - SPP[1]*(P(2,15) + P(0,15)*SF[6] + P(1,15)*SF[10] + P(3,15)*SF[8] + P(12,15)*SF[14] - P(10,15)*SPP[10] - (P(11,15)*q0)*0.5f);
|
||||
nextP(3,6) = P(3,6) + P(0,6)*SF[7] + P(1,6)*SF[6] + P(2,6)*SF[9] + P(10,6)*SF[15] - P(11,6)*SF[14] - (P(12,6)*q0)*0.5f + SF[4]*(P(3,1) + P(0,1)*SF[7] + P(1,1)*SF[6] + P(2,1)*SF[9] + P(10,1)*SF[15] - P(11,1)*SF[14] - (P(12,1)*q0)*0.5f) - SF[5]*(P(3,2) + P(0,2)*SF[7] + P(1,2)*SF[6] + P(2,2)*SF[9] + P(10,2)*SF[15] - P(11,2)*SF[14] - (P(12,2)*q0)*0.5f) + SF[3]*(P(3,3) + P(0,3)*SF[7] + P(1,3)*SF[6] + P(2,3)*SF[9] + P(10,3)*SF[15] - P(11,3)*SF[14] - (P(12,3)*q0)*0.5f) + SPP[0]*(P(3,0) + P(0,0)*SF[7] + P(1,0)*SF[6] + P(2,0)*SF[9] + P(10,0)*SF[15] - P(11,0)*SF[14] - (P(12,0)*q0)*0.5f) + SPP[4]*(P(3,13) + P(0,13)*SF[7] + P(1,13)*SF[6] + P(2,13)*SF[9] + P(10,13)*SF[15] - P(11,13)*SF[14] - (P(12,13)*q0)*0.5f) - SPP[7]*(P(3,14) + P(0,14)*SF[7] + P(1,14)*SF[6] + P(2,14)*SF[9] + P(10,14)*SF[15] - P(11,14)*SF[14] - (P(12,14)*q0)*0.5f) - SPP[1]*(P(3,15) + P(0,15)*SF[7] + P(1,15)*SF[6] + P(2,15)*SF[9] + P(10,15)*SF[15] - P(11,15)*SF[14] - (P(12,15)*q0)*0.5f);
|
||||
nextP(4,6) = P(4,6) + SQ[1] + P(0,6)*SF[5] + P(1,6)*SF[3] - P(3,6)*SF[4] + P(2,6)*SPP[0] + P(13,6)*SPP[3] + P(14,6)*SPP[6] - P(15,6)*SPP[9] + SF[4]*(P(4,1) + P(0,1)*SF[5] + P(1,1)*SF[3] - P(3,1)*SF[4] + P(2,1)*SPP[0] + P(13,1)*SPP[3] + P(14,1)*SPP[6] - P(15,1)*SPP[9]) - SF[5]*(P(4,2) + P(0,2)*SF[5] + P(1,2)*SF[3] - P(3,2)*SF[4] + P(2,2)*SPP[0] + P(13,2)*SPP[3] + P(14,2)*SPP[6] - P(15,2)*SPP[9]) + SF[3]*(P(4,3) + P(0,3)*SF[5] + P(1,3)*SF[3] - P(3,3)*SF[4] + P(2,3)*SPP[0] + P(13,3)*SPP[3] + P(14,3)*SPP[6] - P(15,3)*SPP[9]) + SPP[0]*(P(4,0) + P(0,0)*SF[5] + P(1,0)*SF[3] - P(3,0)*SF[4] + P(2,0)*SPP[0] + P(13,0)*SPP[3] + P(14,0)*SPP[6] - P(15,0)*SPP[9]) + SPP[4]*(P(4,13) + P(0,13)*SF[5] + P(1,13)*SF[3] - P(3,13)*SF[4] + P(2,13)*SPP[0] + P(13,13)*SPP[3] + P(14,13)*SPP[6] - P(15,13)*SPP[9]) - SPP[7]*(P(4,14) + P(0,14)*SF[5] + P(1,14)*SF[3] - P(3,14)*SF[4] + P(2,14)*SPP[0] + P(13,14)*SPP[3] + P(14,14)*SPP[6] - P(15,14)*SPP[9]) - SPP[1]*(P(4,15) + P(0,15)*SF[5] + P(1,15)*SF[3] - P(3,15)*SF[4] + P(2,15)*SPP[0] + P(13,15)*SPP[3] + P(14,15)*SPP[6] - P(15,15)*SPP[9]);
|
||||
nextP(5,6) = P(5,6) + SQ[0] + P(0,6)*SF[4] + P(2,6)*SF[3] + P(3,6)*SF[5] - P(1,6)*SPP[0] - P(13,6)*SPP[8] + P(14,6)*SPP[2] + P(15,6)*SPP[5] + SF[4]*(P(5,1) + P(0,1)*SF[4] + P(2,1)*SF[3] + P(3,1)*SF[5] - P(1,1)*SPP[0] - P(13,1)*SPP[8] + P(14,1)*SPP[2] + P(15,1)*SPP[5]) - SF[5]*(P(5,2) + P(0,2)*SF[4] + P(2,2)*SF[3] + P(3,2)*SF[5] - P(1,2)*SPP[0] - P(13,2)*SPP[8] + P(14,2)*SPP[2] + P(15,2)*SPP[5]) + SF[3]*(P(5,3) + P(0,3)*SF[4] + P(2,3)*SF[3] + P(3,3)*SF[5] - P(1,3)*SPP[0] - P(13,3)*SPP[8] + P(14,3)*SPP[2] + P(15,3)*SPP[5]) + SPP[0]*(P(5,0) + P(0,0)*SF[4] + P(2,0)*SF[3] + P(3,0)*SF[5] - P(1,0)*SPP[0] - P(13,0)*SPP[8] + P(14,0)*SPP[2] + P(15,0)*SPP[5]) + SPP[4]*(P(5,13) + P(0,13)*SF[4] + P(2,13)*SF[3] + P(3,13)*SF[5] - P(1,13)*SPP[0] - P(13,13)*SPP[8] + P(14,13)*SPP[2] + P(15,13)*SPP[5]) - SPP[7]*(P(5,14) + P(0,14)*SF[4] + P(2,14)*SF[3] + P(3,14)*SF[5] - P(1,14)*SPP[0] - P(13,14)*SPP[8] + P(14,14)*SPP[2] + P(15,14)*SPP[5]) - SPP[1]*(P(5,15) + P(0,15)*SF[4] + P(2,15)*SF[3] + P(3,15)*SF[5] - P(1,15)*SPP[0] - P(13,15)*SPP[8] + P(14,15)*SPP[2] + P(15,15)*SPP[5]);
|
||||
nextP(6,6) = P(6,6) + P(1,6)*SF[4] - P(2,6)*SF[5] + P(3,6)*SF[3] + P(0,6)*SPP[0] + P(13,6)*SPP[4] - P(14,6)*SPP[7] - P(15,6)*SPP[1] + dvxVar*sq(SG[6] - 2*q0*q2) + dvyVar*sq(SG[5] + 2*q0*q1) + SF[4]*(P(6,1) + P(1,1)*SF[4] - P(2,1)*SF[5] + P(3,1)*SF[3] + P(0,1)*SPP[0] + P(13,1)*SPP[4] - P(14,1)*SPP[7] - P(15,1)*SPP[1]) - SF[5]*(P(6,2) + P(1,2)*SF[4] - P(2,2)*SF[5] + P(3,2)*SF[3] + P(0,2)*SPP[0] + P(13,2)*SPP[4] - P(14,2)*SPP[7] - P(15,2)*SPP[1]) + SF[3]*(P(6,3) + P(1,3)*SF[4] - P(2,3)*SF[5] + P(3,3)*SF[3] + P(0,3)*SPP[0] + P(13,3)*SPP[4] - P(14,3)*SPP[7] - P(15,3)*SPP[1]) + SPP[0]*(P(6,0) + P(1,0)*SF[4] - P(2,0)*SF[5] + P(3,0)*SF[3] + P(0,0)*SPP[0] + P(13,0)*SPP[4] - P(14,0)*SPP[7] - P(15,0)*SPP[1]) + SPP[4]*(P(6,13) + P(1,13)*SF[4] - P(2,13)*SF[5] + P(3,13)*SF[3] + P(0,13)*SPP[0] + P(13,13)*SPP[4] - P(14,13)*SPP[7] - P(15,13)*SPP[1]) - SPP[7]*(P(6,14) + P(1,14)*SF[4] - P(2,14)*SF[5] + P(3,14)*SF[3] + P(0,14)*SPP[0] + P(13,14)*SPP[4] - P(14,14)*SPP[7] - P(15,14)*SPP[1]) - SPP[1]*(P(6,15) + P(1,15)*SF[4] - P(2,15)*SF[5] + P(3,15)*SF[3] + P(0,15)*SPP[0] + P(13,15)*SPP[4] - P(14,15)*SPP[7] - P(15,15)*SPP[1]) + dvzVar*sq(SG[1] - SG[2] - SG[3] + SG[4]);
|
||||
nextP(0,7) = P(0,7) + P(1,7)*SF[9] + P(2,7)*SF[11] + P(3,7)*SF[10] + P(10,7)*SF[14] + P(11,7)*SF[15] + P(12,7)*SPP[10] + dt*(P(0,4) + P(1,4)*SF[9] + P(2,4)*SF[11] + P(3,4)*SF[10] + P(10,4)*SF[14] + P(11,4)*SF[15] + P(12,4)*SPP[10]);
|
||||
nextP(1,7) = P(1,7) + P(0,7)*SF[8] + P(2,7)*SF[7] + P(3,7)*SF[11] - P(12,7)*SF[15] + P(11,7)*SPP[10] - (P(10,7)*q0)*0.5f + dt*(P(1,4) + P(0,4)*SF[8] + P(2,4)*SF[7] + P(3,4)*SF[11] - P(12,4)*SF[15] + P(11,4)*SPP[10] - (P(10,4)*q0)*0.5f);
|
||||
nextP(2,7) = P(2,7) + P(0,7)*SF[6] + P(1,7)*SF[10] + P(3,7)*SF[8] + P(12,7)*SF[14] - P(10,7)*SPP[10] - (P(11,7)*q0)*0.5f + dt*(P(2,4) + P(0,4)*SF[6] + P(1,4)*SF[10] + P(3,4)*SF[8] + P(12,4)*SF[14] - P(10,4)*SPP[10] - (P(11,4)*q0)*0.5f);
|
||||
nextP(3,7) = P(3,7) + P(0,7)*SF[7] + P(1,7)*SF[6] + P(2,7)*SF[9] + P(10,7)*SF[15] - P(11,7)*SF[14] - (P(12,7)*q0)*0.5f + dt*(P(3,4) + P(0,4)*SF[7] + P(1,4)*SF[6] + P(2,4)*SF[9] + P(10,4)*SF[15] - P(11,4)*SF[14] - (P(12,4)*q0)*0.5f);
|
||||
nextP(4,7) = P(4,7) + P(0,7)*SF[5] + P(1,7)*SF[3] - P(3,7)*SF[4] + P(2,7)*SPP[0] + P(13,7)*SPP[3] + P(14,7)*SPP[6] - P(15,7)*SPP[9] + dt*(P(4,4) + P(0,4)*SF[5] + P(1,4)*SF[3] - P(3,4)*SF[4] + P(2,4)*SPP[0] + P(13,4)*SPP[3] + P(14,4)*SPP[6] - P(15,4)*SPP[9]);
|
||||
nextP(5,7) = P(5,7) + P(0,7)*SF[4] + P(2,7)*SF[3] + P(3,7)*SF[5] - P(1,7)*SPP[0] - P(13,7)*SPP[8] + P(14,7)*SPP[2] + P(15,7)*SPP[5] + dt*(P(5,4) + P(0,4)*SF[4] + P(2,4)*SF[3] + P(3,4)*SF[5] - P(1,4)*SPP[0] - P(13,4)*SPP[8] + P(14,4)*SPP[2] + P(15,4)*SPP[5]);
|
||||
nextP(6,7) = P(6,7) + P(1,7)*SF[4] - P(2,7)*SF[5] + P(3,7)*SF[3] + P(0,7)*SPP[0] + P(13,7)*SPP[4] - P(14,7)*SPP[7] - P(15,7)*SPP[1] + dt*(P(6,4) + P(1,4)*SF[4] - P(2,4)*SF[5] + P(3,4)*SF[3] + P(0,4)*SPP[0] + P(13,4)*SPP[4] - P(14,4)*SPP[7] - P(15,4)*SPP[1]);
|
||||
nextP(7,7) = P(7,7) + P(4,7)*dt + dt*(P(7,4) + P(4,4)*dt);
|
||||
nextP(0,8) = P(0,8) + P(1,8)*SF[9] + P(2,8)*SF[11] + P(3,8)*SF[10] + P(10,8)*SF[14] + P(11,8)*SF[15] + P(12,8)*SPP[10] + dt*(P(0,5) + P(1,5)*SF[9] + P(2,5)*SF[11] + P(3,5)*SF[10] + P(10,5)*SF[14] + P(11,5)*SF[15] + P(12,5)*SPP[10]);
|
||||
nextP(1,8) = P(1,8) + P(0,8)*SF[8] + P(2,8)*SF[7] + P(3,8)*SF[11] - P(12,8)*SF[15] + P(11,8)*SPP[10] - (P(10,8)*q0)*0.5f + dt*(P(1,5) + P(0,5)*SF[8] + P(2,5)*SF[7] + P(3,5)*SF[11] - P(12,5)*SF[15] + P(11,5)*SPP[10] - (P(10,5)*q0)*0.5f);
|
||||
nextP(2,8) = P(2,8) + P(0,8)*SF[6] + P(1,8)*SF[10] + P(3,8)*SF[8] + P(12,8)*SF[14] - P(10,8)*SPP[10] - (P(11,8)*q0)*0.5f + dt*(P(2,5) + P(0,5)*SF[6] + P(1,5)*SF[10] + P(3,5)*SF[8] + P(12,5)*SF[14] - P(10,5)*SPP[10] - (P(11,5)*q0)*0.5f);
|
||||
nextP(3,8) = P(3,8) + P(0,8)*SF[7] + P(1,8)*SF[6] + P(2,8)*SF[9] + P(10,8)*SF[15] - P(11,8)*SF[14] - (P(12,8)*q0)*0.5f + dt*(P(3,5) + P(0,5)*SF[7] + P(1,5)*SF[6] + P(2,5)*SF[9] + P(10,5)*SF[15] - P(11,5)*SF[14] - (P(12,5)*q0)*0.5f);
|
||||
nextP(4,8) = P(4,8) + P(0,8)*SF[5] + P(1,8)*SF[3] - P(3,8)*SF[4] + P(2,8)*SPP[0] + P(13,8)*SPP[3] + P(14,8)*SPP[6] - P(15,8)*SPP[9] + dt*(P(4,5) + P(0,5)*SF[5] + P(1,5)*SF[3] - P(3,5)*SF[4] + P(2,5)*SPP[0] + P(13,5)*SPP[3] + P(14,5)*SPP[6] - P(15,5)*SPP[9]);
|
||||
nextP(5,8) = P(5,8) + P(0,8)*SF[4] + P(2,8)*SF[3] + P(3,8)*SF[5] - P(1,8)*SPP[0] - P(13,8)*SPP[8] + P(14,8)*SPP[2] + P(15,8)*SPP[5] + dt*(P(5,5) + P(0,5)*SF[4] + P(2,5)*SF[3] + P(3,5)*SF[5] - P(1,5)*SPP[0] - P(13,5)*SPP[8] + P(14,5)*SPP[2] + P(15,5)*SPP[5]);
|
||||
nextP(6,8) = P(6,8) + P(1,8)*SF[4] - P(2,8)*SF[5] + P(3,8)*SF[3] + P(0,8)*SPP[0] + P(13,8)*SPP[4] - P(14,8)*SPP[7] - P(15,8)*SPP[1] + dt*(P(6,5) + P(1,5)*SF[4] - P(2,5)*SF[5] + P(3,5)*SF[3] + P(0,5)*SPP[0] + P(13,5)*SPP[4] - P(14,5)*SPP[7] - P(15,5)*SPP[1]);
|
||||
nextP(7,8) = P(7,8) + P(4,8)*dt + dt*(P(7,5) + P(4,5)*dt);
|
||||
nextP(8,8) = P(8,8) + P(5,8)*dt + dt*(P(8,5) + P(5,5)*dt);
|
||||
nextP(0,9) = P(0,9) + P(1,9)*SF[9] + P(2,9)*SF[11] + P(3,9)*SF[10] + P(10,9)*SF[14] + P(11,9)*SF[15] + P(12,9)*SPP[10] + dt*(P(0,6) + P(1,6)*SF[9] + P(2,6)*SF[11] + P(3,6)*SF[10] + P(10,6)*SF[14] + P(11,6)*SF[15] + P(12,6)*SPP[10]);
|
||||
nextP(1,9) = P(1,9) + P(0,9)*SF[8] + P(2,9)*SF[7] + P(3,9)*SF[11] - P(12,9)*SF[15] + P(11,9)*SPP[10] - (P(10,9)*q0)*0.5f + dt*(P(1,6) + P(0,6)*SF[8] + P(2,6)*SF[7] + P(3,6)*SF[11] - P(12,6)*SF[15] + P(11,6)*SPP[10] - (P(10,6)*q0)*0.5f);
|
||||
nextP(2,9) = P(2,9) + P(0,9)*SF[6] + P(1,9)*SF[10] + P(3,9)*SF[8] + P(12,9)*SF[14] - P(10,9)*SPP[10] - (P(11,9)*q0)*0.5f + dt*(P(2,6) + P(0,6)*SF[6] + P(1,6)*SF[10] + P(3,6)*SF[8] + P(12,6)*SF[14] - P(10,6)*SPP[10] - (P(11,6)*q0)*0.5f);
|
||||
nextP(3,9) = P(3,9) + P(0,9)*SF[7] + P(1,9)*SF[6] + P(2,9)*SF[9] + P(10,9)*SF[15] - P(11,9)*SF[14] - (P(12,9)*q0)*0.5f + dt*(P(3,6) + P(0,6)*SF[7] + P(1,6)*SF[6] + P(2,6)*SF[9] + P(10,6)*SF[15] - P(11,6)*SF[14] - (P(12,6)*q0)*0.5f);
|
||||
nextP(4,9) = P(4,9) + P(0,9)*SF[5] + P(1,9)*SF[3] - P(3,9)*SF[4] + P(2,9)*SPP[0] + P(13,9)*SPP[3] + P(14,9)*SPP[6] - P(15,9)*SPP[9] + dt*(P(4,6) + P(0,6)*SF[5] + P(1,6)*SF[3] - P(3,6)*SF[4] + P(2,6)*SPP[0] + P(13,6)*SPP[3] + P(14,6)*SPP[6] - P(15,6)*SPP[9]);
|
||||
nextP(5,9) = P(5,9) + P(0,9)*SF[4] + P(2,9)*SF[3] + P(3,9)*SF[5] - P(1,9)*SPP[0] - P(13,9)*SPP[8] + P(14,9)*SPP[2] + P(15,9)*SPP[5] + dt*(P(5,6) + P(0,6)*SF[4] + P(2,6)*SF[3] + P(3,6)*SF[5] - P(1,6)*SPP[0] - P(13,6)*SPP[8] + P(14,6)*SPP[2] + P(15,6)*SPP[5]);
|
||||
nextP(6,9) = P(6,9) + P(1,9)*SF[4] - P(2,9)*SF[5] + P(3,9)*SF[3] + P(0,9)*SPP[0] + P(13,9)*SPP[4] - P(14,9)*SPP[7] - P(15,9)*SPP[1] + dt*(P(6,6) + P(1,6)*SF[4] - P(2,6)*SF[5] + P(3,6)*SF[3] + P(0,6)*SPP[0] + P(13,6)*SPP[4] - P(14,6)*SPP[7] - P(15,6)*SPP[1]);
|
||||
nextP(7,9) = P(7,9) + P(4,9)*dt + dt*(P(7,6) + P(4,6)*dt);
|
||||
nextP(8,9) = P(8,9) + P(5,9)*dt + dt*(P(8,6) + P(5,6)*dt);
|
||||
nextP(9,9) = P(9,9) + P(6,9)*dt + dt*(P(9,6) + P(6,6)*dt);
|
||||
nextP(0,10) = P(0,10) + P(1,10)*SF[9] + P(2,10)*SF[11] + P(3,10)*SF[10] + P(10,10)*SF[14] + P(11,10)*SF[15] + P(12,10)*SPP[10];
|
||||
nextP(1,10) = P(1,10) + P(0,10)*SF[8] + P(2,10)*SF[7] + P(3,10)*SF[11] - P(12,10)*SF[15] + P(11,10)*SPP[10] - (P(10,10)*q0)*0.5f;
|
||||
nextP(2,10) = P(2,10) + P(0,10)*SF[6] + P(1,10)*SF[10] + P(3,10)*SF[8] + P(12,10)*SF[14] - P(10,10)*SPP[10] - (P(11,10)*q0)*0.5f;
|
||||
nextP(3,10) = P(3,10) + P(0,10)*SF[7] + P(1,10)*SF[6] + P(2,10)*SF[9] + P(10,10)*SF[15] - P(11,10)*SF[14] - (P(12,10)*q0)*0.5f;
|
||||
nextP(4,10) = P(4,10) + P(0,10)*SF[5] + P(1,10)*SF[3] - P(3,10)*SF[4] + P(2,10)*SPP[0] + P(13,10)*SPP[3] + P(14,10)*SPP[6] - P(15,10)*SPP[9];
|
||||
nextP(5,10) = P(5,10) + P(0,10)*SF[4] + P(2,10)*SF[3] + P(3,10)*SF[5] - P(1,10)*SPP[0] - P(13,10)*SPP[8] + P(14,10)*SPP[2] + P(15,10)*SPP[5];
|
||||
nextP(6,10) = P(6,10) + P(1,10)*SF[4] - P(2,10)*SF[5] + P(3,10)*SF[3] + P(0,10)*SPP[0] + P(13,10)*SPP[4] - P(14,10)*SPP[7] - P(15,10)*SPP[1];
|
||||
nextP(7,10) = P(7,10) + P(4,10)*dt;
|
||||
nextP(8,10) = P(8,10) + P(5,10)*dt;
|
||||
nextP(9,10) = P(9,10) + P(6,10)*dt;
|
||||
nextP(10,10) = P(10,10);
|
||||
nextP(0,11) = P(0,11) + P(1,11)*SF[9] + P(2,11)*SF[11] + P(3,11)*SF[10] + P(10,11)*SF[14] + P(11,11)*SF[15] + P(12,11)*SPP[10];
|
||||
nextP(1,11) = P(1,11) + P(0,11)*SF[8] + P(2,11)*SF[7] + P(3,11)*SF[11] - P(12,11)*SF[15] + P(11,11)*SPP[10] - (P(10,11)*q0)*0.5f;
|
||||
nextP(2,11) = P(2,11) + P(0,11)*SF[6] + P(1,11)*SF[10] + P(3,11)*SF[8] + P(12,11)*SF[14] - P(10,11)*SPP[10] - (P(11,11)*q0)*0.5f;
|
||||
nextP(3,11) = P(3,11) + P(0,11)*SF[7] + P(1,11)*SF[6] + P(2,11)*SF[9] + P(10,11)*SF[15] - P(11,11)*SF[14] - (P(12,11)*q0)*0.5f;
|
||||
nextP(4,11) = P(4,11) + P(0,11)*SF[5] + P(1,11)*SF[3] - P(3,11)*SF[4] + P(2,11)*SPP[0] + P(13,11)*SPP[3] + P(14,11)*SPP[6] - P(15,11)*SPP[9];
|
||||
nextP(5,11) = P(5,11) + P(0,11)*SF[4] + P(2,11)*SF[3] + P(3,11)*SF[5] - P(1,11)*SPP[0] - P(13,11)*SPP[8] + P(14,11)*SPP[2] + P(15,11)*SPP[5];
|
||||
nextP(6,11) = P(6,11) + P(1,11)*SF[4] - P(2,11)*SF[5] + P(3,11)*SF[3] + P(0,11)*SPP[0] + P(13,11)*SPP[4] - P(14,11)*SPP[7] - P(15,11)*SPP[1];
|
||||
nextP(7,11) = P(7,11) + P(4,11)*dt;
|
||||
nextP(8,11) = P(8,11) + P(5,11)*dt;
|
||||
nextP(9,11) = P(9,11) + P(6,11)*dt;
|
||||
nextP(10,11) = P(10,11);
|
||||
nextP(11,11) = P(11,11);
|
||||
nextP(0,12) = P(0,12) + P(1,12)*SF[9] + P(2,12)*SF[11] + P(3,12)*SF[10] + P(10,12)*SF[14] + P(11,12)*SF[15] + P(12,12)*SPP[10];
|
||||
nextP(1,12) = P(1,12) + P(0,12)*SF[8] + P(2,12)*SF[7] + P(3,12)*SF[11] - P(12,12)*SF[15] + P(11,12)*SPP[10] - (P(10,12)*q0)*0.5f;
|
||||
nextP(2,12) = P(2,12) + P(0,12)*SF[6] + P(1,12)*SF[10] + P(3,12)*SF[8] + P(12,12)*SF[14] - P(10,12)*SPP[10] - (P(11,12)*q0)*0.5f;
|
||||
nextP(3,12) = P(3,12) + P(0,12)*SF[7] + P(1,12)*SF[6] + P(2,12)*SF[9] + P(10,12)*SF[15] - P(11,12)*SF[14] - (P(12,12)*q0)*0.5f;
|
||||
nextP(4,12) = P(4,12) + P(0,12)*SF[5] + P(1,12)*SF[3] - P(3,12)*SF[4] + P(2,12)*SPP[0] + P(13,12)*SPP[3] + P(14,12)*SPP[6] - P(15,12)*SPP[9];
|
||||
nextP(5,12) = P(5,12) + P(0,12)*SF[4] + P(2,12)*SF[3] + P(3,12)*SF[5] - P(1,12)*SPP[0] - P(13,12)*SPP[8] + P(14,12)*SPP[2] + P(15,12)*SPP[5];
|
||||
nextP(6,12) = P(6,12) + P(1,12)*SF[4] - P(2,12)*SF[5] + P(3,12)*SF[3] + P(0,12)*SPP[0] + P(13,12)*SPP[4] - P(14,12)*SPP[7] - P(15,12)*SPP[1];
|
||||
nextP(7,12) = P(7,12) + P(4,12)*dt;
|
||||
nextP(8,12) = P(8,12) + P(5,12)*dt;
|
||||
nextP(9,12) = P(9,12) + P(6,12)*dt;
|
||||
nextP(10,12) = P(10,12);
|
||||
nextP(11,12) = P(11,12);
|
||||
nextP(12,12) = P(12,12);
|
||||
|
||||
for (unsigned i = 13; i <= 15; i++) {
|
||||
nextP(0,i) = P(0,i) + P(1,i)*SF[9] + P(2,i)*SF[11] + P(3,i)*SF[10] + P(10,i)*SF[14] + P(11,i)*SF[15] + P(12,i)*SPP[10];
|
||||
nextP(1,i) = P(1,i) + P(0,i)*SF[8] + P(2,i)*SF[7] + P(3,i)*SF[11] - P(12,i)*SF[15] + P(11,i)*SPP[10] - (P(10,i)*q0)*0.5f;
|
||||
nextP(2,i) = P(2,i) + P(0,i)*SF[6] + P(1,i)*SF[10] + P(3,i)*SF[8] + P(12,i)*SF[14] - P(10,i)*SPP[10] - (P(11,i)*q0)*0.5f;
|
||||
nextP(3,i) = P(3,i) + P(0,i)*SF[7] + P(1,i)*SF[6] + P(2,i)*SF[9] + P(10,i)*SF[15] - P(11,i)*SF[14] - (P(12,i)*q0)*0.5f;
|
||||
nextP(4,i) = P(4,i) + P(0,i)*SF[5] + P(1,i)*SF[3] - P(3,i)*SF[4] + P(2,i)*SPP[0] + P(13,i)*SPP[3] + P(14,i)*SPP[6] - P(15,i)*SPP[9];
|
||||
nextP(5,i) = P(5,i) + P(0,i)*SF[4] + P(2,i)*SF[3] + P(3,i)*SF[5] - P(1,i)*SPP[0] - P(13,i)*SPP[8] + P(14,i)*SPP[2] + P(15,i)*SPP[5];
|
||||
nextP(6,i) = P(6,i) + P(1,i)*SF[4] - P(2,i)*SF[5] + P(3,i)*SF[3] + P(0,i)*SPP[0] + P(13,i)*SPP[4] - P(14,i)*SPP[7] - P(15,i)*SPP[1];
|
||||
nextP(7,i) = P(7,i) + P(4,i)*dt;
|
||||
nextP(8,i) = P(8,i) + P(5,i)*dt;
|
||||
nextP(9,i) = P(9,i) + P(6,i)*dt;
|
||||
nextP(10,i) = P(10,i);
|
||||
nextP(11,i) = P(11,i);
|
||||
nextP(12,i) = P(12,i);
|
||||
nextP(13,i) = P(13,i);
|
||||
|
||||
if (i > 13) {
|
||||
nextP(14,i) = P(14,i);
|
||||
}
|
||||
|
||||
if (i > 14) {
|
||||
nextP(15,i) = P(15,i);
|
||||
}
|
||||
}
|
||||
|
||||
nextP(0,16) = P(0,16) + P(1,16)*SF[9] + P(2,16)*SF[11] + P(3,16)*SF[10] + P(10,16)*SF[14] + P(11,16)*SF[15] + P(12,16)*SPP[10];
|
||||
nextP(1,16) = P(1,16) + P(0,16)*SF[8] + P(2,16)*SF[7] + P(3,16)*SF[11] - P(12,16)*SF[15] + P(11,16)*SPP[10] - (P(10,16)*q0)*0.5f;
|
||||
nextP(2,16) = P(2,16) + P(0,16)*SF[6] + P(1,16)*SF[10] + P(3,16)*SF[8] + P(12,16)*SF[14] - P(10,16)*SPP[10] - (P(11,16)*q0)*0.5f;
|
||||
nextP(3,16) = P(3,16) + P(0,16)*SF[7] + P(1,16)*SF[6] + P(2,16)*SF[9] + P(10,16)*SF[15] - P(11,16)*SF[14] - (P(12,16)*q0)*0.5f;
|
||||
nextP(4,16) = P(4,16) + P(0,16)*SF[5] + P(1,16)*SF[3] - P(3,16)*SF[4] + P(2,16)*SPP[0] + P(13,16)*SPP[3] + P(14,16)*SPP[6] - P(15,16)*SPP[9];
|
||||
nextP(5,16) = P(5,16) + P(0,16)*SF[4] + P(2,16)*SF[3] + P(3,16)*SF[5] - P(1,16)*SPP[0] - P(13,16)*SPP[8] + P(14,16)*SPP[2] + P(15,16)*SPP[5];
|
||||
nextP(6,16) = P(6,16) + P(1,16)*SF[4] - P(2,16)*SF[5] + P(3,16)*SF[3] + P(0,16)*SPP[0] + P(13,16)*SPP[4] - P(14,16)*SPP[7] - P(15,16)*SPP[1];
|
||||
nextP(7,16) = P(7,16) + P(4,16)*dt;
|
||||
nextP(8,16) = P(8,16) + P(5,16)*dt;
|
||||
nextP(9,16) = P(9,16) + P(6,16)*dt;
|
||||
nextP(10,16) = P(10,16);
|
||||
nextP(11,16) = P(11,16);
|
||||
nextP(12,16) = P(12,16);
|
||||
nextP(13,16) = P(13,16);
|
||||
nextP(14,16) = P(14,16);
|
||||
nextP(15,16) = P(15,16);
|
||||
nextP(16,16) = P(16,16);
|
||||
nextP(0,17) = P(0,17) + P(1,17)*SF[9] + P(2,17)*SF[11] + P(3,17)*SF[10] + P(10,17)*SF[14] + P(11,17)*SF[15] + P(12,17)*SPP[10];
|
||||
nextP(1,17) = P(1,17) + P(0,17)*SF[8] + P(2,17)*SF[7] + P(3,17)*SF[11] - P(12,17)*SF[15] + P(11,17)*SPP[10] - (P(10,17)*q0)*0.5f;
|
||||
nextP(2,17) = P(2,17) + P(0,17)*SF[6] + P(1,17)*SF[10] + P(3,17)*SF[8] + P(12,17)*SF[14] - P(10,17)*SPP[10] - (P(11,17)*q0)*0.5f;
|
||||
nextP(3,17) = P(3,17) + P(0,17)*SF[7] + P(1,17)*SF[6] + P(2,17)*SF[9] + P(10,17)*SF[15] - P(11,17)*SF[14] - (P(12,17)*q0)*0.5f;
|
||||
nextP(4,17) = P(4,17) + P(0,17)*SF[5] + P(1,17)*SF[3] - P(3,17)*SF[4] + P(2,17)*SPP[0] + P(13,17)*SPP[3] + P(14,17)*SPP[6] - P(15,17)*SPP[9];
|
||||
nextP(5,17) = P(5,17) + P(0,17)*SF[4] + P(2,17)*SF[3] + P(3,17)*SF[5] - P(1,17)*SPP[0] - P(13,17)*SPP[8] + P(14,17)*SPP[2] + P(15,17)*SPP[5];
|
||||
nextP(6,17) = P(6,17) + P(1,17)*SF[4] - P(2,17)*SF[5] + P(3,17)*SF[3] + P(0,17)*SPP[0] + P(13,17)*SPP[4] - P(14,17)*SPP[7] - P(15,17)*SPP[1];
|
||||
nextP(7,17) = P(7,17) + P(4,17)*dt;
|
||||
nextP(8,17) = P(8,17) + P(5,17)*dt;
|
||||
nextP(9,17) = P(9,17) + P(6,17)*dt;
|
||||
nextP(10,17) = P(10,17);
|
||||
nextP(11,17) = P(11,17);
|
||||
nextP(12,17) = P(12,17);
|
||||
nextP(13,17) = P(13,17);
|
||||
nextP(14,17) = P(14,17);
|
||||
nextP(15,17) = P(15,17);
|
||||
nextP(16,17) = P(16,17);
|
||||
nextP(17,17) = P(17,17);
|
||||
nextP(0,18) = P(0,18) + P(1,18)*SF[9] + P(2,18)*SF[11] + P(3,18)*SF[10] + P(10,18)*SF[14] + P(11,18)*SF[15] + P(12,18)*SPP[10];
|
||||
nextP(1,18) = P(1,18) + P(0,18)*SF[8] + P(2,18)*SF[7] + P(3,18)*SF[11] - P(12,18)*SF[15] + P(11,18)*SPP[10] - (P(10,18)*q0)*0.5f;
|
||||
nextP(2,18) = P(2,18) + P(0,18)*SF[6] + P(1,18)*SF[10] + P(3,18)*SF[8] + P(12,18)*SF[14] - P(10,18)*SPP[10] - (P(11,18)*q0)*0.5f;
|
||||
nextP(3,18) = P(3,18) + P(0,18)*SF[7] + P(1,18)*SF[6] + P(2,18)*SF[9] + P(10,18)*SF[15] - P(11,18)*SF[14] - (P(12,18)*q0)*0.5f;
|
||||
nextP(4,18) = P(4,18) + P(0,18)*SF[5] + P(1,18)*SF[3] - P(3,18)*SF[4] + P(2,18)*SPP[0] + P(13,18)*SPP[3] + P(14,18)*SPP[6] - P(15,18)*SPP[9];
|
||||
nextP(5,18) = P(5,18) + P(0,18)*SF[4] + P(2,18)*SF[3] + P(3,18)*SF[5] - P(1,18)*SPP[0] - P(13,18)*SPP[8] + P(14,18)*SPP[2] + P(15,18)*SPP[5];
|
||||
nextP(6,18) = P(6,18) + P(1,18)*SF[4] - P(2,18)*SF[5] + P(3,18)*SF[3] + P(0,18)*SPP[0] + P(13,18)*SPP[4] - P(14,18)*SPP[7] - P(15,18)*SPP[1];
|
||||
nextP(7,18) = P(7,18) + P(4,18)*dt;
|
||||
nextP(8,18) = P(8,18) + P(5,18)*dt;
|
||||
nextP(9,18) = P(9,18) + P(6,18)*dt;
|
||||
nextP(10,18) = P(10,18);
|
||||
nextP(11,18) = P(11,18);
|
||||
nextP(12,18) = P(12,18);
|
||||
nextP(13,18) = P(13,18);
|
||||
nextP(14,18) = P(14,18);
|
||||
nextP(15,18) = P(15,18);
|
||||
nextP(16,18) = P(16,18);
|
||||
nextP(17,18) = P(17,18);
|
||||
nextP(18,18) = P(18,18);
|
||||
nextP(0,19) = P(0,19) + P(1,19)*SF[9] + P(2,19)*SF[11] + P(3,19)*SF[10] + P(10,19)*SF[14] + P(11,19)*SF[15] + P(12,19)*SPP[10];
|
||||
nextP(1,19) = P(1,19) + P(0,19)*SF[8] + P(2,19)*SF[7] + P(3,19)*SF[11] - P(12,19)*SF[15] + P(11,19)*SPP[10] - (P(10,19)*q0)*0.5f;
|
||||
nextP(2,19) = P(2,19) + P(0,19)*SF[6] + P(1,19)*SF[10] + P(3,19)*SF[8] + P(12,19)*SF[14] - P(10,19)*SPP[10] - (P(11,19)*q0)*0.5f;
|
||||
nextP(3,19) = P(3,19) + P(0,19)*SF[7] + P(1,19)*SF[6] + P(2,19)*SF[9] + P(10,19)*SF[15] - P(11,19)*SF[14] - (P(12,19)*q0)*0.5f;
|
||||
nextP(4,19) = P(4,19) + P(0,19)*SF[5] + P(1,19)*SF[3] - P(3,19)*SF[4] + P(2,19)*SPP[0] + P(13,19)*SPP[3] + P(14,19)*SPP[6] - P(15,19)*SPP[9];
|
||||
nextP(5,19) = P(5,19) + P(0,19)*SF[4] + P(2,19)*SF[3] + P(3,19)*SF[5] - P(1,19)*SPP[0] - P(13,19)*SPP[8] + P(14,19)*SPP[2] + P(15,19)*SPP[5];
|
||||
nextP(6,19) = P(6,19) + P(1,19)*SF[4] - P(2,19)*SF[5] + P(3,19)*SF[3] + P(0,19)*SPP[0] + P(13,19)*SPP[4] - P(14,19)*SPP[7] - P(15,19)*SPP[1];
|
||||
nextP(7,19) = P(7,19) + P(4,19)*dt;
|
||||
nextP(8,19) = P(8,19) + P(5,19)*dt;
|
||||
nextP(9,19) = P(9,19) + P(6,19)*dt;
|
||||
nextP(10,19) = P(10,19);
|
||||
nextP(11,19) = P(11,19);
|
||||
nextP(12,19) = P(12,19);
|
||||
nextP(13,19) = P(13,19);
|
||||
nextP(14,19) = P(14,19);
|
||||
nextP(15,19) = P(15,19);
|
||||
nextP(16,19) = P(16,19);
|
||||
nextP(17,19) = P(17,19);
|
||||
nextP(18,19) = P(18,19);
|
||||
nextP(19,19) = P(19,19);
|
||||
nextP(0,20) = P(0,20) + P(1,20)*SF[9] + P(2,20)*SF[11] + P(3,20)*SF[10] + P(10,20)*SF[14] + P(11,20)*SF[15] + P(12,20)*SPP[10];
|
||||
nextP(1,20) = P(1,20) + P(0,20)*SF[8] + P(2,20)*SF[7] + P(3,20)*SF[11] - P(12,20)*SF[15] + P(11,20)*SPP[10] - (P(10,20)*q0)*0.5f;
|
||||
nextP(2,20) = P(2,20) + P(0,20)*SF[6] + P(1,20)*SF[10] + P(3,20)*SF[8] + P(12,20)*SF[14] - P(10,20)*SPP[10] - (P(11,20)*q0)*0.5f;
|
||||
nextP(3,20) = P(3,20) + P(0,20)*SF[7] + P(1,20)*SF[6] + P(2,20)*SF[9] + P(10,20)*SF[15] - P(11,20)*SF[14] - (P(12,20)*q0)*0.5f;
|
||||
nextP(4,20) = P(4,20) + P(0,20)*SF[5] + P(1,20)*SF[3] - P(3,20)*SF[4] + P(2,20)*SPP[0] + P(13,20)*SPP[3] + P(14,20)*SPP[6] - P(15,20)*SPP[9];
|
||||
nextP(5,20) = P(5,20) + P(0,20)*SF[4] + P(2,20)*SF[3] + P(3,20)*SF[5] - P(1,20)*SPP[0] - P(13,20)*SPP[8] + P(14,20)*SPP[2] + P(15,20)*SPP[5];
|
||||
nextP(6,20) = P(6,20) + P(1,20)*SF[4] - P(2,20)*SF[5] + P(3,20)*SF[3] + P(0,20)*SPP[0] + P(13,20)*SPP[4] - P(14,20)*SPP[7] - P(15,20)*SPP[1];
|
||||
nextP(7,20) = P(7,20) + P(4,20)*dt;
|
||||
nextP(8,20) = P(8,20) + P(5,20)*dt;
|
||||
nextP(9,20) = P(9,20) + P(6,20)*dt;
|
||||
nextP(10,20) = P(10,20);
|
||||
nextP(11,20) = P(11,20);
|
||||
nextP(12,20) = P(12,20);
|
||||
nextP(13,20) = P(13,20);
|
||||
nextP(14,20) = P(14,20);
|
||||
nextP(15,20) = P(15,20);
|
||||
nextP(16,20) = P(16,20);
|
||||
nextP(17,20) = P(17,20);
|
||||
nextP(18,20) = P(18,20);
|
||||
nextP(19,20) = P(19,20);
|
||||
nextP(20,20) = P(20,20);
|
||||
nextP(0,21) = P(0,21) + P(1,21)*SF[9] + P(2,21)*SF[11] + P(3,21)*SF[10] + P(10,21)*SF[14] + P(11,21)*SF[15] + P(12,21)*SPP[10];
|
||||
nextP(1,21) = P(1,21) + P(0,21)*SF[8] + P(2,21)*SF[7] + P(3,21)*SF[11] - P(12,21)*SF[15] + P(11,21)*SPP[10] - (P(10,21)*q0)*0.5f;
|
||||
nextP(2,21) = P(2,21) + P(0,21)*SF[6] + P(1,21)*SF[10] + P(3,21)*SF[8] + P(12,21)*SF[14] - P(10,21)*SPP[10] - (P(11,21)*q0)*0.5f;
|
||||
nextP(3,21) = P(3,21) + P(0,21)*SF[7] + P(1,21)*SF[6] + P(2,21)*SF[9] + P(10,21)*SF[15] - P(11,21)*SF[14] - (P(12,21)*q0)*0.5f;
|
||||
nextP(4,21) = P(4,21) + P(0,21)*SF[5] + P(1,21)*SF[3] - P(3,21)*SF[4] + P(2,21)*SPP[0] + P(13,21)*SPP[3] + P(14,21)*SPP[6] - P(15,21)*SPP[9];
|
||||
nextP(5,21) = P(5,21) + P(0,21)*SF[4] + P(2,21)*SF[3] + P(3,21)*SF[5] - P(1,21)*SPP[0] - P(13,21)*SPP[8] + P(14,21)*SPP[2] + P(15,21)*SPP[5];
|
||||
nextP(6,21) = P(6,21) + P(1,21)*SF[4] - P(2,21)*SF[5] + P(3,21)*SF[3] + P(0,21)*SPP[0] + P(13,21)*SPP[4] - P(14,21)*SPP[7] - P(15,21)*SPP[1];
|
||||
nextP(7,21) = P(7,21) + P(4,21)*dt;
|
||||
nextP(8,21) = P(8,21) + P(5,21)*dt;
|
||||
nextP(9,21) = P(9,21) + P(6,21)*dt;
|
||||
nextP(10,21) = P(10,21);
|
||||
nextP(11,21) = P(11,21);
|
||||
nextP(12,21) = P(12,21);
|
||||
nextP(13,21) = P(13,21);
|
||||
nextP(14,21) = P(14,21);
|
||||
nextP(15,21) = P(15,21);
|
||||
nextP(16,21) = P(16,21);
|
||||
nextP(17,21) = P(17,21);
|
||||
nextP(18,21) = P(18,21);
|
||||
nextP(19,21) = P(19,21);
|
||||
nextP(20,21) = P(20,21);
|
||||
nextP(21,21) = P(21,21);
|
||||
nextP(0,22) = P(0,22) + P(1,22)*SF[9] + P(2,22)*SF[11] + P(3,22)*SF[10] + P(10,22)*SF[14] + P(11,22)*SF[15] + P(12,22)*SPP[10];
|
||||
nextP(1,22) = P(1,22) + P(0,22)*SF[8] + P(2,22)*SF[7] + P(3,22)*SF[11] - P(12,22)*SF[15] + P(11,22)*SPP[10] - (P(10,22)*q0)*0.5f;
|
||||
nextP(2,22) = P(2,22) + P(0,22)*SF[6] + P(1,22)*SF[10] + P(3,22)*SF[8] + P(12,22)*SF[14] - P(10,22)*SPP[10] - (P(11,22)*q0)*0.5f;
|
||||
nextP(3,22) = P(3,22) + P(0,22)*SF[7] + P(1,22)*SF[6] + P(2,22)*SF[9] + P(10,22)*SF[15] - P(11,22)*SF[14] - (P(12,22)*q0)*0.5f;
|
||||
nextP(4,22) = P(4,22) + P(0,22)*SF[5] + P(1,22)*SF[3] - P(3,22)*SF[4] + P(2,22)*SPP[0] + P(13,22)*SPP[3] + P(14,22)*SPP[6] - P(15,22)*SPP[9];
|
||||
nextP(5,22) = P(5,22) + P(0,22)*SF[4] + P(2,22)*SF[3] + P(3,22)*SF[5] - P(1,22)*SPP[0] - P(13,22)*SPP[8] + P(14,22)*SPP[2] + P(15,22)*SPP[5];
|
||||
nextP(6,22) = P(6,22) + P(1,22)*SF[4] - P(2,22)*SF[5] + P(3,22)*SF[3] + P(0,22)*SPP[0] + P(13,22)*SPP[4] - P(14,22)*SPP[7] - P(15,22)*SPP[1];
|
||||
nextP(7,22) = P(7,22) + P(4,22)*dt;
|
||||
nextP(8,22) = P(8,22) + P(5,22)*dt;
|
||||
nextP(9,22) = P(9,22) + P(6,22)*dt;
|
||||
nextP(10,22) = P(10,22);
|
||||
nextP(11,22) = P(11,22);
|
||||
nextP(12,22) = P(12,22);
|
||||
nextP(13,22) = P(13,22);
|
||||
nextP(14,22) = P(14,22);
|
||||
nextP(15,22) = P(15,22);
|
||||
nextP(16,22) = P(16,22);
|
||||
nextP(17,22) = P(17,22);
|
||||
nextP(18,22) = P(18,22);
|
||||
nextP(19,22) = P(19,22);
|
||||
nextP(20,22) = P(20,22);
|
||||
nextP(21,22) = P(21,22);
|
||||
nextP(22,22) = P(22,22);
|
||||
nextP(0,23) = P(0,23) + P(1,23)*SF[9] + P(2,23)*SF[11] + P(3,23)*SF[10] + P(10,23)*SF[14] + P(11,23)*SF[15] + P(12,23)*SPP[10];
|
||||
nextP(1,23) = P(1,23) + P(0,23)*SF[8] + P(2,23)*SF[7] + P(3,23)*SF[11] - P(12,23)*SF[15] + P(11,23)*SPP[10] - (P(10,23)*q0)*0.5f;
|
||||
nextP(2,23) = P(2,23) + P(0,23)*SF[6] + P(1,23)*SF[10] + P(3,23)*SF[8] + P(12,23)*SF[14] - P(10,23)*SPP[10] - (P(11,23)*q0)*0.5f;
|
||||
nextP(3,23) = P(3,23) + P(0,23)*SF[7] + P(1,23)*SF[6] + P(2,23)*SF[9] + P(10,23)*SF[15] - P(11,23)*SF[14] - (P(12,23)*q0)*0.5f;
|
||||
nextP(4,23) = P(4,23) + P(0,23)*SF[5] + P(1,23)*SF[3] - P(3,23)*SF[4] + P(2,23)*SPP[0] + P(13,23)*SPP[3] + P(14,23)*SPP[6] - P(15,23)*SPP[9];
|
||||
nextP(5,23) = P(5,23) + P(0,23)*SF[4] + P(2,23)*SF[3] + P(3,23)*SF[5] - P(1,23)*SPP[0] - P(13,23)*SPP[8] + P(14,23)*SPP[2] + P(15,23)*SPP[5];
|
||||
nextP(6,23) = P(6,23) + P(1,23)*SF[4] - P(2,23)*SF[5] + P(3,23)*SF[3] + P(0,23)*SPP[0] + P(13,23)*SPP[4] - P(14,23)*SPP[7] - P(15,23)*SPP[1];
|
||||
nextP(7,23) = P(7,23) + P(4,23)*dt;
|
||||
nextP(8,23) = P(8,23) + P(5,23)*dt;
|
||||
nextP(9,23) = P(9,23) + P(6,23)*dt;
|
||||
nextP(10,23) = P(10,23);
|
||||
nextP(11,23) = P(11,23);
|
||||
nextP(12,23) = P(12,23);
|
||||
nextP(13,23) = P(13,23);
|
||||
nextP(14,23) = P(14,23);
|
||||
nextP(15,23) = P(15,23);
|
||||
nextP(16,23) = P(16,23);
|
||||
nextP(17,23) = P(17,23);
|
||||
nextP(18,23) = P(18,23);
|
||||
nextP(19,23) = P(19,23);
|
||||
nextP(20,23) = P(20,23);
|
||||
nextP(21,23) = P(21,23);
|
||||
nextP(22,23) = P(22,23);
|
||||
nextP(23,23) = P(23,23);
|
||||
|
||||
// capture largest difference
|
||||
float max_diff_fraction = 0.0f;
|
||||
int max_row, max_col;
|
||||
float max_old, max_new;
|
||||
|
||||
for (int col=0; col<=23; col++) {
|
||||
for (int row=0; row<=col; row++) {
|
||||
float diff_fraction = fabsf(nextP_sympy(row,col)-nextP(row,col)) / fabsf(nextP(row,col));
|
||||
if (diff_fraction > max_diff_fraction) {
|
||||
max_diff_fraction = diff_fraction;
|
||||
max_row = row;
|
||||
max_col = col;
|
||||
max_old = nextP(row,col);
|
||||
max_new = nextP_sympy(row,col);
|
||||
}
|
||||
}
|
||||
}
|
||||
if (max_diff_fraction > 5E-5f) {
|
||||
printf("Fail: Covariance Prediction max diff fraction = %e , old = %e , new = %e , location index = %i,%i\n",max_diff_fraction, max_old, max_new, max_row, max_col);
|
||||
} else {
|
||||
printf("Pass: Covariance Prediction max diff fraction = %e , old = %e , new = %e , location index = %i,%i\n",max_diff_fraction, max_old, max_new, max_row, max_col);
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
@@ -0,0 +1,489 @@
|
||||
from sympy import *
|
||||
from code_gen import *
|
||||
|
||||
# q: quaternion describing rotation from frame 1 to frame 2
|
||||
# returns a rotation matrix derived form q which describes the same
|
||||
# rotation
|
||||
def quat2Rot(q):
|
||||
q0 = q[0]
|
||||
q1 = q[1]
|
||||
q2 = q[2]
|
||||
q3 = q[3]
|
||||
|
||||
Rot = Matrix([[q0**2 + q1**2 - q2**2 - q3**2, 2*(q1*q2 - q0*q3), 2*(q1*q3 + q0*q2)],
|
||||
[2*(q1*q2 + q0*q3), q0**2 - q1**2 + q2**2 - q3**2, 2*(q2*q3 - q0*q1)],
|
||||
[2*(q1*q3-q0*q2), 2*(q2*q3 + q0*q1), q0**2 - q1**2 - q2**2 + q3**2]])
|
||||
|
||||
return Rot
|
||||
|
||||
def create_cov_matrix(i, j):
|
||||
if j >= i:
|
||||
return Symbol("P(" + str(i) + "," + str(j) + ")", real=True)
|
||||
# legacy array format
|
||||
# return Symbol("P[" + str(i) + "][" + str(j) + "]", real=True)
|
||||
else:
|
||||
return 0
|
||||
|
||||
def create_Tbs_matrix(i, j):
|
||||
return Symbol("Tbs(" + str(i) + "," + str(j) + ")", real=True)
|
||||
# legacy array format
|
||||
# return Symbol("Tbs[" + str(i) + "][" + str(j) + "]", real=True)
|
||||
|
||||
def quat_mult(p,q):
|
||||
r = Matrix([p[0] * q[0] - p[1] * q[1] - p[2] * q[2] - p[3] * q[3],
|
||||
p[0] * q[1] + p[1] * q[0] + p[2] * q[3] - p[3] * q[2],
|
||||
p[0] * q[2] - p[1] * q[3] + p[2] * q[0] + p[3] * q[1],
|
||||
p[0] * q[3] + p[1] * q[2] - p[2] * q[1] + p[3] * q[0]])
|
||||
|
||||
return r
|
||||
|
||||
def create_symmetric_cov_matrix():
|
||||
# define a symbolic covariance matrix
|
||||
P = Matrix(24,24,create_cov_matrix)
|
||||
|
||||
for index in range(24):
|
||||
for j in range(24):
|
||||
if index > j:
|
||||
P[index,j] = P[j,index]
|
||||
|
||||
return P
|
||||
|
||||
# generate equations for observation Jacobian and Kalman gain
|
||||
def generate_observation_equations(P,state,observation,variance):
|
||||
H = Matrix([observation]).jacobian(state)
|
||||
innov_var = H * P * H.T + Matrix([variance])
|
||||
assert(innov_var.shape[0] == 1)
|
||||
assert(innov_var.shape[1] == 1)
|
||||
K = P * H.T / innov_var[0,0]
|
||||
HK_simple = cse(Matrix([H.transpose(), K]), symbols("HK0:1000"), optimizations='basic')
|
||||
|
||||
return HK_simple
|
||||
|
||||
# generate equations for observation vector Jacobian and Kalman gain
|
||||
# n_obs is the vector dimension and must be >= 2
|
||||
def generate_observation_vector_equations(P,state,observation,variance,n_obs):
|
||||
K = zeros(24,n_obs)
|
||||
H = observation.jacobian(state)
|
||||
HK = zeros(n_obs*48,1)
|
||||
for index in range(n_obs):
|
||||
H[index,:] = Matrix([observation[index]]).jacobian(state)
|
||||
innov_var = H[index,:] * P * H[index,:].T + Matrix([variance])
|
||||
assert(innov_var.shape[0] == 1)
|
||||
assert(innov_var.shape[1] == 1)
|
||||
K[:,index] = P * H[index,:].T / innov_var[0,0]
|
||||
HK[index*48:(index+1)*48,0] = Matrix([H[index,:].transpose(), K[:,index]])
|
||||
|
||||
HK_simple = cse(HK, symbols("HK0:1000"), optimizations='basic')
|
||||
|
||||
return HK_simple
|
||||
|
||||
# write single observation equations to file
|
||||
def write_equations_to_file(equations,code_generator_id,n_obs):
|
||||
if (n_obs < 1):
|
||||
return
|
||||
|
||||
if (n_obs == 1):
|
||||
code_generator_id.print_string("Sub Expressions")
|
||||
code_generator_id.write_subexpressions(equations[0])
|
||||
code_generator_id.print_string("Observation Jacobians")
|
||||
code_generator_id.write_matrix(Matrix(equations[1][0][0:24]), "Hfusion")
|
||||
code_generator_id.print_string("Kalman gains")
|
||||
code_generator_id.write_matrix(Matrix(equations[1][0][24:]), "Kfusion")
|
||||
else:
|
||||
code_generator_id.print_string("Sub Expressions")
|
||||
code_generator_id.write_subexpressions(equations[0])
|
||||
for axis_index in range(n_obs):
|
||||
start_index = axis_index*48
|
||||
code_generator_id.print_string("Observation Jacobians - axis %i" % axis_index)
|
||||
code_generator_id.write_matrix(Matrix(equations[1][0][start_index:start_index+24]), "Hfusion")
|
||||
code_generator_id.print_string("Kalman gains - axis %i" % axis_index)
|
||||
code_generator_id.write_matrix(Matrix(equations[1][0][start_index+24:start_index+48]), "Kfusion")
|
||||
|
||||
return
|
||||
|
||||
# derive equations for sequential fusion of optical flow measurements
|
||||
def optical_flow_observation(P,state,R_to_body,vx,vy,vz):
|
||||
flow_code_generator = CodeGenerator("./generated/flow_generated.cpp")
|
||||
range = symbols("range", real=True) # range from camera focal point to ground along sensor Z axis
|
||||
obs_var = symbols("R_LOS", real=True) # optical flow line of sight rate measurement noise variance
|
||||
|
||||
# Define rotation matrix from body to sensor frame
|
||||
Tbs = Matrix(3,3,create_Tbs_matrix)
|
||||
|
||||
# Calculate earth relative velocity in a non-rotating sensor frame
|
||||
relVelSensor = Tbs * R_to_body * Matrix([vx,vy,vz])
|
||||
|
||||
# Divide by range to get predicted angular LOS rates relative to X and Y
|
||||
# axes. Note these are rates in a non-rotating sensor frame
|
||||
losRateSensorX = +relVelSensor[1]/range
|
||||
losRateSensorY = -relVelSensor[0]/range
|
||||
|
||||
# calculate the observation Jacobian and Kalman gains for the X axis
|
||||
equations = generate_observation_equations(P,state,losRateSensorX,obs_var)
|
||||
|
||||
flow_code_generator.print_string("X Axis Equations")
|
||||
write_equations_to_file(equations,flow_code_generator,1)
|
||||
|
||||
# calculate the observation Jacobian and Kalman gains for the Y axis
|
||||
equations = generate_observation_equations(P,state,losRateSensorY,obs_var)
|
||||
|
||||
flow_code_generator.print_string("Y Axis Equations")
|
||||
write_equations_to_file(equations,flow_code_generator,1)
|
||||
|
||||
flow_code_generator.close()
|
||||
|
||||
# calculate a combined result for a possible reduction in operations, but will use more stack
|
||||
observation = Matrix([relVelSensor[1]/range,-relVelSensor[0]/range])
|
||||
equations = generate_observation_vector_equations(P,state,observation,obs_var,2)
|
||||
flow_code_generator_alt = CodeGenerator("./generated/flow_generated_alt.cpp")
|
||||
write_equations_to_file(equations,flow_code_generator_alt,2)
|
||||
flow_code_generator_alt.close()
|
||||
|
||||
return
|
||||
|
||||
# Derive equations for sequential fusion of body frame velocity measurements
|
||||
def body_frame_velocity_observation(P,state,R_to_body,vx,vy,vz):
|
||||
obs_var = symbols("R_VEL", real=True) # measurement noise variance
|
||||
|
||||
# Calculate earth relative velocity in a non-rotating sensor frame
|
||||
vel_bf = R_to_body * Matrix([vx,vy,vz])
|
||||
|
||||
vel_bf_code_generator = CodeGenerator("./generated/vel_bf_generated.cpp")
|
||||
axes = [0,1,2]
|
||||
H_obs = vel_bf.jacobian(state) # observation Jacobians
|
||||
K_gain = zeros(24,3)
|
||||
for index in axes:
|
||||
equations = generate_observation_equations(P,state,vel_bf[index],obs_var)
|
||||
|
||||
vel_bf_code_generator.print_string("axis %i" % index)
|
||||
vel_bf_code_generator.write_subexpressions(equations[0])
|
||||
vel_bf_code_generator.write_matrix(Matrix(equations[1][0][0:24]), "H_VEL")
|
||||
vel_bf_code_generator.write_matrix(Matrix(equations[1][0][24:]), "Kfusion")
|
||||
|
||||
vel_bf_code_generator.close()
|
||||
|
||||
# calculate a combined result for a possible reduction in operations, but will use more stack
|
||||
equations = generate_observation_vector_equations(P,state,vel_bf,obs_var,3)
|
||||
|
||||
vel_bf_code_generator_alt = CodeGenerator("./generated/vel_bf_generated_alt.cpp")
|
||||
write_equations_to_file(equations,vel_bf_code_generator_alt,3)
|
||||
vel_bf_code_generator_alt.close()
|
||||
|
||||
# derive equations for fusion of dual antenna yaw measurement
|
||||
def gps_yaw_observation(P,state,R_to_body):
|
||||
obs_var = symbols("R_YAW", real=True) # measurement noise variance
|
||||
ant_yaw = symbols("ant_yaw", real=True) # yaw angle of antenna array axis wrt X body axis
|
||||
|
||||
# define antenna vector in body frame
|
||||
ant_vec_bf = Matrix([cos(ant_yaw),sin(ant_yaw),0])
|
||||
|
||||
# rotate into earth frame
|
||||
ant_vec_ef = R_to_body.T * ant_vec_bf
|
||||
|
||||
# Calculate the yaw angle from the projection
|
||||
observation = atan(ant_vec_ef[1]/ant_vec_ef[0])
|
||||
|
||||
equations = generate_observation_equations(P,state,observation,obs_var)
|
||||
|
||||
gps_yaw_code_generator = CodeGenerator("./generated/gps_yaw_generated.cpp")
|
||||
write_equations_to_file(equations,gps_yaw_code_generator,1)
|
||||
gps_yaw_code_generator.close()
|
||||
|
||||
return
|
||||
|
||||
# derive equations for fusion of declination
|
||||
def declination_observation(P,state,ix,iy):
|
||||
obs_var = symbols("R_DECL", real=True) # measurement noise variance
|
||||
|
||||
# the predicted measurement is the angle wrt magnetic north of the horizontal
|
||||
# component of the measured field
|
||||
observation = atan(iy/ix)
|
||||
|
||||
equations = generate_observation_equations(P,state,observation,obs_var)
|
||||
|
||||
mag_decl_code_generator = CodeGenerator("./generated/mag_decl_generated.cpp")
|
||||
write_equations_to_file(equations,mag_decl_code_generator,1)
|
||||
mag_decl_code_generator.close()
|
||||
|
||||
return
|
||||
|
||||
# derive equations for fusion of lateral body acceleration (multirotors only)
|
||||
def body_frame_accel_observation(P,state,R_to_body,vx,vy,vz,wx,wy):
|
||||
obs_var = symbols("R_ACC", real=True) # measurement noise variance
|
||||
Kaccx = symbols("Kaccx", real=True) # measurement noise variance
|
||||
Kaccy = symbols("Kaccy", real=True) # measurement noise variance
|
||||
|
||||
# use relationship between airspeed along the X and Y body axis and the
|
||||
# drag to predict the lateral acceleration for a multirotor vehicle type
|
||||
# where propulsion forces are generated primarily along the Z body axis
|
||||
|
||||
vrel = R_to_body*Matrix([vx-wx,vy-wy,vz]) # predicted wind relative velocity
|
||||
|
||||
# Use this nonlinear model for the prediction in the implementation only
|
||||
# It uses a ballistic coefficient for each axis
|
||||
# accXpred = -0.5*rho*vrel[0]*vrel[0]*BCXinv # predicted acceleration measured along X body axis
|
||||
# accYpred = -0.5*rho*vrel[1]*vrel[1]*BCYinv # predicted acceleration measured along Y body axis
|
||||
|
||||
# Use a simple viscous drag model for the linear estimator equations
|
||||
# Use the the derivative from speed to acceleration averaged across the
|
||||
# speed range. This avoids the generation of a dirac function in the derivation
|
||||
# The nonlinear equation will be used to calculate the predicted measurement in implementation
|
||||
observation = Matrix([-Kaccx*vrel[0],-Kaccy*vrel[1]])
|
||||
|
||||
acc_bf_code_generator = CodeGenerator("./generated/acc_bf_generated.cpp")
|
||||
H = observation.jacobian(state)
|
||||
K = zeros(24,2)
|
||||
axes = [0,1]
|
||||
for index in axes:
|
||||
equations = generate_observation_equations(P,state,observation[index],obs_var)
|
||||
acc_bf_code_generator.print_string("Axis %i equations" % index)
|
||||
write_equations_to_file(equations,acc_bf_code_generator,1)
|
||||
|
||||
acc_bf_code_generator.close()
|
||||
|
||||
# calculate a combined result for a possible reduction in operations, but will use more stack
|
||||
equations = generate_observation_vector_equations(P,state,observation,obs_var,2)
|
||||
|
||||
acc_bf_code_generator_alt = CodeGenerator("./generated/acc_bf_generated_alt.cpp")
|
||||
write_equations_to_file(equations,acc_bf_code_generator_alt,3)
|
||||
acc_bf_code_generator_alt.close()
|
||||
|
||||
return
|
||||
|
||||
# yaw fusion
|
||||
def yaw_observation(P,state,R_to_earth):
|
||||
yaw_code_generator = CodeGenerator("./generated/yaw_generated.cpp")
|
||||
|
||||
# Derive observation Jacobian for fusion of 321 sequence yaw measurement
|
||||
# Calculate the yaw (first rotation) angle from the 321 rotation sequence
|
||||
# Provide alternative angle that avoids singularity at +-pi/2 yaw
|
||||
angMeasA = atan(R_to_earth[1,0]/R_to_earth[0,0])
|
||||
H_YAW321_A = Matrix([angMeasA]).jacobian(state)
|
||||
H_YAW321_A_simple = cse(H_YAW321_A, symbols('SA0:200'))
|
||||
|
||||
angMeasB = pi/2 - atan(R_to_earth[0,0]/R_to_earth[1,0])
|
||||
H_YAW321_B = Matrix([angMeasB]).jacobian(state)
|
||||
H_YAW321_B_simple = cse(H_YAW321_B, symbols('SB0:200'))
|
||||
|
||||
yaw_code_generator.print_string("calculate 321 yaw observation matrix - option A")
|
||||
yaw_code_generator.write_subexpressions(H_YAW321_A_simple[0])
|
||||
yaw_code_generator.write_matrix(Matrix(H_YAW321_A_simple[1]).T, "H_YAW")
|
||||
|
||||
yaw_code_generator.print_string("calculate 321 yaw observation matrix - option B")
|
||||
yaw_code_generator.write_subexpressions(H_YAW321_B_simple[0])
|
||||
yaw_code_generator.write_matrix(Matrix(H_YAW321_B_simple[1]).T, "H_YAW")
|
||||
|
||||
# Derive observation Jacobian for fusion of 312 sequence yaw measurement
|
||||
# Calculate the yaw (first rotation) angle from an Euler 312 sequence
|
||||
# Provide alternative angle that avoids singularity at +-pi/2 yaw
|
||||
angMeasA = atan(-R_to_earth[0,1]/R_to_earth[1,1])
|
||||
H_YAW312_A = Matrix([angMeasA]).jacobian(state)
|
||||
H_YAW312_A_simple = cse(H_YAW312_A, symbols('SA0:200'))
|
||||
|
||||
angMeasB = pi/2 - atan(-R_to_earth[1,1]/R_to_earth[0,1])
|
||||
H_YAW312_B = Matrix([angMeasB]).jacobian(state)
|
||||
H_YAW312_B_simple = cse(H_YAW312_B, symbols('SB0:200'))
|
||||
|
||||
yaw_code_generator.print_string("calculate 312 yaw observation matrix - option A")
|
||||
yaw_code_generator.write_subexpressions(H_YAW312_A_simple[0])
|
||||
yaw_code_generator.write_matrix(Matrix(H_YAW312_A_simple[1]).T, "H_YAW")
|
||||
|
||||
yaw_code_generator.print_string("calculate 312 yaw observation matrix - option B")
|
||||
yaw_code_generator.write_subexpressions(H_YAW312_B_simple[0])
|
||||
yaw_code_generator.write_matrix(Matrix(H_YAW312_B_simple[1]).T, "H_YAW")
|
||||
|
||||
yaw_code_generator.close()
|
||||
|
||||
return
|
||||
|
||||
# 3D magnetometer fusion
|
||||
def mag_observation(P,state,R_to_body,i,ib):
|
||||
obs_var = symbols("R_MAG", real=True) # magnetometer measurement noise variance
|
||||
|
||||
m_mag = R_to_body * i + ib
|
||||
|
||||
# calculate a separate set of equations for each axis
|
||||
mag_code_generator = CodeGenerator("./generated/3Dmag_generated.cpp")
|
||||
|
||||
axes = [0,1,2]
|
||||
for index in axes:
|
||||
equations = generate_observation_equations(P,state,m_mag[index],obs_var)
|
||||
mag_code_generator.print_string("Axis %i equations" % index)
|
||||
write_equations_to_file(equations,mag_code_generator,1)
|
||||
|
||||
mag_code_generator.close()
|
||||
|
||||
# calculate a combined set of equations for a possible reduction in operations, but will use slighlty more stack
|
||||
equations = generate_observation_vector_equations(P,state,m_mag,obs_var,3)
|
||||
|
||||
mag_code_generator_alt = CodeGenerator("./generated/3Dmag_generated_alt.cpp")
|
||||
write_equations_to_file(equations,mag_code_generator_alt,3)
|
||||
mag_code_generator_alt.close()
|
||||
|
||||
return
|
||||
|
||||
# airspeed fusion
|
||||
def tas_observation(P,state,vx,vy,vz,wx,wy):
|
||||
obs_var = symbols("R_TAS", real=True) # true airspeed measurement noise variance
|
||||
|
||||
observation = sqrt((vx-wx)*(vx-wx)+(vy-wy)*(vy-wy)+vz*vz)
|
||||
|
||||
equations = generate_observation_equations(P,state,observation,obs_var)
|
||||
|
||||
tas_code_generator = CodeGenerator("./generated/tas_generated.cpp")
|
||||
write_equations_to_file(equations,tas_code_generator,1)
|
||||
tas_code_generator.close()
|
||||
|
||||
return
|
||||
|
||||
# sideslip fusion
|
||||
def beta_observation(P,state,R_to_body,vx,vy,vz,wx,wy):
|
||||
obs_var = symbols("R_BETA", real=True) # sideslip measurement noise variance
|
||||
|
||||
v_rel_ef = Matrix([vx-wx,vy-wy,vz])
|
||||
v_rel_bf = R_to_body * v_rel_ef
|
||||
observation = v_rel_bf[1]/v_rel_bf[0]
|
||||
|
||||
equations = generate_observation_equations(P,state,observation,obs_var)
|
||||
|
||||
beta_code_generator = CodeGenerator("./generated/beta_generated.cpp")
|
||||
write_equations_to_file(equations,beta_code_generator,1)
|
||||
beta_code_generator.close()
|
||||
|
||||
return
|
||||
|
||||
def generate_code():
|
||||
print('Starting code generation:')
|
||||
print('Creating symbolic variables ...')
|
||||
|
||||
dt = symbols("dt", real=True) # dt
|
||||
g = symbols("g", real=True) # gravity constant
|
||||
|
||||
r_hor_vel = symbols("R_hor_vel", real=True) # horizontal velocity noise variance
|
||||
r_ver_vel = symbols("R_vert_vel", real=True) # vertical velocity noise variance
|
||||
r_hor_pos = symbols("R_hor_pos", real=True) # horizontal position noise variance
|
||||
|
||||
# inputs, integrated gyro measurements
|
||||
# delta angle x y z
|
||||
d_ang_x, d_ang_y, d_ang_z = symbols("dax day daz", real=True) # delta angle x
|
||||
d_ang = Matrix([d_ang_x, d_ang_y, d_ang_z])
|
||||
|
||||
# inputs, integrated accelerometer measurements
|
||||
# delta velocity x y z
|
||||
d_v_x, d_v_y, d_v_z = symbols("dvx dvy dvz", real=True)
|
||||
d_v = Matrix([d_v_x, d_v_y,d_v_z])
|
||||
|
||||
u = Matrix([d_ang, d_v])
|
||||
|
||||
# input noise
|
||||
d_ang_x_var, d_ang_y_var, d_ang_z_var = symbols("daxVar dayVar dazVar", real=True)
|
||||
|
||||
d_v_x_var, d_v_y_var, d_v_z_var = symbols("dvxVar dvyVar dvzVar", real=True)
|
||||
|
||||
var_u = Matrix.diag(d_ang_x_var, d_ang_y_var, d_ang_z_var, d_v_x_var, d_v_y_var, d_v_z_var)
|
||||
|
||||
# define state vector
|
||||
|
||||
# attitude quaternion
|
||||
qw, qx, qy, qz = symbols("q0 q1 q2 q3", real=True)
|
||||
q = Matrix([qw,qx,qy,qz])
|
||||
R_to_earth = quat2Rot(q)
|
||||
R_to_body = R_to_earth.T
|
||||
|
||||
# velocity in NED local frame (north, east, down)
|
||||
vx, vy, vz = symbols("vn ve vd", real=True)
|
||||
v = Matrix([vx,vy,vz])
|
||||
|
||||
# position in NED local frame (north, east, down)
|
||||
px, py, pz = symbols("pn pe pd", real=True)
|
||||
p = Matrix([px,py,pz])
|
||||
|
||||
# delta angle bias x y z
|
||||
d_ang_bx, d_ang_by, d_ang_bz = symbols("dax_b day_b daz_b", real=True)
|
||||
d_ang_b = Matrix([d_ang_bx, d_ang_by, d_ang_bz])
|
||||
d_ang_true = d_ang - d_ang_b
|
||||
|
||||
# delta velocity bias x y z
|
||||
d_vel_bx, d_vel_by, d_vel_bz = symbols("dvx_b dvy_b dvz_b", real=True)
|
||||
d_vel_b = Matrix([d_vel_bx, d_vel_by, d_vel_bz])
|
||||
d_vel_true = d_v - d_vel_b
|
||||
|
||||
# earth magnetic field vector x y z
|
||||
ix, iy, iz = symbols("magN magE magD", real=True)
|
||||
i = Matrix([ix,iy,iz])
|
||||
|
||||
# earth magnetic field bias in body frame
|
||||
ibx, iby, ibz = symbols("ibx iby ibz", real=True)
|
||||
|
||||
ib = Matrix([ibx,iby,ibz])
|
||||
|
||||
# wind in local NE frame (north, east)
|
||||
wx, wy = symbols("vwn, vwe", real=True)
|
||||
w = Matrix([wx,wy])
|
||||
|
||||
# state vector at arbitrary time t
|
||||
state = Matrix([q,v,p,d_ang_b,d_vel_b,i,ib,w])
|
||||
|
||||
print('Defining state propagation ...')
|
||||
q_new = quat_mult(q, Matrix([1, 0.5 * d_ang_true[0], 0.5 * d_ang_true[1], 0.5 * d_ang_true[2]]))
|
||||
v_new = v + R_to_earth * d_vel_true + Matrix([0,0,g]) * dt
|
||||
p_new = p + v * dt
|
||||
|
||||
d_ang_b_new = d_ang_b
|
||||
d_vel_b_new = d_vel_b
|
||||
i_new = i
|
||||
ib_new = ib
|
||||
w_new = w
|
||||
|
||||
# predicted state vector at time t + dt
|
||||
state_new = Matrix([q_new, v_new, p_new, d_ang_b_new, d_vel_b_new, i_new, ib_new, w_new])
|
||||
|
||||
print('Computing state propagation jacobian ...')
|
||||
A = state_new.jacobian(state)
|
||||
G = state_new.jacobian(u)
|
||||
|
||||
P = create_symmetric_cov_matrix()
|
||||
|
||||
print('Computing covariance propagation ...')
|
||||
P_new = A * P * A.T + G * var_u * G.T
|
||||
|
||||
for index in range(24):
|
||||
for j in range(24):
|
||||
if index > j:
|
||||
P_new[index,j] = 0
|
||||
|
||||
print('Simplifying covariance propagation ...')
|
||||
P_new_simple = cse(P_new, symbols("PS0:400"), optimizations='basic')
|
||||
|
||||
print('Writing covariance propagation to file ...')
|
||||
cov_code_generator = CodeGenerator("./generated/covariance_generated.cpp")
|
||||
cov_code_generator.print_string("Equations for covariance matrix prediction, without process noise!")
|
||||
cov_code_generator.write_subexpressions(P_new_simple[0])
|
||||
cov_code_generator.write_matrix(Matrix(P_new_simple[1]), "nextP", True)
|
||||
|
||||
cov_code_generator.close()
|
||||
|
||||
# derive autocode for observation methods
|
||||
print('Generating heading observation code ...')
|
||||
yaw_observation(P,state,R_to_earth)
|
||||
print('Generating gps heading observation code ...')
|
||||
gps_yaw_observation(P,state,R_to_body)
|
||||
print('Generating mag observation code ...')
|
||||
mag_observation(P,state,R_to_body,i,ib)
|
||||
print('Generating declination observation code ...')
|
||||
declination_observation(P,state,ix,iy)
|
||||
print('Generating airspeed observation code ...')
|
||||
tas_observation(P,state,vx,vy,vz,wx,wy)
|
||||
print('Generating sideslip observation code ...')
|
||||
beta_observation(P,state,R_to_body,vx,vy,vz,wx,wy)
|
||||
print('Generating optical flow observation code ...')
|
||||
optical_flow_observation(P,state,R_to_body,vx,vy,vz)
|
||||
print('Generating body frame velocity observation code ...')
|
||||
body_frame_velocity_observation(P,state,R_to_body,vx,vy,vz)
|
||||
print('Generating body frame acceleration observation code ...')
|
||||
body_frame_accel_observation(P,state,R_to_body,vx,vy,vz,wx,wy)
|
||||
print('Code generation finished!')
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
generate_code()
|
||||
@@ -1,5 +1,6 @@
|
||||
#include <matrix/math.hpp>
|
||||
|
||||
#pragma once
|
||||
|
||||
// converts Tait-Bryan 312 sequence of rotations from frame 1 to frame 2
|
||||
// to the corresponding rotation matrix that rotates from frame 2 to frame 1
|
||||
@@ -18,3 +19,20 @@ float kahanSummation(float sum_previous, float input, float &accumulator);
|
||||
// calculate the inverse rotation matrix from a quaternion rotation
|
||||
// this produces the inverse rotation to that produced by the math library quaternion to Dcmf operator
|
||||
matrix::Dcmf quatToInverseRotMat(const matrix::Quatf &quat);
|
||||
|
||||
namespace ecl{
|
||||
inline float powf(float x, int exp)
|
||||
{
|
||||
float ret;
|
||||
if (exp > 0) {
|
||||
ret = x;
|
||||
for (int count = 1; count < exp; count++) {
|
||||
ret *= x;
|
||||
}
|
||||
return ret;
|
||||
} else if (exp < 0) {
|
||||
return 1.0f / ecl::powf(x, -exp);
|
||||
}
|
||||
return 1.0f;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -55,6 +55,7 @@ set(SRCS
|
||||
test_SensorRangeFinder.cpp
|
||||
test_geo.cpp
|
||||
test_geo_lookup.cpp
|
||||
test_EKF_utils.cpp
|
||||
)
|
||||
add_executable(ECL_GTESTS ${SRCS})
|
||||
|
||||
|
||||
+346
-346
@@ -3,349 +3,349 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
|
||||
85000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
|
||||
185000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
|
||||
285000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
|
||||
385000,0.982906,-0.00775222,-0.0134292,0.183453,0.000445835,0.000257906,-0.00515775,3.74516e-06,5.43776e-06,-7.479e-05,0,0,0,0,0,0,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,0.000168954,0.00247418,0.00247368,0.00483311,25.0004,25.0004,0.562573,0.259374,0.259374,4.00051,1e-06,1e-06,1e-06,0,0,4e-06,0,0,0,0,0,0,0,0
|
||||
485000,0.983207,-0.00779267,-0.0137988,0.181806,0.00149516,0.000487556,-0.0226199,0.000128857,3.88731e-05,0.012004,3.89716e-08,1.38181e-10,1.63937e-06,0,0,5.50648e-08,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,9.05599e-05,0.00251394,0.0025137,0.00257812,25.0144,25.0144,0.56266,0.609418,0.609418,0.802449,9.99999e-07,1e-06,9.98121e-07,0,0,4.00001e-06,0,0,0,0,0,0,0,0
|
||||
585000,0.983235,-0.00781283,-0.0140176,0.181633,0.000142817,0.000425494,-0.0407873,4.57242e-05,1.65576e-05,0.00559437,4.92314e-08,-1.10892e-10,2.06611e-06,0,0,1.69579e-07,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,6.31735e-05,0.00260317,0.00260303,0.00179033,7.81663,7.81663,0.56147,0.228172,0.228172,0.451638,9.99994e-07,9.99999e-07,9.91443e-07,0,0,4e-06,0,0,0,0,0,0,0,0
|
||||
685000,0.983166,-0.00784229,-0.0143846,0.181978,0.00273131,0.00149319,-0.0490413,0.00022836,0.000116917,0.0168581,1.00722e-08,-3.0771e-10,4.6197e-07,0,0,-3.88273e-07,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,4.99494e-05,0.00274313,0.00274301,0.00140913,7.85794,7.85794,0.557235,0.486139,0.486139,0.322026,9.99986e-07,9.99999e-07,9.77538e-07,0,0,3.99989e-06,0,0,0,0,0,0,0,0
|
||||
785000,0.983129,-0.00784217,-0.0146116,0.18216,0.00372337,0.00338268,-0.0598125,0.000120916,8.73528e-05,0.0131548,-2.03628e-08,-5.71333e-09,-8.26481e-07,0,0,-6.61608e-07,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,4.2747e-05,0.00292596,0.00292586,0.00120115,2.60141,2.60142,0.548781,0.195736,0.195736,0.259034,9.99886e-07,9.99914e-07,9.55188e-07,0,0,3.99951e-06,0,0,0,0,0,0,0,0
|
||||
885000,0.983035,-0.0078867,-0.0149611,0.182637,0.00537375,0.00623852,-0.0766231,0.000540952,0.000537906,-0.000216641,-1.6477e-07,-9.61094e-09,-6.50679e-06,0,0,9.87685e-08,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.8706e-05,0.00316567,0.00316556,0.00108283,2.66545,2.66547,0.534815,0.329581,0.329582,0.225286,9.99866e-07,9.99914e-07,9.23082e-07,0,0,3.99856e-06,0,0,0,0,0,0,0,0
|
||||
985000,0.982858,-0.00782901,-0.0152572,0.183566,0.00823652,0.00902617,-0.0901081,0.00123165,0.00123919,-0.00832501,-4.8827e-07,-1.48091e-08,-1.91202e-05,0,0,-1.56205e-07,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.82299e-05,0.00345539,0.00345524,0.00106637,2.75673,2.75676,0.521629,0.517615,0.517616,0.218362,9.99846e-07,9.99914e-07,8.92597e-07,0,0,3.99721e-06,0,0,0,0,0,0,0,0
|
||||
1085000,0.982942,-0.00793611,-0.0154438,0.183097,0.0140873,0.00748822,-0.109262,0.0013254,0.00114805,-0.0271139,-2.76351e-07,-7.16625e-08,-1.192e-05,0,0,2.02263e-06,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.6974e-05,0.00376377,0.00376359,0.00102686,1.29637,1.29641,0.497696,0.244345,0.244346,0.207776,9.98973e-07,9.99074e-07,8.44402e-07,0,0,3.99418e-06,0,0,0,0,0,0,0,0
|
||||
1185000,0.982986,-0.00789683,-0.0157172,0.182837,0.0200033,0.00774763,-0.10944,0.00300045,0.00190009,-0.0224507,-1.67147e-07,-5.74796e-08,-7.66274e-06,0,0,-3.17895e-06,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.64378e-05,0.00415181,0.00415156,0.00100717,1.42437,1.42444,0.469193,0.352138,0.352141,0.202802,9.98935e-07,9.99074e-07,7.89548e-07,0,0,3.98936e-06,0,0,0,0,0,0,0,0
|
||||
1285000,0.983228,-0.0078191,-0.0159541,0.181511,0.0248719,0.00741285,-0.118106,0.00314531,0.00131956,-0.0274478,4.83599e-07,-3.64063e-07,1.44699e-05,0,0,-5.99276e-06,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.61687e-05,0.00448529,0.00448496,0.000997098,0.899467,0.899538,0.437026,0.197243,0.197244,0.200584,9.94637e-07,9.94818e-07,7.29674e-07,0,0,3.98218e-06,0,0,0,0,0,0,0,0
|
||||
1385000,0.983298,-0.00779835,-0.0161705,0.181118,0.0336815,0.00815884,-0.117744,0.00609985,0.00212856,-0.0250338,6.08962e-07,-3.33023e-07,1.90582e-05,0,0,-1.3188e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.60413e-05,0.00496644,0.00496601,0.000990509,1.07437,1.07449,0.402816,0.274389,0.274394,0.199431,9.9459e-07,9.94818e-07,6.67293e-07,0,0,3.97225e-06,0,0,0,0,0,0,0,0
|
||||
1485000,0.983221,-0.00778091,-0.0161964,0.181532,0.0329266,0.0073408,-0.131168,0.0054041,0.00161758,-0.0377952,3.2572e-07,-1.54916e-06,1.05507e-05,0,0,-1.32214e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.58839e-05,0.00520925,0.00520879,0.000984313,0.83815,0.83827,0.368572,0.171805,0.171809,0.198527,9.80091e-07,9.80363e-07,6.05295e-07,0,0,3.95945e-06,0,0,0,0,0,0,0,0
|
||||
1585000,0.983218,-0.00787221,-0.0165617,0.181513,0.0407795,0.00829228,-0.142897,0.00908255,0.00236705,-0.0487389,3.18934e-07,-1.53709e-06,1.02505e-05,0,0,-1.50662e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.74386e-05,0.00576907,0.00576849,0.00102231,1.06615,1.06633,0.345438,0.239486,0.239496,0.207551,9.80056e-07,9.80363e-07,5.60027e-07,0,0,3.94785e-06,0,0,0,0,0,0,0,0
|
||||
1685000,0.983244,-0.00798178,-0.0164415,0.181374,0.0397497,0.00800314,-0.149395,0.00739773,0.0017971,-0.0545586,4.61745e-08,-4.39663e-06,1.25191e-05,0,0,-2.08158e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.70136e-05,0.00572877,0.00572826,0.00100996,0.909048,0.909223,0.313729,0.160449,0.160456,0.205396,9.44133e-07,9.44473e-07,5.02322e-07,0,0,3.92954e-06,0,0,0,0,0,0,0,0
|
||||
1785000,0.983211,-0.00812528,-0.0167314,0.181525,0.0500155,0.00828673,-0.150961,0.0119333,0.00261026,-0.0574123,-6.28687e-08,-4.33172e-06,8.13446e-06,0,0,-2.95762e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.67506e-05,0.00633743,0.00633678,0.00099398,1.18508,1.18535,0.284486,0.229233,0.22925,0.202407,9.44093e-07,9.44472e-07,4.48613e-07,0,0,3.90791e-06,0,0,0,0,0,0,0,0
|
||||
1885000,0.983329,-0.008071,-0.0162732,0.180926,0.0439593,0.00901281,-0.152979,0.00905303,0.00190364,-0.0623796,-6.43542e-07,-9.51365e-06,1.69775e-05,0,0,-3.75597e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.58607e-05,0.00582732,0.00582685,0.000975149,0.997286,0.997509,0.258346,0.157537,0.157547,0.198874,8.7715e-07,8.7754e-07,3.99727e-07,0,0,3.88319e-06,0,0,0,0,0,0,0,0
|
||||
1985000,0.983356,-0.00817263,-0.0166403,0.18074,0.0524564,0.0100551,-0.151652,0.0138998,0.00281358,-0.0616902,-5.74976e-07,-9.39287e-06,1.86412e-05,0,0,-5.10333e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.54401e-05,0.00644038,0.00643974,0.000953698,1.3017,1.30203,0.235188,0.231153,0.231176,0.194764,8.77119e-07,8.77538e-07,3.55598e-07,0,0,3.85509e-06,0,0,0,0,0,0,0,0
|
||||
2085000,0.983278,-0.00824902,-0.0159796,0.181223,0.0423133,0.00766312,-0.150052,0.00962687,0.00189525,-0.0592164,-1.97347e-06,-1.64931e-05,1.03483e-05,0,0,-6.7451e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.41815e-05,0.00545387,0.00545355,0.000930439,1.032,1.03222,0.215118,0.157316,0.157327,0.190412,7.81977e-07,7.8238e-07,3.16277e-07,0,0,3.82386e-06,0,0,0,0,0,0,0,0
|
||||
2185000,0.983296,-0.00821787,-0.0163173,0.181093,0.0499701,0.00842154,-0.151875,0.014255,0.00276072,-0.0637417,-1.93576e-06,-1.63949e-05,1.09397e-05,0,0,-7.80004e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.36451e-05,0.00602725,0.00602675,0.000905951,1.33555,1.33586,0.19779,0.234207,0.234233,0.185808,7.81957e-07,7.82377e-07,2.81393e-07,0,0,3.78909e-06,0,0,0,0,0,0,0,0
|
||||
2285000,0.983449,-0.00829695,-0.0155482,0.180329,0.0363965,0.00624905,-0.149364,0.00912446,0.00173222,-0.0631072,-3.09465e-06,-2.41594e-05,2.03215e-05,0,0,-9.45512e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.34003e-05,0.00478277,0.00478261,0.000917772,0.993006,0.993186,0.188684,0.15558,0.155591,0.189826,6.74557e-07,6.74939e-07,2.57849e-07,0,0,3.76059e-06,0,0,0,0,0,0,0,0
|
||||
2385000,0.983469,-0.00835843,-0.0157261,0.1802,0.0434517,0.00562693,-0.149239,0.0131525,0.00231492,-0.0614994,-3.04487e-06,-2.40114e-05,2.08998e-05,0,0,-0.000112629,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.26693e-05,0.00529045,0.00529019,0.000890197,1.27336,1.27361,0.175645,0.231693,0.231716,0.184795,6.74544e-07,6.74936e-07,2.2987e-07,0,0,3.71943e-06,0,0,0,0,0,0,0,0
|
||||
2485000,0.983603,-0.00828275,-0.0150001,0.17953,0.029255,0.0037607,-0.150956,0.00801574,0.00132731,-0.0648776,-4.27571e-06,-3.10751e-05,2.90678e-05,0,0,-0.00012596,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.1076e-05,0.00405365,0.00405362,0.000862728,0.907778,0.907908,0.164701,0.151099,0.151107,0.179986,5.7159e-07,5.71939e-07,2.05298e-07,0,0,3.67475e-06,0,0,0,0,0,0,0,0
|
||||
2585000,0.983643,-0.00840973,-0.0151349,0.179296,0.0323446,0.00229609,-0.153886,0.0110928,0.00167314,-0.0690116,-4.24891e-06,-3.09813e-05,2.90745e-05,0,0,-0.000139431,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.02732e-05,0.0044909,0.0044908,0.000835868,1.15351,1.15368,0.155524,0.223054,0.223072,0.175337,5.7158e-07,5.71936e-07,1.83745e-07,0,0,3.62596e-06,0,0,0,0,0,0,0,0
|
||||
2685000,0.98371,-0.00847264,-0.0145357,0.178976,0.0217589,0.00156795,-0.153275,0.00655819,0.000880254,-0.0681838,-5.45805e-06,-3.64499e-05,3.15734e-05,0,0,-0.000161173,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.87529e-05,0.00341288,0.00341295,0.000809219,0.808184,0.808272,0.147821,0.144645,0.144652,0.170893,4.81467e-07,4.81778e-07,1.64742e-07,0,0,3.57283e-06,0,0,0,0,0,0,0,0
|
||||
2785000,0.98369,-0.00842791,-0.0146958,0.17907,0.0271298,0.00123464,-0.150514,0.00913909,0.00102508,-0.0647036,-5.47649e-06,-3.62672e-05,2.79765e-05,0,0,-0.000187638,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.79807e-05,0.00378709,0.00378709,0.000783899,1.01998,1.02011,0.141514,0.210823,0.210836,0.166798,4.8146e-07,4.81775e-07,1.48141e-07,0,0,3.51578e-06,0,0,0,0,0,0,0,0
|
||||
2885000,0.983783,-0.00844618,-0.0142704,0.178596,0.0195799,-0.00138268,-0.152025,0.00545396,0.000471641,-0.0659934,-6.61286e-06,-4.04882e-05,3.07905e-05,0,0,-0.000207842,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.75279e-05,0.00290065,0.00290076,0.000786818,0.714774,0.714835,0.139977,0.137385,0.13739,0.169975,4.05328e-07,4.05602e-07,1.36973e-07,0,0,3.47017e-06,0,0,0,0,0,0,0,0
|
||||
2985000,0.983855,-0.00848407,-0.0143674,0.178188,0.022551,-0.00288663,-0.155036,0.00766761,0.000275074,-0.070213,-6.52766e-06,-4.04353e-05,3.35937e-05,0,0,-0.000224419,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.67624e-05,0.0032222,0.00322227,0.000761629,0.897624,0.897705,0.135474,0.197572,0.197582,0.16618,4.05323e-07,4.05599e-07,1.23686e-07,0,0,3.40535e-06,0,0,0,0,0,0,0,0
|
||||
3085000,0.983807,-0.00852936,-0.0145495,0.178437,0.0282543,-0.00545783,-0.158896,0.0102479,-0.000189071,-0.0749505,-6.53549e-06,-4.03283e-05,3.13232e-05,0,0,-0.00024195,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.61127e-05,0.003564,0.00356403,0.000737381,1.11474,1.11485,0.131739,0.282393,0.282411,0.162668,4.05318e-07,4.05597e-07,1.11949e-07,0,0,3.3358e-06,0,0,0,0,0,0,0,0
|
||||
3185000,0.983688,-0.00848064,-0.0142268,0.179119,0.0219764,-0.00760471,-0.160673,0.00671653,-0.00075708,-0.0803081,-8.02997e-06,-4.35435e-05,2.31909e-05,0,0,-0.000259185,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.48982e-05,0.00278001,0.00278011,0.000714218,0.794681,0.794739,0.12867,0.18485,0.184857,0.159519,3.41211e-07,3.41452e-07,1.01558e-07,0,0,3.26217e-06,0,0,0,0,0,0,0,0
|
||||
3285000,0.983703,-0.00851014,-0.0142393,0.179036,0.0249533,-0.00855829,-0.164702,0.00909614,-0.00161782,-0.0887615,-8.00248e-06,-4.34856e-05,2.31214e-05,0,0,-0.00027296,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.42591e-05,0.00307504,0.00307511,0.000692208,0.98363,0.983714,0.126108,0.261342,0.261356,0.156631,3.41207e-07,3.4145e-07,9.23739e-08,0,0,3.1839e-06,0,0,0,0,0,0,0,0
|
||||
3385000,0.983642,-0.00821894,-0.0139273,0.179407,0.0181045,-0.00707572,-0.163835,0.00592437,-0.00141375,-0.0871293,-9.65931e-06,-4.59989e-05,1.85514e-05,0,0,-0.000306306,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.31918e-05,0.00242841,0.00242851,0.000671221,0.711267,0.711318,0.123969,0.173306,0.173312,0.154065,2.86716e-07,2.86925e-07,8.4202e-08,0,0,3.10183e-06,0,0,0,0,0,0,0,0
|
||||
3485000,0.983566,-0.00821416,-0.0139639,0.179822,0.0229659,-0.00561835,-0.162854,0.00807939,-0.00205976,-0.087665,-9.69255e-06,-4.58424e-05,1.37131e-05,0,0,-0.000336241,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.26099e-05,0.00268391,0.00268399,0.000651288,0.878357,0.878441,0.122127,0.242741,0.242753,0.151721,2.86713e-07,2.86923e-07,7.69473e-08,0,0,3.01547e-06,0,0,0,0,0,0,0,0
|
||||
3585000,0.983571,-0.00802001,-0.0135971,0.179831,0.0184667,-0.00504873,-0.169073,0.00551618,-0.00140349,-0.0958653,-1.12525e-05,-4.80172e-05,1.26142e-05,0,0,-0.000352529,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.23001e-05,0.00213814,0.00213826,0.000651169,0.64357,0.643622,0.123406,0.163107,0.163112,0.155467,2.39917e-07,2.40096e-07,7.19936e-08,0,0,2.94806e-06,0,0,0,0,0,0,0,0
|
||||
3685000,0.983675,-0.00805637,-0.0136608,0.179254,0.0202823,-0.00578342,-0.166136,0.00759578,-0.00196568,-0.094842,-1.11054e-05,-4.7978e-05,1.71327e-05,0,0,-0.000388322,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.1743e-05,0.00235936,0.00235947,0.000632042,0.792727,0.792798,0.121856,0.226633,0.226643,0.153422,2.39915e-07,2.40094e-07,6.60401e-08,0,0,2.85523e-06,0,0,0,0,0,0,0,0
|
||||
3785000,0.983643,-0.00788794,-0.013498,0.179449,0.0143059,-0.00145491,-0.168314,0.00501935,-0.00114755,-0.100559,-1.25255e-05,-4.99104e-05,1.48532e-05,0,0,-0.000410309,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.09112e-05,0.00188821,0.00188834,0.000613845,0.586864,0.586915,0.120419,0.154123,0.154127,0.151619,1.99511e-07,1.99663e-07,6.06917e-08,0,0,2.75979e-06,0,0,0,0,0,0,0,0
|
||||
3885000,0.983686,-0.00787387,-0.013566,0.179208,0.0149644,-0.0014384,-0.166856,0.00661424,-0.00123588,-0.102399,-1.24461e-05,-4.98727e-05,1.67549e-05,0,0,-0.000440567,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.04136e-05,0.00207907,0.00207919,0.000596572,0.720756,0.720824,0.119001,0.212622,0.212631,0.149953,1.99509e-07,1.99662e-07,5.59051e-08,0,0,2.66146e-06,0,0,0,0,0,0,0,0
|
||||
3985000,0.983582,-0.00782581,-0.0133633,0.179795,0.0130527,-0.00088674,-0.166908,0.00436819,-0.000741638,-0.102399,-1.35171e-05,-5.145e-05,1.19718e-05,0,0,-0.000476217,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.96825e-05,0.0016659,0.00166605,0.000579989,0.53821,0.538255,0.11754,0.146154,0.146159,0.148396,1.64686e-07,1.64814e-07,5.15719e-08,0,0,2.56072e-06,0,0,0,0,0,0,0,0
|
||||
4085000,0.983524,-0.00779302,-0.0133144,0.18012,0.0153951,-0.00188179,-0.156312,0.00596055,-0.000878696,-0.0921034,-1.34963e-05,-5.1315e-05,9.32832e-06,0,0,-0.000532879,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.92245e-05,0.0018296,0.00182975,0.000564366,0.658725,0.658783,0.116075,0.20032,0.200329,0.147005,1.64684e-07,1.64813e-07,4.76888e-08,0,0,2.4589e-06,0,0,0,0,0,0,0,0
|
||||
4185000,0.983562,-0.00785847,-0.0130832,0.179923,0.0116707,-0.00229863,-0.158782,0.00399179,-0.000607056,-0.0991928,-1.43023e-05,-5.28073e-05,1.02073e-05,0,0,-0.000551467,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.90325e-05,0.00146433,0.00146451,0.000563687,0.494379,0.494413,0.117305,0.138992,0.138996,0.15126,1.34883e-07,1.34991e-07,4.50058e-08,0,0,2.3819e-06,0,0,0,0,0,0,0,0
|
||||
4285000,0.983622,-0.00793231,-0.0131451,0.179588,0.0149483,-0.00200575,-0.161876,0.00540754,-0.000838403,-0.105807,-1.424e-05,-5.28124e-05,1.2459e-05,0,0,-0.000571865,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.85913e-05,0.00160373,0.00160392,0.000548788,0.602968,0.603015,0.11563,0.189299,0.189306,0.149954,1.34882e-07,1.3499e-07,4.17451e-08,0,0,2.27864e-06,0,0,0,0,0,0,0,0
|
||||
4385000,0.983699,-0.00782217,-0.0130172,0.179182,0.012909,-0.0034482,-0.153749,0.00382945,-0.000663158,-0.0968789,-1.49164e-05,-5.41001e-05,1.46851e-05,0,0,-0.000625177,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.79686e-05,0.0012806,0.00128078,0.00053451,0.454423,0.45445,0.113817,0.132457,0.13246,0.14867,1.09661e-07,1.0975e-07,3.87687e-08,0,0,2.17513e-06,0,0,0,0,0,0,0,0
|
||||
4485000,0.983699,-0.00788973,-0.0129821,0.179178,0.0147311,-0.0015473,-0.150889,0.00531365,-0.000872531,-0.0961348,-1.48891e-05,-5.40628e-05,1.45279e-05,0,0,-0.000659595,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.75586e-05,0.00139845,0.00139865,0.000521001,0.551713,0.551752,0.111926,0.179252,0.179258,0.147471,1.0966e-07,1.09749e-07,3.60807e-08,0,0,2.07268e-06,0,0,0,0,0,0,0,0
|
||||
4585000,0.983643,-0.00784971,-0.0128659,0.1795,0.0120529,-0.00300697,-0.150866,0.00368752,-0.000620461,-0.0995364,-1.56101e-05,-5.52143e-05,1.22245e-05,0,0,-0.000685028,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.70221e-05,0.00111386,0.00111404,0.000508017,0.416979,0.417,0.109892,0.126413,0.126415,0.146259,8.85881e-08,8.86603e-08,3.36171e-08,0,0,1.97111e-06,0,0,0,0,0,0,0,0
|
||||
4685000,0.983711,-0.0078257,-0.0128314,0.179128,0.0124526,-0.00328027,-0.142685,0.00504528,-0.000870769,-0.0940295,-1.55456e-05,-5.52058e-05,1.39887e-05,0,0,-0.000728597,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.663e-05,0.00121283,0.00121302,0.000495742,0.503726,0.503752,0.107779,0.169948,0.169953,0.1451,8.85874e-08,8.86598e-08,3.13835e-08,0,0,1.87162e-06,0,0,0,0,0,0,0,0
|
||||
4785000,0.98367,-0.00765319,-0.0127624,0.179364,0.00413133,-0.0024387,-0.141588,0.00323698,-0.000626184,-0.095955,-1.61673e-05,-5.61616e-05,1.24285e-05,0,0,-0.000755018,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.61505e-05,0.00096404,0.000964206,0.000483915,0.381715,0.381729,0.105531,0.120761,0.120763,0.143905,7.12094e-08,7.12676e-08,2.93288e-08,0,0,1.77397e-06,0,0,0,0,0,0,0,0
|
||||
4885000,0.983705,-0.00761045,-0.0127964,0.179175,0.00540026,-0.00498621,-0.13838,0.00374827,-0.00101178,-0.0969353,-1.61295e-05,-5.61655e-05,1.35874e-05,0,0,-0.000782408,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.61518e-05,0.00104669,0.00104687,0.000483171,0.45891,0.458924,0.105757,0.161249,0.161252,0.14802,7.1209e-08,7.12673e-08,2.79086e-08,0,0,1.70225e-06,0,0,0,0,0,0,0,0
|
||||
4985000,0.983694,-0.00753245,-0.0126973,0.179243,0.00451065,-0.00351987,-0.131601,0.00239287,-0.000799296,-0.0932215,-1.66425e-05,-5.67613e-05,1.26185e-05,0,0,-0.000818231,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.56902e-05,0.000831009,0.000831162,0.000471894,0.348614,0.348624,0.103268,0.115446,0.115448,0.14671,5.70454e-08,5.70918e-08,2.61444e-08,0,0,1.60913e-06,0,0,0,0,0,0,0,0
|
||||
5085000,0.983647,-0.00741243,-0.0126383,0.179509,0.00550126,-0.00363457,-0.127284,0.00294956,-0.00120442,-0.0895937,-1.66556e-05,-5.67205e-05,1.10329e-05,0,0,-0.000852159,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.53618e-05,0.00089975,0.00089991,0.000461168,0.417163,0.417176,0.100736,0.153075,0.153077,0.145416,5.70449e-08,5.70913e-08,2.45336e-08,0,0,1.51944e-06,0,0,0,0,0,0,0,0
|
||||
5185000,0.983641,-0.00727397,-0.012687,0.179544,0.00366767,-0.00152422,-0.124138,0.00342073,-0.00147241,-0.0875618,-1.66449e-05,-5.67037e-05,1.07872e-05,0,0,-0.000881862,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.5049e-05,0.000971344,0.000971507,0.000450877,0.495392,0.495411,0.0981217,0.202288,0.202293,0.144061,5.70444e-08,5.70909e-08,2.30501e-08,0,0,1.43284e-06,0,0,0,0,0,0,0,0
|
||||
5285000,0.983651,-0.00713119,-0.0125976,0.179506,0.00249006,0.000246272,-0.113363,0.00211939,-0.000825767,-0.0813373,-1.70401e-05,-5.71256e-05,1.09745e-05,0,0,-0.000918191,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.46546e-05,0.000771238,0.000771374,0.000440952,0.378358,0.37837,0.0954424,0.145393,0.145395,0.142644,4.56124e-08,4.56492e-08,2.16749e-08,0,0,1.34956e-06,0,0,0,0,0,0,0,0
|
||||
5385000,0.983636,-0.00704012,-0.0126093,0.179586,0.000294446,0.00232863,-0.108653,0.00230815,-0.0007504,-0.0762983,-1.70448e-05,-5.70993e-05,1.00672e-05,0,0,-0.000949944,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.43534e-05,0.000830531,0.000830673,0.000431515,0.447235,0.447253,0.0927603,0.190825,0.190828,0.141237,4.5612e-08,4.56488e-08,2.04136e-08,0,0,1.27021e-06,0,0,0,0,0,0,0,0
|
||||
5485000,0.98362,-0.00703458,-0.012634,0.179672,-0.000395822,0.00549093,-0.10557,0.00121379,-5.95267e-05,-0.0771072,-1.72646e-05,-5.73536e-05,9.28163e-06,0,0,-0.000969248,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.4271e-05,0.000659984,0.000660103,0.000430796,0.342899,0.342914,0.0923274,0.138168,0.13817,0.1449,3.64558e-08,3.64848e-08,1.95252e-08,0,0,1.21314e-06,0,0,0,0,0,0,0,0
|
||||
5585000,0.983619,-0.00705725,-0.0126702,0.179677,-0.000705822,0.00840561,-0.0974005,0.00124481,0.000631885,-0.0694876,-1.72672e-05,-5.73366e-05,8.67199e-06,0,0,-0.00100262,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.39778e-05,0.000709028,0.000709155,0.000421763,0.403323,0.403344,0.0895482,0.180104,0.180107,0.143333,3.64554e-08,3.64845e-08,1.84245e-08,0,0,1.14021e-06,0,0,0,0,0,0,0,0
|
||||
5685000,0.983592,-0.00704666,-0.0125437,0.179834,-0.00115354,0.0100725,-0.0972898,0.000563971,0.00107906,-0.0690066,-1.72447e-05,-5.74888e-05,7.04758e-06,0,0,-0.0010214,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.36292e-05,0.000564435,0.000564542,0.000413047,0.310632,0.310649,0.086761,0.131396,0.131398,0.14171,2.91607e-08,2.91837e-08,1.73993e-08,0,0,1.07088e-06,0,0,0,0,0,0,0,0
|
||||
5785000,0.98364,-0.00692038,-0.0125231,0.179577,-0.00093727,0.0119372,-0.091111,0.000500787,0.0021569,-0.0629591,-1.72236e-05,-5.75018e-05,7.87883e-06,0,0,-0.00104929,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.33553e-05,0.000605002,0.000605112,0.000404722,0.363779,0.3638,0.0840194,0.17011,0.170113,0.140101,2.91604e-08,2.91834e-08,1.64533e-08,0,0,1.00549e-06,0,0,0,0,0,0,0,0
|
||||
5885000,0.983625,-0.00691013,-0.0125665,0.179656,0.00109684,0.0112451,-0.0875392,0.000322448,0.00220104,-0.0644419,-1.69679e-05,-5.76525e-05,7.3849e-06,0,0,-0.00106242,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.30589e-05,0.000482864,0.000482954,0.000396661,0.281196,0.281211,0.0812937,0.125064,0.125066,0.138443,2.33678e-08,2.3386e-08,1.55701e-08,0,0,9.43598e-07,0,0,0,0,0,0,0,0
|
||||
5985000,0.983579,-0.00686289,-0.0126868,0.179903,0.00181953,0.0123204,-0.0805733,0.00050405,0.00335484,-0.058575,-1.69991e-05,-5.76192e-05,5.73907e-06,0,0,-0.00108726,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.28135e-05,0.000516448,0.000516542,0.000388956,0.327824,0.327842,0.0786304,0.160807,0.16081,0.136806,2.33675e-08,2.33858e-08,1.47526e-08,0,0,8.85455e-07,0,0,0,0,0,0,0,0
|
||||
6085000,0.983538,-0.00692464,-0.0126092,0.180129,0.000832395,0.0109612,-0.0770675,0.000385034,0.00283613,-0.0567628,-1.66831e-05,-5.77748e-05,3.39581e-06,0,0,-0.00110366,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.25142e-05,0.000413539,0.000413618,0.000381523,0.254704,0.254717,0.0760008,0.119145,0.119146,0.13513,1.87758e-08,1.87903e-08,1.39879e-08,0,0,8.3063e-07,0,0,0,0,0,0,0,0
|
||||
6185000,0.98351,-0.00695142,-0.0125686,0.180281,0.000128293,0.0125409,-0.0755698,0.00048579,0.00403041,-0.0563871,-1.66997e-05,-5.77585e-05,2.57341e-06,0,0,-0.00111722,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.25073e-05,0.000441394,0.000441478,0.000380912,0.295783,0.295799,0.0752295,0.152173,0.152176,0.138085,1.87757e-08,1.87902e-08,1.34501e-08,0,0,7.91649e-07,0,0,0,0,0,0,0,0
|
||||
6285000,0.983486,-0.00698955,-0.0125771,0.180411,-0.00164073,0.0116774,-0.0764565,0.000224229,0.00327019,-0.060146,-1.6311e-05,-5.7945e-05,2.01428e-06,0,0,-0.00112346,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.22595e-05,0.00035478,0.000354847,0.00037374,0.231021,0.231032,0.0726396,0.113631,0.113633,0.136286,1.51362e-08,1.51479e-08,1.27729e-08,0,0,7.425e-07,0,0,0,0,0,0,0,0
|
||||
6385000,0.983509,-0.00694116,-0.0125178,0.180295,-0.000498553,0.0131742,-0.0755622,7.57358e-05,0.00450374,-0.0614799,-1.63015e-05,-5.79544e-05,2.48826e-06,0,0,-0.00113336,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.20443e-05,0.000377938,0.000378011,0.000366867,0.267186,0.267199,0.0701353,0.144185,0.144187,0.134521,1.51361e-08,1.51477e-08,1.21428e-08,0,0,6.9657e-07,0,0,0,0,0,0,0,0
|
||||
6485000,0.983183,-0.00694596,-0.0125173,0.182061,-0.00279071,0.00895075,-0.0715183,-6.998e-05,0.00344684,-0.0582517,-1.58942e-05,-5.81061e-05,2.14613e-06,0,0,-0.00114967,0.204181,0,0.433701,0,0,0,0,0,8.36293e-05,0.000301612,0.000301432,0.00246491,0.203869,0.203876,0.0676889,0.108482,0.108484,0.132734,1.22483e-08,1.22576e-08,1.16947e-08,0,0,6.53471e-07,0,0,0,0,0,0,0,0
|
||||
6585000,0.9831,-0.00690329,-0.0124773,0.182514,-0.00344542,0.010076,-0.072561,-0.00035842,0.00435147,-0.0600447,-1.58948e-05,-5.81062e-05,2.13877e-06,0,0,-0.00115791,0.204181,0,0.433701,0,0,0,0,0,5.75396e-05,0.000301975,0.000301877,0.0016966,0.206199,0.206208,0.0653051,0.135565,0.135568,0.130934,1.22484e-08,1.22577e-08,1.16944e-08,0,0,6.13077e-07,0,0,0,0,0,0,0,0
|
||||
6685000,0.983048,-0.00681051,-0.0124523,0.1828,-0.00648032,0.0103135,-0.0737935,-0.000604235,0.00340563,-0.0598123,-1.55142e-05,-5.81884e-05,2.09561e-06,0,0,-0.00116916,0.204181,0,0.433701,0,0,0,0,0,4.38648e-05,0.000302527,0.000302471,0.00129389,0.146946,0.146952,0.0630125,0.101684,0.101685,0.129174,1.00349e-08,1.00424e-08,1.1692e-08,0,0,5.7542e-07,0,0,0,0,0,0,0,0
|
||||
6785000,0.983032,-0.00684809,-0.0123882,0.182889,-0.00536464,0.0117271,-0.0704552,-0.00124012,0.00447011,-0.059244,-1.55151e-05,-5.81886e-05,2.0843e-06,0,0,-0.00118029,0.204181,0,0.433701,0,0,0,0,0,3.72502e-05,0.000303823,0.000303791,0.00109902,0.154911,0.154917,0.0622368,0.123703,0.123705,0.131649,1.0035e-08,1.00425e-08,1.16904e-08,0,0,5.48818e-07,0,0,0,0,0,0,0,0
|
||||
6885000,0.983026,-0.00667298,-0.0123047,0.182933,-0.00490025,0.00904224,-0.0668893,-0.00113641,0.00351827,-0.0579714,-1.5152e-05,-5.82084e-05,2.06337e-06,0,0,-0.00119167,0.204181,0,0.433701,0,0,0,0,0,3.10188e-05,0.000303273,0.000303257,0.000915618,0.120509,0.120512,0.060031,0.0940152,0.0940161,0.129809,8.41448e-09,8.42067e-09,1.16857e-08,0,0,5.15359e-07,0,0,0,0,0,0,0,0
|
||||
6985000,0.983069,-0.00663134,-0.0122667,0.182704,-0.0057765,0.00983905,-0.0629462,-0.00171787,0.00445596,-0.0551108,-1.5152e-05,-5.82094e-05,2.09925e-06,0,0,-0.00120447,0.204181,0,0.433701,0,0,0,0,0,2.66018e-05,0.000304925,0.000304924,0.000785282,0.13312,0.133124,0.0578959,0.112545,0.112546,0.12797,8.41458e-09,8.42077e-09,1.16801e-08,0,0,4.84069e-07,0,0,0,0,0,0,0,0
|
||||
7085000,0.983052,-0.00655397,-0.0121744,0.182804,-0.00590083,0.0127082,-0.0626764,-0.00153764,0.00375204,-0.0560237,-1.48072e-05,-5.81998e-05,2.08131e-06,0,0,-0.00121164,0.204181,0,0.433701,0,0,0,0,0,2.33258e-05,0.000300928,0.000300935,0.000688054,0.113243,0.113245,0.0558522,0.0872968,0.0872977,0.126181,7.23271e-09,7.23794e-09,1.16716e-08,0,0,4.54942e-07,0,0,0,0,0,0,0,0
|
||||
7185000,0.983031,-0.00649565,-0.0122412,0.182917,-0.00695103,0.014394,-0.0611044,-0.0022296,0.00516143,-0.0577484,-1.48086e-05,-5.81985e-05,2.02651e-06,0,0,-0.00121758,0.204181,0,0.433701,0,0,0,0,0,2.07794e-05,0.000302555,0.000302568,0.000612911,0.129671,0.129672,0.0538782,0.103849,0.10385,0.124397,7.2328e-09,7.23804e-09,1.16612e-08,0,0,4.27716e-07,0,0,0,0,0,0,0,0
|
||||
7285000,0.98305,-0.00647744,-0.0122486,0.182817,-0.00664438,0.0172145,-0.0568319,-0.00298328,0.00672417,-0.0530891,-1.48085e-05,-5.81985e-05,2.05721e-06,0,0,-0.00123103,0.204181,0,0.433701,0,0,0,0,0,1.87541e-05,0.000304545,0.000304565,0.000553234,0.148827,0.148829,0.0519915,0.123562,0.123564,0.122664,7.2329e-09,7.23814e-09,1.16479e-08,0,0,4.0238e-07,0,0,0,0,0,0,0,0
|
||||
7385000,0.983078,-0.00645403,-0.0122442,0.182662,-0.00779282,0.0176512,-0.0533839,-0.00262855,0.00616267,-0.0496051,-1.44472e-05,-5.81789e-05,2.08659e-06,0,0,-0.00124229,0.204181,0,0.433701,0,0,0,0,0,1.71046e-05,0.000294144,0.000294166,0.000504813,0.13654,0.13654,0.0501721,0.0980018,0.0980028,0.120941,6.37196e-09,6.3765e-09,1.16309e-08,0,0,3.78698e-07,0,0,0,0,0,0,0,0
|
||||
7485000,0.98312,-0.00641682,-0.0122776,0.182437,-0.00579404,0.0203021,-0.0488508,-0.00330608,0.00807324,-0.0460054,-1.44443e-05,-5.81808e-05,2.23691e-06,0,0,-0.00125293,0.204181,0,0.433701,0,0,0,0,0,1.61004e-05,0.000295793,0.000295817,0.000474992,0.158482,0.158482,0.0495032,0.117248,0.117249,0.122934,6.37205e-09,6.37659e-09,1.16162e-08,0,0,3.61967e-07,0,0,0,0,0,0,0,0
|
||||
7585000,0.983147,-0.00657502,-0.0122558,0.182286,-0.00418596,0.0195106,-0.0443831,-0.00266743,0.0071671,-0.0396888,-1.40703e-05,-5.81725e-05,2.30995e-06,0,0,-0.00126597,0.204181,0,0.433701,0,0,0,0,0,1.49166e-05,0.000277846,0.000277872,0.000440135,0.147643,0.147642,0.047777,0.094765,0.0947657,0.121171,5.75633e-09,5.76039e-09,1.1593e-08,0,0,3.40973e-07,0,0,0,0,0,0,0,0
|
||||
7685000,0.983153,-0.00660154,-0.0123176,0.182248,-0.00473826,0.0227289,-0.0424067,-0.00312227,0.00933429,-0.0330012,-1.40702e-05,-5.817e-05,2.29988e-06,0,0,-0.00127874,0.204181,0,0.433701,0,0,0,0,0,1.39211e-05,0.000279008,0.000279037,0.000410738,0.171442,0.17144,0.046131,0.114462,0.114462,0.119463,5.75642e-09,5.76047e-09,1.15663e-08,0,0,3.21431e-07,0,0,0,0,0,0,0,0
|
||||
7785000,0.983148,-0.00658573,-0.0123348,0.182278,-0.00226495,0.0205997,-0.0439898,-0.00240331,0.00811043,-0.0370098,-1.3717e-05,-5.81856e-05,2.24495e-06,0,0,-0.001279,0.204181,0,0.433701,0,0,0,0,0,1.30712e-05,0.000253254,0.000253278,0.000385694,0.158201,0.158198,0.0445471,0.093531,0.0935314,0.117771,5.3355e-09,5.33922e-09,1.15349e-08,0,0,3.03159e-07,0,0,0,0,0,0,0,0
|
||||
7885000,0.983136,-0.00661292,-0.0124083,0.182335,-0.00381574,0.024156,-0.0435014,-0.00279766,0.0103331,-0.0396533,-1.3717e-05,-5.8185e-05,2.23824e-06,0,0,-0.00128089,0.204181,0,0.433701,0,0,0,0,0,1.23573e-05,0.000253912,0.000253938,0.000364185,0.182472,0.182469,0.0430245,0.114101,0.114101,0.116098,5.33558e-09,5.3393e-09,1.14993e-08,0,0,2.86074e-07,0,0,0,0,0,0,0,0
|
||||
7985000,0.983142,-0.00667064,-0.0123308,0.182306,-0.00268074,0.0215113,-0.0392962,-0.00217073,0.00880345,-0.0358011,-1.34041e-05,-5.82164e-05,2.31201e-06,0,0,-0.00128965,0.204181,0,0.433701,0,0,0,0,0,1.17315e-05,0.000221905,0.000221927,0.000345606,0.164349,0.164346,0.0415732,0.0934545,0.0934547,0.114479,5.06865e-09,5.07217e-09,1.14589e-08,0,0,2.70158e-07,0,0,0,0,0,0,0,0
|
||||
8085000,0.98312,-0.00656391,-0.0123292,0.182429,-0.001756,0.024541,-0.0395255,-0.00235715,0.0110874,-0.038266,-1.3409e-05,-5.82106e-05,2.061e-06,0,0,-0.00129127,0.204181,0,0.433701,0,0,0,0,0,1.13556e-05,0.000222153,0.000222175,0.000334554,0.187941,0.187939,0.0410301,0.114855,0.114855,0.116192,5.06874e-09,5.07225e-09,1.14255e-08,0,0,2.58918e-07,0,0,0,0,0,0,0,0
|
||||
8185000,0.983107,-0.00674614,-0.0122585,0.182496,-0.000516045,0.0248095,-0.0356893,-0.0016496,0.00940557,-0.0334884,-1.31594e-05,-5.82469e-05,1.94032e-06,0,0,-0.00130025,0.204181,0,0.433701,0,0,0,0,0,1.08626e-05,0.000187026,0.000187043,0.00032006,0.164327,0.164325,0.0396605,0.0936525,0.0936525,0.114553,4.91643e-09,4.91982e-09,1.13763e-08,0,0,2.44775e-07,0,0,0,0,0,0,0,0
|
||||
8285000,0.983117,-0.00673721,-0.012245,0.182441,0.00174062,0.0272348,-0.0329184,-0.00160609,0.0119881,-0.0319919,-1.31594e-05,-5.82437e-05,1.8926e-06,0,0,-0.00130513,0.204181,0,0.433701,0,0,0,0,0,1.04299e-05,0.000187039,0.000187058,0.000307403,0.186136,0.186134,0.038345,0.115494,0.115493,0.112936,4.9165e-09,4.9199e-09,1.13218e-08,0,0,2.31536e-07,0,0,0,0,0,0,0,0
|
||||
8385000,0.983119,-0.00683781,-0.0122332,0.182431,-0.000197723,0.023194,-0.0309734,-0.000994337,0.00986905,-0.028256,-1.29696e-05,-5.8289e-05,1.92543e-06,0,0,-0.00131195,0.204181,0,0.433701,0,0,0,0,0,1.0054e-05,0.000152453,0.000152466,0.000296302,0.158093,0.158091,0.0370917,0.093431,0.093431,0.111373,4.84083e-09,4.84416e-09,1.12621e-08,0,0,2.19186e-07,0,0,0,0,0,0,0,0
|
||||
8485000,0.983147,-0.00675063,-0.012232,0.182281,-0.000560704,0.025823,-0.0314358,-0.00100639,0.01228,-0.0322828,-1.2963e-05,-5.82963e-05,2.25437e-06,0,0,-0.00131101,0.204181,0,0.433701,0,0,0,0,0,9.73085e-06,0.000152443,0.000152456,0.000286557,0.177457,0.177455,0.0358884,0.115159,0.115159,0.109833,4.8409e-09,4.84423e-09,1.11967e-08,0,0,2.07615e-07,0,0,0,0,0,0,0,0
|
||||
8585000,0.983158,-0.00684223,-0.0123253,0.182212,0.000680482,0.0221068,-0.0259982,-0.000679085,0.00989538,-0.0268822,-1.28383e-05,-5.83282e-05,2.23771e-06,0,0,-0.0013188,0.204181,0,0.433701,0,0,0,0,0,9.43262e-06,0.000121392,0.000121399,0.000277997,0.147029,0.147027,0.0347417,0.0924249,0.0924248,0.108344,4.80965e-09,4.81296e-09,1.11259e-08,0,0,1.9681e-07,0,0,0,0,0,0,0,0
|
||||
8685000,0.983189,-0.0068897,-0.0124131,0.18204,0.000650779,0.0227219,-0.0271251,-0.00065114,0.0121241,-0.0285423,-1.28341e-05,-5.83315e-05,2.42653e-06,0,0,-0.00131964,0.204181,0,0.433701,0,0,0,0,0,9.17431e-06,0.000121552,0.00012156,0.000270466,0.163671,0.163669,0.0336406,0.113491,0.113491,0.106878,4.80972e-09,4.81302e-09,1.10493e-08,0,0,1.86678e-07,0,0,0,0,0,0,0,0
|
||||
8785000,0.983187,-0.00697111,-0.0123633,0.182051,0.00182275,0.0188252,-0.0259459,-0.000390793,0.0094815,-0.0250907,-1.27676e-05,-5.83475e-05,2.30121e-06,0,0,-0.00132517,0.204181,0,0.433701,0,0,0,0,0,9.05543e-06,9.57126e-05,9.57159e-05,0.000267074,0.133243,0.133242,0.0332244,0.0905757,0.0905755,0.108315,4.79995e-09,4.80325e-09,1.09881e-08,0,0,1.79498e-07,0,0,0,0,0,0,0,0
|
||||
8885000,0.983223,-0.00703599,-0.0123589,0.181854,0.00220797,0.0205486,-0.0223637,-0.000167995,0.011474,-0.0192426,-1.27571e-05,-5.83494e-05,2.67692e-06,0,0,-0.0013325,0.204181,0,0.433701,0,0,0,0,0,8.85382e-06,9.61919e-05,9.61966e-05,0.000261097,0.147172,0.14717,0.0321875,0.110563,0.110563,0.106843,4.80001e-09,4.8033e-09,1.09014e-08,0,0,1.70453e-07,0,0,0,0,0,0,0,0
|
||||
8985000,0.98326,-0.00706045,-0.0122733,0.18166,0.00135301,0.0182992,-0.0203376,-3.35371e-05,0.0089335,-0.0208623,-1.2719e-05,-5.83707e-05,3.20666e-06,0,0,-0.00133286,0.204181,0,0.433701,0,0,0,0,0,8.67669e-06,7.59675e-05,7.5969e-05,0.000255842,0.118441,0.11844,0.0311992,0.0880246,0.0880245,0.10542,4.79826e-09,4.80154e-09,1.08092e-08,0,0,1.61991e-07,0,0,0,0,0,0,0,0
|
||||
9085000,0.983311,-0.00708758,-0.0123437,0.181378,0.00182529,0.0208409,-0.0215807,0.000119018,0.0108439,-0.0204796,-1.27058e-05,-5.8381e-05,3.80445e-06,0,0,-0.0013349,0.204181,0,0.433701,0,0,0,0,0,8.51906e-06,7.68654e-05,7.68674e-05,0.000251232,0.129979,0.129978,0.0302501,0.10667,0.10667,0.10402,4.79831e-09,4.8016e-09,1.07112e-08,0,0,1.54042e-07,0,0,0,0,0,0,0,0
|
||||
9185000,0.983343,-0.00716545,-0.0123713,0.181197,0.00472661,0.0167822,-0.0195919,0.000284011,0.00859231,-0.0202335,-1.26906e-05,-5.8392e-05,4.3375e-06,0,0,-0.00133681,0.204181,0,0.433701,0,0,0,0,0,8.38312e-06,6.18199e-05,6.18192e-05,0.000247177,0.104093,0.104092,0.0293383,0.0849867,0.0849866,0.102643,4.79833e-09,4.80161e-09,1.06074e-08,0,0,1.46572e-07,0,0,0,0,0,0,0,0
|
||||
9285000,0.983367,-0.00702949,-0.0121977,0.181082,0.00695749,0.0179993,-0.0177571,0.000925636,0.0103106,-0.0174081,-1.26824e-05,-5.83944e-05,4.64891e-06,0,0,-0.00134061,0.204181,0,0.433701,0,0,0,0,0,8.26617e-06,6.31891e-05,6.31893e-05,0.000243635,0.113585,0.113584,0.0284693,0.102182,0.102182,0.101313,4.79839e-09,4.80166e-09,1.04984e-08,0,0,1.39574e-07,0,0,0,0,0,0,0,0
|
||||
9385000,0.98336,-0.00693635,-0.0122383,0.181121,0.0071192,0.0186239,-0.0161599,0.00166452,0.0121575,-0.0171828,-1.26869e-05,-5.83876e-05,4.39566e-06,0,0,-0.00134211,0.204181,0,0.433701,0,0,0,0,0,8.25366e-06,6.47995e-05,6.47994e-05,0.000243234,0.12352,0.12352,0.0281473,0.122375,0.122375,0.102592,4.79845e-09,4.80172e-09,1.04132e-08,0,0,1.34608e-07,0,0,0,0,0,0,0,0
|
||||
9485000,0.983388,-0.00704946,-0.0122897,0.18096,0.00622851,0.0143605,-0.0137522,0.00170274,0.00953531,-0.0131018,-1.2687e-05,-5.83845e-05,4.67067e-06,0,0,-0.00134646,0.204181,0,0.433701,0,0,0,0,0,8.15536e-06,5.43623e-05,5.43605e-05,0.000240479,0.0988759,0.0988753,0.0273285,0.097425,0.097425,0.101261,4.79831e-09,4.80158e-09,1.0295e-08,0,0,1.28327e-07,0,0,0,0,0,0,0,0
|
||||
9585000,0.983362,-0.00708731,-0.0122672,0.181103,0.00569406,0.0134295,-0.0143234,0.00222381,0.0109117,-0.0160443,-1.2696e-05,-5.83781e-05,4.26688e-06,0,0,-0.00134523,0.204181,0,0.433701,0,0,0,0,0,8.08079e-06,5.64666e-05,5.64659e-05,0.000238071,0.107162,0.107161,0.0265417,0.115774,0.115774,0.0999538,4.79836e-09,4.80162e-09,1.01715e-08,0,0,1.22414e-07,0,0,0,0,0,0,0,0
|
||||
9685000,0.983374,-0.00714829,-0.0122007,0.181039,0.00486144,0.0107893,-0.0110384,0.00205615,0.00850537,-0.0135156,-1.27058e-05,-5.83673e-05,4.17944e-06,0,0,-0.00134812,0.204181,0,0.433701,0,0,0,0,0,8.00498e-06,4.94871e-05,4.94857e-05,0.000235995,0.0862588,0.0862579,0.0257911,0.092652,0.0926519,0.0986901,4.79807e-09,4.80132e-09,1.00435e-08,0,0,1.16862e-07,0,0,0,0,0,0,0,0
|
||||
9785000,0.983361,-0.0071318,-0.012153,0.181112,0.00613534,0.012232,-0.0115416,0.00262879,0.00967422,-0.0138337,-1.27175e-05,-5.83548e-05,3.59567e-06,0,0,-0.00134876,0.204181,0,0.433701,0,0,0,0,0,7.94076e-06,5.20886e-05,5.2088e-05,0.000234196,0.0933303,0.0933296,0.0250696,0.109292,0.109292,0.0974481,4.79811e-09,4.80136e-09,9.91072e-09,0,0,1.1163e-07,0,0,0,0,0,0,0,0
|
||||
9885000,0.983379,-0.00714935,-0.0120775,0.18102,0.00755453,0.00904403,-0.00984277,0.00237585,0.00742259,-0.0139233,-1.27152e-05,-5.83578e-05,3.93555e-06,0,0,-0.00134946,0.204181,0,0.433701,0,0,0,0,0,7.89121e-06,4.77462e-05,4.7745e-05,0.00023264,0.0758739,0.0758733,0.024381,0.0880405,0.0880404,0.0962476,4.79804e-09,4.80128e-09,9.77388e-09,0,0,1.06711e-07,0,0,0,0,0,0,0,0
|
||||
9985000,0.983354,-0.00714698,-0.012153,0.181153,0.00905707,0.00844355,-0.00874687,0.00318381,0.00823885,-0.0149431,-1.27265e-05,-5.83469e-05,3.38667e-06,0,0,-0.00134943,0.204181,0,0.433701,0,0,0,0,0,7.84931e-06,5.08368e-05,5.08358e-05,0.000231296,0.0820986,0.0820981,0.0237188,0.103155,0.103155,0.0950676,4.79808e-09,4.80131e-09,9.63287e-09,0,0,1.02071e-07,0,0,0,0,0,0,0,0
|
||||
10085000,0.983347,-0.00713167,-0.0122924,0.181184,0.00717711,0.00377816,-0.00754097,0.00292305,0.00617939,-0.0133466,-1.27313e-05,-5.83395e-05,2.99579e-06,0,0,-0.00135111,0.204181,0,0.433701,0,0,0,0,0,7.8913e-06,4.84582e-05,4.84554e-05,0.000232608,0.0676717,0.0676709,0.0234799,0.0837081,0.083708,0.0961849,4.79807e-09,4.8013e-09,9.52458e-09,0,0,9.8765e-08,0,0,0,0,0,0,0,0
|
||||
10185000,0.98331,-0.00710591,-0.0122117,0.18139,0.0050176,0.00412533,-0.00585023,0.00351238,0.0065896,-0.0133605,-1.2748e-05,-5.83222e-05,2.1641e-06,0,0,-0.0013516,0.204181,0,0.433701,0,0,0,0,0,7.86112e-06,5.2022e-05,5.20202e-05,0.000231593,0.0733978,0.0733969,0.0228551,0.0975028,0.0975027,0.0950087,4.79811e-09,4.80133e-09,9.37714e-09,0,0,9.45753e-08,0,0,0,0,0,0,0,0
|
||||
10285000,0.983341,-0.00717174,-0.0121188,0.181227,0.00448319,0.00274066,-0.00689189,0.00284079,0.00488064,-0.0132468,-1.27298e-05,-5.83415e-05,2.61407e-06,0,0,-0.00135207,0.204181,0,0.433701,0,0,0,0,0,7.83148e-06,5.10696e-05,5.10682e-05,0.000230727,0.0615549,0.0615542,0.0222584,0.0797331,0.0797329,0.0938714,4.79695e-09,4.80016e-09,9.22674e-09,0,0,9.0629e-08,0,0,0,0,0,0,0,0
|
||||
10385000,0.98249,-0.00712816,-0.0120529,0.185789,0.00719306,0.00200989,-0.00298336,0.00077468,2.98475e-05,-0.0114183,-1.27287e-05,-5.83394e-05,2.62434e-06,0,0,-0.00135338,0.204706,0.00196982,0.434395,0,0,0,0,0,6.39327e-05,5.22096e-05,5.20548e-05,0.00177858,0.034724,0.034724,0.0374564,0.12528,0.12528,0.0867783,4.79704e-09,4.80025e-09,9.22677e-09,0,0,8.70915e-08,0,0,0,0,0,0,0,0
|
||||
10485000,0.982349,-0.00703601,-0.0120072,0.18654,0.00748085,0.00135395,-0.00193104,0.0015003,0.000194954,-0.0067598,-1.27269e-05,-5.83332e-05,2.60444e-06,0,0,-0.0013566,0.204706,0.00196982,0.434395,0,0,0,0,0,4.81406e-05,5.25101e-05,5.23973e-05,0.00134012,0.0353689,0.0353688,0.0375608,0.126252,0.126252,0.0808878,4.79714e-09,4.80034e-09,9.22634e-09,0,0,8.41135e-08,0,0,0,0,0,0,0,0
|
||||
10585000,0.982488,-0.00699465,-0.0119472,0.185813,0.0061154,0.000616676,-0.000628686,0.0011734,-0.00345086,-0.00580305,-1.27279e-05,-5.83433e-05,2.66111e-06,0,0,-0.00135713,0.204706,0.00196982,0.434395,0,0,0,0,0,3.86532e-05,5.29427e-05,5.28554e-05,0.00107544,0.0318294,0.0318292,0.0352723,0.084859,0.084859,0.0763573,4.79716e-09,4.80035e-09,9.22519e-09,0,0,8.15701e-08,0,0,0,0,0,0,0,0
|
||||
10685000,0.98249,-0.00695664,-0.0119826,0.185799,0.00660942,-0.00174935,-0.000519127,0.00180228,-0.00351191,-0.00490483,-1.27277e-05,-5.8342e-05,2.65073e-06,0,0,-0.00135773,0.204706,0.00196982,0.434395,0,0,0,0,0,3.36591e-05,5.37694e-05,5.3694e-05,0.000937318,0.0331945,0.033194,0.0353181,0.0865709,0.0865709,0.0744962,4.79725e-09,4.80044e-09,9.22371e-09,0,0,7.98997e-08,0,0,0,0,0,0,0,0
|
||||
10785000,0.982489,-0.00696168,-0.0120896,0.1858,0.00737691,-0.00300667,0.000364341,0.00171922,-0.00316178,-0.00196135,-1.27197e-05,-5.83522e-05,2.6394e-06,0,0,-0.00135951,0.204706,0.00196982,0.434395,0,0,0,0,0,2.87288e-05,5.43145e-05,5.42498e-05,0.000800521,0.0306288,0.0306281,0.033191,0.0656959,0.0656959,0.0717259,4.79677e-09,4.79995e-09,9.22068e-09,0,0,7.79243e-08,0,0,0,0,0,0,0,0
|
||||
10885000,0.982591,-0.0069498,-0.0121354,0.185254,0.0079189,-0.00305563,0.000567794,0.00248568,-0.00352072,-0.00133615,-1.2717e-05,-5.8354e-05,2.76384e-06,0,0,-0.00135984,0.204706,0.00196982,0.434395,0,0,0,0,0,2.51015e-05,5.56202e-05,5.55647e-05,0.000699048,0.032658,0.0326571,0.0330675,0.067967,0.0679669,0.0700806,4.79687e-09,4.80004e-09,9.21624e-09,0,0,7.62041e-08,0,0,0,0,0,0,0,0
|
||||
10985000,0.982595,-0.00694933,-0.0122443,0.185227,0.00628729,0.00238811,0.00257047,0.00225655,-0.00267844,0.00149545,-1.2733e-05,-5.83679e-05,2.73816e-06,0,0,-0.00136101,0.204706,0.00196982,0.434395,0,0,0,0,0,2.22798e-05,5.60437e-05,5.5994e-05,0.000620951,0.0306195,0.0306186,0.0310543,0.0551375,0.0551375,0.0684177,4.79462e-09,4.79779e-09,9.21027e-09,0,0,7.46926e-08,0,0,0,0,0,0,0,0
|
||||
11085000,0.982497,-0.00707951,-0.0122305,0.185741,0.00715688,0.00462366,0.00444658,0.00290039,-0.00238893,0.00415347,-1.27358e-05,-5.83621e-05,2.5592e-06,0,0,-0.00136226,0.204706,0.00196982,0.434395,0,0,0,0,0,2.0068e-05,5.78171e-05,5.77758e-05,0.000559052,0.0332659,0.0332647,0.0307894,0.0579097,0.0579096,0.0678385,4.79471e-09,4.79788e-09,9.20249e-09,0,0,7.33684e-08,0,0,0,0,0,0,0,0
|
||||
11185000,0.982475,-0.00710064,-0.0121894,0.185863,0.00690952,0.00638772,0.00768243,0.0032939,-0.00169443,0.00882484,-1.27139e-05,-5.83549e-05,2.46328e-06,0,0,-0.00136391,0.204706,0.00196982,0.434395,0,0,0,0,0,1.82491e-05,5.79153e-05,5.78798e-05,0.000508935,0.0314297,0.0314285,0.0288866,0.048959,0.0489589,0.0667991,4.78829e-09,4.79144e-09,9.19279e-09,0,0,7.2199e-08,0,0,0,0,0,0,0,0
|
||||
11285000,0.982457,-0.00711106,-0.0122252,0.185954,0.00609506,0.00591773,0.00874468,0.00390194,-0.0010233,0.00862288,-1.27152e-05,-5.83549e-05,2.41219e-06,0,0,-0.00136343,0.204706,0.00196982,0.434395,0,0,0,0,0,1.67682e-05,6.01365e-05,6.01051e-05,0.000467579,0.0346498,0.0346483,0.0284996,0.0522163,0.0522161,0.0668724,4.78838e-09,4.79154e-09,9.1809e-09,0,0,7.1172e-08,0,0,0,0,0,0,0,0
|
||||
11385000,0.982455,-0.00703082,-0.0122149,0.185967,0.00497077,0.00647418,0.00783496,0.00331084,-0.000626791,0.00676195,-1.26982e-05,-5.84176e-05,2.38463e-06,0,0,-0.00136216,0.204706,0.00196982,0.434395,0,0,0,0,0,1.58385e-05,5.97453e-05,5.97155e-05,0.000441789,0.032762,0.0327607,0.0268619,0.0453285,0.0453283,0.0672749,4.77425e-09,4.7774e-09,9.17044e-09,0,0,7.04811e-08,0,0,0,0,0,0,0,0
|
||||
11485000,0.98249,-0.00694938,-0.0121942,0.185786,0.00358352,0.00578158,0.00950918,0.00368951,8.17779e-06,0.00997326,-1.26965e-05,-5.84165e-05,2.43212e-06,0,0,-0.00136317,0.204706,0.00196982,0.434395,0,0,0,0,0,1.47336e-05,6.23824e-05,6.23556e-05,0.000411337,0.0365082,0.0365065,0.0263978,0.0490661,0.0490658,0.0677349,4.77435e-09,4.77749e-09,9.15428e-09,0,0,6.96577e-08,0,0,0,0,0,0,0,0
|
||||
11585000,0.982489,-0.00704469,-0.0121654,0.185792,0.00519945,0.00563578,0.0100204,0.00321796,0.00013188,0.0113267,-1.26591e-05,-5.84768e-05,2.39697e-06,0,0,-0.00136394,0.204706,0.00196982,0.434395,0,0,0,0,0,1.37993e-05,6.13706e-05,6.13469e-05,0.000385355,0.0343511,0.0343497,0.0247429,0.0432992,0.0432989,0.0671538,4.74822e-09,4.75135e-09,9.13554e-09,0,0,6.89278e-08,0,0,0,0,0,0,0,0
|
||||
11685000,0.982502,-0.00700968,-0.0121155,0.185726,0.00564276,0.00798346,0.0117568,0.0037692,0.000810153,0.011552,-1.26584e-05,-5.84784e-05,2.44424e-06,0,0,-0.00136359,0.204706,0.00196982,0.434395,0,0,0,0,0,1.29971e-05,6.43847e-05,6.43638e-05,0.000363001,0.0385546,0.038553,0.024215,0.0475075,0.0475072,0.0677985,4.74832e-09,4.75144e-09,9.11393e-09,0,0,6.82875e-08,0,0,0,0,0,0,0,0
|
||||
11785000,0.98254,-0.00710707,-0.0120829,0.185523,0.0042563,0.00844405,0.0125792,0.0031215,-9.49955e-05,0.0143243,-1.24727e-05,-5.86325e-05,2.66361e-06,0,0,-0.00136417,0.204706,0.00196982,0.434395,0,0,0,0,0,1.23061e-05,6.26892e-05,6.26702e-05,0.000343625,0.0359874,0.0359862,0.0226927,0.0423102,0.0423099,0.0672496,4.70587e-09,4.70897e-09,9.08926e-09,0,0,6.77191e-08,0,0,0,0,0,0,0,0
|
||||
11885000,0.982525,-0.00718948,-0.0119859,0.185603,0.00702313,0.00877238,0.0116126,0.00361325,0.000721109,0.0156474,-1.2476e-05,-5.86294e-05,2.50198e-06,0,0,-0.00136419,0.204706,0.00196982,0.434395,0,0,0,0,0,1.1697e-05,6.60327e-05,6.60175e-05,0.000326749,0.040601,0.0405998,0.0221319,0.0469687,0.0469683,0.0679443,4.70595e-09,4.70906e-09,9.06156e-09,0,0,6.72211e-08,0,0,0,0,0,0,0,0
|
||||
11985000,0.982543,-0.00727689,-0.0120285,0.185503,0.00792936,0.00994221,0.0107363,0.00400545,-0.000104188,0.0131021,-1.24341e-05,-5.86194e-05,2.53609e-06,0,0,-0.00136328,0.204706,0.00196982,0.434395,0,0,0,0,0,1.1322e-05,6.36416e-05,6.36277e-05,0.00031652,0.0375202,0.0375195,0.0209308,0.0419946,0.0419943,0.0685372,4.64337e-09,4.64644e-09,9.03866e-09,0,0,6.68844e-08,0,0,0,0,0,0,0,0
|
||||
12085000,0.982523,-0.0071957,-0.0120869,0.18561,0.00962046,0.0097641,0.0133348,0.00488759,0.000842444,0.0198671,-1.24355e-05,-5.86131e-05,2.40936e-06,0,0,-0.00136494,0.204706,0.00196982,0.434395,0,0,0,0,0,1.08479e-05,6.72633e-05,6.72502e-05,0.000303143,0.0424534,0.0424527,0.0203698,0.0470688,0.0470684,0.069219,4.64346e-09,4.64653e-09,9.00514e-09,0,0,6.64845e-08,0,0,0,0,0,0,0,0
|
||||
12185000,0.98251,-0.00709445,-0.0120618,0.185684,0.0093811,0.00910126,0.0126802,0.00407767,0.00170695,0.0215173,-1.252e-05,-5.87733e-05,2.12878e-06,0,0,-0.00136508,0.204706,0.00196982,0.434395,0,0,0,0,0,1.04138e-05,6.42226e-05,6.421e-05,0.000291367,0.0388427,0.0388424,0.019123,0.0420977,0.0420974,0.0685745,4.55827e-09,4.56129e-09,8.96802e-09,0,0,6.61246e-08,0,0,0,0,0,0,0,0
|
||||
12285000,0.982494,-0.00714666,-0.0120538,0.185766,0.00715931,0.00782774,0.0110894,0.0049152,0.0025465,0.0221272,-1.25235e-05,-5.87703e-05,1.95699e-06,0,0,-0.00136492,0.204706,0.00196982,0.434395,0,0,0,0,0,1.00415e-05,6.80651e-05,6.80544e-05,0.000280956,0.0440438,0.0440433,0.0185756,0.0475412,0.0475409,0.0691661,4.55836e-09,4.56137e-09,8.92747e-09,0,0,6.58117e-08,0,0,0,0,0,0,0,0
|
||||
12385000,0.982502,-0.007196,-0.0119778,0.185725,0.00582798,0.00607615,0.011579,0.00405052,0.00200233,0.0192436,-1.24361e-05,-5.89632e-05,1.83179e-06,0,0,-0.00136401,0.204706,0.00196982,0.434395,0,0,0,0,0,9.70054e-06,6.445e-05,6.44403e-05,0.000271743,0.0398981,0.0398978,0.0174671,0.0424385,0.0424382,0.0684575,4.44944e-09,4.45238e-09,8.88311e-09,0,0,6.55256e-08,0,0,0,0,0,0,0,0
|
||||
12485000,0.982479,-0.00719731,-0.0119893,0.185849,0.00637676,0.00689552,0.0154454,0.004668,0.00263356,0.0212864,-1.24389e-05,-5.89599e-05,1.68226e-06,0,0,-0.00136416,0.204706,0.00196982,0.434395,0,0,0,0,0,9.41567e-06,6.84581e-05,6.84498e-05,0.000263561,0.0452657,0.0452656,0.0169503,0.0481969,0.0481965,0.0689326,4.44952e-09,4.45246e-09,8.8352e-09,0,0,6.52787e-08,0,0,0,0,0,0,0,0
|
||||
12585000,0.982454,-0.0072742,-0.0119237,0.185983,0.00850121,0.00242017,0.0171141,0.00509891,0.000746111,0.022594,-1.20859e-05,-5.90188e-05,1.45797e-06,0,0,-0.00136406,0.204706,0.00196982,0.434395,0,0,0,0,0,9.15895e-06,6.43741e-05,6.43666e-05,0.000256295,0.0406722,0.0406723,0.0159743,0.0428917,0.0428915,0.0681627,4.31754e-09,4.32039e-09,8.78333e-09,0,0,6.50465e-08,0,0,0,0,0,0,0,0
|
||||
12685000,0.982456,-0.00724858,-0.0119413,0.185969,0.00881647,0.00064036,0.0172508,0.00590889,0.000898649,0.0255181,-1.20877e-05,-5.90161e-05,1.35895e-06,0,0,-0.00136432,0.204706,0.00196982,0.434395,0,0,0,0,0,9.02857e-06,6.84952e-05,6.84885e-05,0.000252758,0.0462009,0.0462009,0.0156637,0.0489096,0.0489093,0.0697071,4.31762e-09,4.32048e-09,8.74195e-09,0,0,6.48989e-08,0,0,0,0,0,0,0,0
|
||||
12785000,0.982517,-0.00741934,-0.01181,0.185652,0.00929772,-0.00107547,0.0184449,0.00543171,-0.00172132,0.0271069,-1.15976e-05,-5.90568e-05,1.89322e-06,0,0,-0.00136424,0.204706,0.00196982,0.434395,0,0,0,0,0,8.81159e-06,6.4029e-05,6.40237e-05,0.000246897,0.0412306,0.041231,0.014802,0.0433748,0.0433746,0.0688567,4.16406e-09,4.16681e-09,8.6833e-09,0,0,6.46992e-08,0,0,0,0,0,0,0,0
|
||||
12885000,0.982557,-0.00740359,-0.0117467,0.185442,0.00917778,-0.00241726,0.0192872,0.00639291,-0.00189591,0.030456,-1.15919e-05,-5.90613e-05,2.17021e-06,0,0,-0.00136452,0.204706,0.00196982,0.434395,0,0,0,0,0,8.61892e-06,6.82119e-05,6.82081e-05,0.000241699,0.0468514,0.0468519,0.0143753,0.0495995,0.0495993,0.0690942,4.16414e-09,4.16688e-09,8.621e-09,0,0,6.45346e-08,0,0,0,0,0,0,0,0
|
||||
12985000,0.982597,-0.00741127,-0.0117199,0.185234,0.00768258,-0.000922228,0.0196694,0.00505323,-0.00149371,0.0319912,-1.17337e-05,-5.92772e-05,2.41536e-06,0,0,-0.00136445,0.204706,0.00196982,0.434395,0,0,0,0,0,8.44356e-06,6.34513e-05,6.34476e-05,0.000237082,0.0415891,0.0415897,0.0136285,0.0438376,0.0438374,0.0682039,3.99163e-09,3.99424e-09,8.55466e-09,0,0,6.43606e-08,0,0,0,0,0,0,0,0
|
||||
13085000,0.982612,-0.00742081,-0.0116452,0.185158,0.00881011,-0.0007578,0.018093,0.00587426,-0.00153219,0.0319906,-1.17266e-05,-5.92856e-05,2.79372e-06,0,0,-0.00136409,0.204706,0.00196982,0.434395,0,0,0,0,0,8.30502e-06,6.76514e-05,6.76494e-05,0.00023297,0.0472763,0.0472774,0.0132529,0.0502215,0.0502214,0.0683195,3.9917e-09,3.99431e-09,8.48448e-09,0,0,6.42233e-08,0,0,0,0,0,0,0,0
|
||||
13185000,0.982621,-0.00743525,-0.0115935,0.185109,0.00507857,-0.00231682,0.0172219,0.0027871,-0.00261669,0.032985,-1.16555e-05,-5.96786e-05,2.9877e-06,0,0,-0.00136394,0.204706,0.00196982,0.434395,0,0,0,0,0,8.17677e-06,6.26637e-05,6.26613e-05,0.000229331,0.0417982,0.0417991,0.0126108,0.0442521,0.0442521,0.0674041,3.80333e-09,3.80581e-09,8.41057e-09,0,0,6.40639e-08,0,0,0,0,0,0,0,0
|
||||
13285000,0.982625,-0.00744819,-0.0115774,0.185091,0.00423994,-0.00318631,0.0154547,0.00318509,-0.00287653,0.0336257,-1.16568e-05,-5.9678e-05,2.92756e-06,0,0,-0.00136377,0.204706,0.00196982,0.434395,0,0,0,0,0,8.14459e-06,6.6841e-05,6.68397e-05,0.000228498,0.0475196,0.0475206,0.0124249,0.0507555,0.0507555,0.0685859,3.80341e-09,3.80589e-09,8.35279e-09,0,0,6.39775e-08,0,0,0,0,0,0,0,0
|
||||
13385000,0.982616,-0.00740036,-0.0116695,0.185136,0.00313819,-0.00201624,0.0145272,0.00248403,-0.00219834,0.0335567,-1.1805e-05,-5.97568e-05,2.66996e-06,0,0,-0.00136349,0.204706,0.00196982,0.434395,0,0,0,0,0,8.03647e-06,6.16839e-05,6.16814e-05,0.000225598,0.0418812,0.0418822,0.0118689,0.0446066,0.0446066,0.0676267,3.60269e-09,3.60502e-09,8.27236e-09,0,0,6.38211e-08,0,0,0,0,0,0,0,0
|
||||
13485000,0.982614,-0.00737255,-0.0116301,0.185151,0.0039196,-0.000182102,0.0152908,0.00283498,-0.00226076,0.0323445,-1.18063e-05,-5.97573e-05,2.6248e-06,0,0,-0.00136306,0.204706,0.00196982,0.434395,0,0,0,0,0,7.94655e-06,6.58016e-05,6.58001e-05,0.000223035,0.0475902,0.0475916,0.0115979,0.0511955,0.0511956,0.067562,3.60276e-09,3.60508e-09,8.18834e-09,0,0,6.37154e-08,0,0,0,0,0,0,0,0
|
||||
13585000,0.982587,-0.00738124,-0.011702,0.185286,0.00724906,-0.000698113,0.016679,0.0050479,-0.00190479,0.0305596,-1.16859e-05,-5.93746e-05,2.36135e-06,0,0,-0.00136249,0.204706,0.00196982,0.434395,0,0,0,0,0,7.86948e-06,6.0527e-05,6.05251e-05,0.000220777,0.0418369,0.041838,0.0111269,0.0448984,0.0448984,0.066604,3.39349e-09,3.39567e-09,8.10091e-09,0,0,6.35571e-08,0,0,0,0,0,0,0,0
|
||||
13685000,0.982619,-0.00731818,-0.0116175,0.185125,0.00678674,-0.00213123,0.0162861,0.00574181,-0.00204751,0.0330021,-1.16817e-05,-5.93782e-05,2.57059e-06,0,0,-0.0013626,0.204706,0.00196982,0.434395,0,0,0,0,0,7.79214e-06,6.45547e-05,6.45539e-05,0.000218804,0.0475431,0.0475443,0.0109072,0.0515447,0.0515448,0.066474,3.39356e-09,3.39573e-09,8.01012e-09,0,0,6.346e-08,0,0,0,0,0,0,0,0
|
||||
13785000,0.982604,-0.00727078,-0.0117389,0.185201,0.0131668,0.000807323,0.0164211,0.00878519,-0.000180167,0.0326131,-1.18016e-05,-5.87536e-05,2.28015e-06,0,0,-0.00136217,0.204706,0.00196982,0.434395,0,0,0,0,0,7.72819e-06,5.92028e-05,5.92014e-05,0.00021707,0.0417398,0.0417409,0.0105116,0.0451311,0.0451312,0.0655283,3.17933e-09,3.18135e-09,7.91618e-09,0,0,6.3293e-08,0,0,0,0,0,0,0,0
|
||||
13885000,0.982631,-0.0071936,-0.0117105,0.185063,0.014427,0.00180544,0.0176846,0.0101366,-2.25254e-05,0.03499,-1.17921e-05,-5.87623e-05,2.74953e-06,0,0,-0.00136227,0.204706,0.00196982,0.434395,0,0,0,0,0,7.67554e-06,6.31152e-05,6.31144e-05,0.000215551,0.047403,0.0474045,0.0103402,0.0518151,0.0518153,0.06535,3.17939e-09,3.18141e-09,7.81918e-09,0,0,6.32003e-08,0,0,0,0,0,0,0,0
|
||||
13985000,0.982642,-0.00725844,-0.0114517,0.185019,0.0143739,0.00268472,0.0166985,0.00798612,-0.00142438,0.0353415,-1.16459e-05,-5.92988e-05,3.05884e-06,0,0,-0.00136205,0.204706,0.00196982,0.434395,0,0,0,0,0,7.70661e-06,5.77185e-05,5.77181e-05,0.000216358,0.041578,0.0415794,0.0101129,0.0453116,0.0453118,0.0654802,2.96355e-09,2.96541e-09,7.74439e-09,0,0,6.30434e-08,0,0,0,0,0,0,0,0
|
||||
14085000,0.98258,-0.00724832,-0.0113889,0.185348,0.0118246,-0.00160341,0.0185108,0.00938498,-0.0013917,0.0338465,-1.16684e-05,-5.92789e-05,1.94909e-06,0,0,-0.00136159,0.204706,0.00196982,0.434395,0,0,0,0,0,7.66644e-06,6.14937e-05,6.14944e-05,0.000215179,0.0471822,0.0471832,0.00998406,0.052017,0.0520173,0.0652622,2.96361e-09,2.96547e-09,7.64238e-09,0,0,6.29521e-08,0,0,0,0,0,0,0,0
|
||||
14185000,0.982539,-0.007231,-0.0113201,0.185574,0.00943342,-0.000323042,0.0174636,0.00858729,-0.00101221,0.0316089,-1.17914e-05,-5.93523e-05,1.18852e-06,0,0,-0.00136065,0.204706,0.00196982,0.434395,0,0,0,0,0,7.62991e-06,5.6088e-05,5.60882e-05,0.000214155,0.0413471,0.0413479,0.00970742,0.0454475,0.0454477,0.0643371,2.74931e-09,2.75101e-09,7.53783e-09,0,0,6.27499e-08,0,0,0,0,0,0,0,0
|
||||
14285000,0.982533,-0.00715574,-0.0113128,0.185609,0.0106055,-0.000764381,0.0163153,0.00945603,-0.00112592,0.0353157,-1.1792e-05,-5.93506e-05,1.14051e-06,0,0,-0.00136096,0.204706,0.00196982,0.434395,0,0,0,0,0,7.60163e-06,5.97097e-05,5.97103e-05,0.000213263,0.0469117,0.0469126,0.00962001,0.0521618,0.0521621,0.0640997,2.74937e-09,2.75107e-09,7.43088e-09,0,0,6.26567e-08,0,0,0,0,0,0,0,0
|
||||
14385000,0.982538,-0.00724566,-0.0112515,0.185579,0.0112367,-0.00363165,0.0163671,0.00887295,-0.0023949,0.0388862,-1.16094e-05,-5.95234e-05,1.372e-06,0,0,-0.00136111,0.204706,0.00196982,0.434395,0,0,0,0,0,7.57613e-06,5.43203e-05,5.43204e-05,0.00021248,0.0410868,0.0410874,0.00939356,0.0455454,0.0455456,0.0632046,2.53918e-09,2.54072e-09,7.32153e-09,0,0,6.24297e-08,0,0,0,0,0,0,0,0
|
||||
14485000,0.982511,-0.00734868,-0.0112193,0.185723,0.0093968,-0.00340197,0.0201136,0.00982795,-0.00275625,0.0411489,-1.16233e-05,-5.95099e-05,6.6601e-07,0,0,-0.00136119,0.204706,0.00196982,0.434395,0,0,0,0,0,7.54981e-06,5.77751e-05,5.77766e-05,0.00021181,0.0465421,0.0465427,0.00934355,0.0522591,0.0522594,0.0629601,2.53923e-09,2.54078e-09,7.21043e-09,0,0,6.23317e-08,0,0,0,0,0,0,0,0
|
||||
14585000,0.982497,-0.00742299,-0.0110435,0.185803,0.00725283,-0.00337394,0.0187326,0.00642845,-0.0035459,0.0389882,-1.16921e-05,-6.00859e-05,4.37373e-07,0,0,-0.00136048,0.204706,0.00196982,0.434395,0,0,0,0,0,7.60374e-06,5.24417e-05,5.24426e-05,0.000213296,0.0407463,0.0407469,0.00924712,0.0456128,0.045613,0.0630912,2.33578e-09,2.33717e-09,7.12586e-09,0,0,6.2104e-08,0,0,0,0,0,0,0,0
|
||||
14685000,0.982515,-0.00739752,-0.0110997,0.185706,0.00667776,-0.00341466,0.0184807,0.00711684,-0.00386724,0.0394614,-1.16882e-05,-6.00904e-05,6.4819e-07,0,0,-0.00136024,0.204706,0.00196982,0.434395,0,0,0,0,0,7.58367e-06,5.57217e-05,5.5723e-05,0.000212774,0.0461271,0.0461277,0.00922957,0.0523177,0.052318,0.0628426,2.33583e-09,2.33723e-09,7.0117e-09,0,0,6.20003e-08,0,0,0,0,0,0,0,0
|
||||
14785000,0.982552,-0.00734822,-0.0110786,0.185514,0.00791011,0.00328671,0.018224,0.00575086,0.0011458,0.0414191,-1.25361e-05,-5.99897e-05,1.12462e-06,0,0,-0.00136052,0.204706,0.00196982,0.434395,0,0,0,0,0,7.56118e-06,5.04688e-05,5.04697e-05,0.00021231,0.0403704,0.040371,0.00908114,0.0456546,0.0456548,0.0620066,2.14083e-09,2.14208e-09,6.89593e-09,0,0,6.17125e-08,0,0,0,0,0,0,0,0
|
||||
14885000,0.982587,-0.007274,-0.0110044,0.185333,0.00662428,0.00132819,0.0218006,0.00646557,0.00138023,0.042356,-1.2526e-05,-5.99999e-05,1.64054e-06,0,0,-0.0013603,0.204706,0.00196982,0.434395,0,0,0,0,0,7.54425e-06,5.35681e-05,5.35697e-05,0.0002119,0.0456254,0.0456258,0.00909371,0.0523442,0.0523445,0.0617708,2.14089e-09,2.14214e-09,6.77918e-09,0,0,6.15991e-08,0,0,0,0,0,0,0,0
|
||||
14985000,0.982591,-0.0074185,-0.0108766,0.185315,0.00566069,-0.000486878,0.024569,0.00512824,-0.000276725,0.0437492,-1.23553e-05,-6.0306e-05,1.8602e-06,0,0,-0.00135955,0.204706,0.00196982,0.434395,0,0,0,0,0,7.53326e-06,4.8429e-05,4.84298e-05,0.000211518,0.0399075,0.0399078,0.00897747,0.0456753,0.0456755,0.0609825,1.95596e-09,1.95706e-09,6.66123e-09,0,0,6.12758e-08,0,0,0,0,0,0,0,0
|
||||
15085000,0.982589,-0.00735974,-0.0109621,0.185325,0.00569353,0.000301774,0.0284362,0.00570591,-0.000319003,0.0461776,-1.23573e-05,-6.03042e-05,1.75916e-06,0,0,-0.0013595,0.204706,0.00196982,0.434395,0,0,0,0,0,7.52101e-06,5.13471e-05,5.13478e-05,0.000211177,0.0450431,0.0450434,0.00901656,0.052342,0.0523423,0.0607668,1.95601e-09,1.95712e-09,6.54271e-09,0,0,6.11503e-08,0,0,0,0,0,0,0,0
|
||||
15185000,0.982582,-0.00748839,-0.0110044,0.185352,0.0040053,-0.00078982,0.0288132,0.00451778,-0.000382163,0.0467459,-1.24122e-05,-6.04665e-05,1.57579e-06,0,0,-0.00135879,0.204706,0.00196982,0.434395,0,0,0,0,0,7.50726e-06,4.63488e-05,4.63488e-05,0.000210853,0.0394087,0.0394088,0.0089271,0.0456777,0.0456779,0.0600272,1.78218e-09,1.78316e-09,6.42343e-09,0,0,6.07887e-08,0,0,0,0,0,0,0,0
|
||||
15285000,0.9826,-0.00758756,-0.011034,0.185249,0.00389033,-0.00140632,0.0286143,0.00493639,-0.000448419,0.0465668,-1.24039e-05,-6.04771e-05,2.05372e-06,0,0,-0.00135817,0.204706,0.00196982,0.434395,0,0,0,0,0,7.57251e-06,4.90864e-05,4.90867e-05,0.000212605,0.044434,0.044434,0.00906408,0.0523177,0.052318,0.0607462,1.78225e-09,1.78322e-09,6.33371e-09,0,0,6.06869e-08,0,0,0,0,0,0,0,0
|
||||
15385000,0.982566,-0.00765763,-0.0110386,0.185427,0.0046174,0.000966974,0.0282464,0.00395783,-0.000241816,0.0457936,-1.24963e-05,-6.05854e-05,1.61126e-06,0,0,-0.00135698,0.204706,0.00196982,0.434395,0,0,0,0,0,7.56564e-06,4.42475e-05,4.42455e-05,0.000212291,0.0388774,0.0388777,0.00899407,0.0456654,0.0456656,0.0600343,1.62006e-09,1.62086e-09,6.21379e-09,0,0,6.02851e-08,0,0,0,0,0,0,0,0
|
||||
15485000,0.982561,-0.00769537,-0.0109989,0.185454,0.00363081,-0.00132675,0.0282523,0.00435924,-0.000223376,0.0466759,-1.24955e-05,-6.0588e-05,1.69232e-06,0,0,-0.00135657,0.204706,0.00196982,0.434395,0,0,0,0,0,7.55962e-06,4.68076e-05,4.68052e-05,0.000211985,0.0437685,0.0437686,0.00907573,0.0522743,0.0522747,0.0598702,1.62013e-09,1.62089e-09,6.09401e-09,0,0,6.01315e-08,0,0,0,0,0,0,0,0
|
||||
15585000,0.98256,-0.00783254,-0.0110058,0.185453,0.00732822,-0.00477543,0.0278306,0.00633061,-0.00420305,0.0456559,-1.18183e-05,-6.05345e-05,1.97617e-06,0,0,-0.00135543,0.204706,0.00196982,0.434395,0,0,0,0,0,7.55374e-06,4.2145e-05,4.21406e-05,0.00021167,0.0382992,0.0382994,0.0090234,0.0456403,0.0456406,0.059208,1.46979e-09,1.47042e-09,5.9742e-09,0,0,5.96874e-08,0,0,0,0,0,0,0,0
|
||||
15685000,0.98259,-0.00779931,-0.0109974,0.185297,0.00907644,-0.0079607,0.0282118,0.00713628,-0.00484122,0.0467574,-1.18122e-05,-6.05447e-05,2.39315e-06,0,0,-0.00135503,0.204706,0.00196982,0.434395,0,0,0,0,0,7.53917e-06,4.45331e-05,4.45279e-05,0.000211354,0.0430471,0.0430474,0.00912099,0.0522135,0.0522139,0.0590736,1.46987e-09,1.47045e-09,5.85464e-09,0,0,5.95143e-08,0,0,0,0,0,0,0,0
|
||||
15785000,0.982628,-0.00780519,-0.0108879,0.185104,0.0058576,-0.00780899,0.0275861,0.00551849,-0.00380282,0.0479525,-1.20782e-05,-6.0707e-05,3.02454e-06,0,0,-0.00135415,0.204706,0.00196982,0.434395,0,0,0,0,0,7.52418e-06,4.0063e-05,4.00566e-05,0.000211027,0.0376802,0.0376803,0.00908211,0.0456041,0.0456044,0.0584597,1.3314e-09,1.33188e-09,5.73564e-09,0,0,5.90266e-08,0,0,0,0,0,0,0,0
|
||||
15885000,0.982596,-0.00785086,-0.0109351,0.185269,0.00450024,-0.00581752,0.0287133,0.00596976,-0.00448813,0.0480049,-1.20863e-05,-6.06969e-05,2.54241e-06,0,0,-0.00135349,0.204706,0.00196982,0.434395,0,0,0,0,0,7.58883e-06,4.22859e-05,4.22789e-05,0.000212747,0.0422763,0.0422765,0.00926543,0.052137,0.0521374,0.0592314,1.33148e-09,1.33193e-09,5.64684e-09,0,0,5.88858e-08,0,0,0,0,0,0,0,0
|
||||
15985000,0.982601,-0.00766544,-0.0108851,0.185253,0.00286259,-0.00415943,0.025187,0.00477224,-0.00345484,0.0457316,-1.22734e-05,-6.07656e-05,2.392e-06,0,0,-0.00135129,0.204706,0.00196982,0.434395,0,0,0,0,0,7.57e-06,3.80199e-05,3.80109e-05,0.000212382,0.0370254,0.0370256,0.00923464,0.0455574,0.0455577,0.0586466,1.20465e-09,1.20501e-09,5.52897e-09,0,0,5.83548e-08,0,0,0,0,0,0,0,0
|
||||
16085000,0.982601,-0.00762876,-0.0108737,0.185255,0.00131744,-0.00531289,0.0237234,0.00491858,-0.00394773,0.0472168,-1.22809e-05,-6.07558e-05,1.93937e-06,0,0,-0.00135106,0.204706,0.00196982,0.434395,0,0,0,0,0,7.54679e-06,4.00848e-05,4.00751e-05,0.000211996,0.0414863,0.0414864,0.00935721,0.0520465,0.0520469,0.0585853,1.20472e-09,1.20505e-09,5.41192e-09,0,0,5.8143e-08,0,0,0,0,0,0,0,0
|
||||
16185000,0.982585,-0.00753945,-0.0107807,0.185346,-0.00251601,-0.00343229,0.0225629,0.0026021,-0.00297279,0.0440267,-1.25155e-05,-6.09272e-05,1.40889e-06,0,0,-0.00134923,0.204706,0.00196982,0.434395,0,0,0,0,0,7.52724e-06,3.6027e-05,3.60161e-05,0.000211584,0.0363383,0.0363383,0.00933286,0.0455009,0.0455012,0.0580455,1.08902e-09,1.08928e-09,5.29596e-09,0,0,5.75679e-08,0,0,0,0,0,0,0,0
|
||||
16285000,0.982581,-0.00759017,-0.0107109,0.185371,-0.0022168,-0.00486099,0.0221027,0.00234583,-0.00340127,0.0453797,-1.25137e-05,-6.09298e-05,1.52157e-06,0,0,-0.001349,0.204706,0.00196982,0.434395,0,0,0,0,0,7.51661e-06,3.79423e-05,3.79314e-05,0.000211135,0.0406426,0.0406427,0.00946362,0.0519417,0.0519421,0.0580231,1.08909e-09,1.08932e-09,5.18108e-09,0,0,5.73328e-08,0,0,0,0,0,0,0,0
|
||||
16385000,0.982594,-0.00754212,-0.0107176,0.185305,0.000210802,-0.00399487,0.0227075,0.00341846,-0.00262925,0.0452751,-1.25386e-05,-6.07212e-05,1.92084e-06,0,0,-0.00134797,0.204706,0.00196982,0.434395,0,0,0,0,0,7.50282e-06,3.40994e-05,3.40876e-05,0.000210663,0.0356169,0.0356169,0.00944267,0.0454351,0.0454354,0.0575251,9.8404e-10,9.84217e-10,5.06752e-09,0,0,5.67143e-08,0,0,0,0,0,0,0,0
|
||||
16485000,0.98259,-0.0076434,-0.010701,0.185324,0.00257247,-0.00542022,0.024563,0.00355439,-0.00316586,0.0486582,-1.25417e-05,-6.07169e-05,1.73004e-06,0,0,-0.00134826,0.204706,0.00196982,0.434395,0,0,0,0,0,7.483e-06,3.58746e-05,3.58626e-05,0.000210165,0.0397607,0.0397608,0.00957909,0.051823,0.0518234,0.0575409,9.84106e-10,9.84266e-10,4.95524e-09,0,0,5.6455e-08,0,0,0,0,0,0,0,0
|
||||
16585000,0.982586,-0.00762813,-0.0107057,0.185341,0.006507,-0.00606706,0.0279772,0.00312945,-0.00246829,0.0493191,-1.26803e-05,-6.07258e-05,1.6231e-06,0,0,-0.00134745,0.204706,0.00196982,0.434395,0,0,0,0,0,7.53549e-06,3.22479e-05,3.22352e-05,0.000211684,0.0348599,0.03486,0.00962963,0.0453598,0.04536,0.0579072,8.89067e-10,8.89185e-10,4.87194e-09,0,0,5.58641e-08,0,0,0,0,0,0,0,0
|
||||
16685000,0.9826,-0.00768579,-0.0106398,0.18527,0.00767128,-0.00978584,0.0282508,0.00383667,-0.00323971,0.0506751,-1.26757e-05,-6.07318e-05,1.89612e-06,0,0,-0.00134703,0.204706,0.00196982,0.434395,0,0,0,0,0,7.51619e-06,3.38917e-05,3.38789e-05,0.000211115,0.0388543,0.0388544,0.00977058,0.0516906,0.0516909,0.0579612,8.89133e-10,8.89237e-10,4.7622e-09,0,0,5.55844e-08,0,0,0,0,0,0,0,0
|
||||
16785000,0.982621,-0.00753588,-0.0105347,0.185172,0.00885154,-0.00946908,0.026981,0.00303175,-0.00238173,0.0497827,-1.29087e-05,-6.08045e-05,2.05092e-06,0,0,-0.0013454,0.204706,0.00196982,0.434395,0,0,0,0,0,7.48995e-06,3.04784e-05,3.04651e-05,0.000210525,0.0341099,0.03411,0.00974733,0.0452756,0.0452758,0.0575229,8.03389e-10,8.03456e-10,4.65412e-09,0,0,5.48849e-08,0,0,0,0,0,0,0,0
|
||||
16885000,0.982665,-0.00750387,-0.0106264,0.184934,0.00756395,-0.00947452,0.028218,0.00384405,-0.00331143,0.0489225,-1.28991e-05,-6.0817e-05,2.62389e-06,0,0,-0.00134425,0.204706,0.00196982,0.434395,0,0,0,0,0,7.46161e-06,3.2001e-05,3.19865e-05,0.000209903,0.0379483,0.0379483,0.00988939,0.051547,0.0515473,0.0576122,8.03456e-10,8.0351e-10,4.54763e-09,0,0,5.45803e-08,0,0,0,0,0,0,0,0
|
||||
16985000,0.982665,-0.00752544,-0.0106523,0.184933,0.00762514,-0.00954776,0.0283224,0.00363401,-0.00249018,0.0479051,-1.30261e-05,-6.06814e-05,2.72133e-06,0,0,-0.00134289,0.204706,0.00196982,0.434395,0,0,0,0,0,7.43952e-06,2.87953e-05,2.87807e-05,0.000209239,0.0333405,0.0333404,0.0098614,0.0451827,0.045183,0.0572,7.26246e-10,7.26274e-10,4.44277e-09,0,0,5.38425e-08,0,0,0,0,0,0,0,0
|
||||
17085000,0.982655,-0.0076264,-0.0105846,0.184985,0.00847359,-0.0119637,0.0284744,0.00444375,-0.00358225,0.0476796,-1.30301e-05,-6.0678e-05,2.5271e-06,0,0,-0.0013419,0.204706,0.00196982,0.434395,0,0,0,0,0,7.41506e-06,3.02038e-05,3.01894e-05,0.000208553,0.0370364,0.0370363,0.0100027,0.0513916,0.0513919,0.0573216,7.26313e-10,7.26332e-10,4.33978e-09,0,0,5.35131e-08,0,0,0,0,0,0,0,0
|
||||
17185000,0.982606,-0.00772613,-0.0104877,0.185245,0.00783742,-0.016633,0.0296088,0.00286992,-0.00713843,0.0503151,-1.29243e-05,-6.08037e-05,1.90421e-06,0,0,-0.00134135,0.204706,0.00196982,0.434395,0,0,0,0,0,7.46737e-06,2.71983e-05,2.71841e-05,0.000209842,0.0325713,0.0325712,0.0100442,0.0450815,0.0450817,0.0577632,6.56916e-10,6.56914e-10,4.26374e-09,0,0,5.28299e-08,0,0,0,0,0,0,0,0
|
||||
17285000,0.982572,-0.00767987,-0.0104829,0.185429,0.00819018,-0.0171974,0.0290795,0.00365692,-0.0088,0.0507962,-1.29358e-05,-6.0792e-05,1.29566e-06,0,0,-0.00134057,0.204706,0.00196982,0.434395,0,0,0,0,0,7.44196e-06,2.85025e-05,2.84877e-05,0.000209083,0.0361268,0.0361266,0.0101845,0.051226,0.0512262,0.0579183,6.56983e-10,6.56974e-10,4.1639e-09,0,0,5.24812e-08,0,0,0,0,0,0,0,0
|
||||
17385000,0.982614,-0.00759581,-0.010478,0.185207,0.0054137,-0.0173089,0.0290734,0.00516345,-0.0056272,0.0513558,-1.32764e-05,-6.05279e-05,1.72768e-06,0,0,-0.00133929,0.204706,0.00196982,0.434395,0,0,0,0,0,7.40572e-06,2.56896e-05,2.56749e-05,0.000208302,0.0318072,0.0318067,0.0101429,0.0449729,0.044973,0.0575445,5.94682e-10,5.94656e-10,4.06586e-09,0,0,5.168e-08,0,0,0,0,0,0,0,0
|
||||
17485000,0.982601,-0.00759475,-0.0105308,0.185276,0.00305748,-0.0181565,0.0285265,0.00551969,-0.00737306,0.0518138,-1.32814e-05,-6.05233e-05,1.47689e-06,0,0,-0.00133848,0.204706,0.00196982,0.434395,0,0,0,0,0,7.37718e-06,2.68975e-05,2.68821e-05,0.00020749,0.0352233,0.0352226,0.0102791,0.0510506,0.0510508,0.0577255,5.9475e-10,5.94718e-10,3.96981e-09,0,0,5.13085e-08,0,0,0,0,0,0,0,0
|
||||
17585000,0.982601,-0.00754145,-0.0104351,0.185282,-0.000319291,-0.0142901,0.0275053,0.0019783,-0.00554856,0.0499126,-1.36511e-05,-6.07197e-05,1.44723e-06,0,0,-0.00133655,0.204706,0.00196982,0.434395,0,0,0,0,0,7.34699e-06,2.42684e-05,2.42529e-05,0.00020665,0.0310476,0.0310471,0.0102294,0.0448569,0.044857,0.0573702,5.38881e-10,5.38832e-10,3.87562e-09,0,0,5.04818e-08,0,0,0,0,0,0,0,0
|
||||
17685000,0.982628,-0.00763672,-0.0103536,0.185139,-0.00141639,-0.0148922,0.028789,0.00191205,-0.00702983,0.0522408,-1.36499e-05,-6.07211e-05,1.51402e-06,0,0,-0.00133637,0.204706,0.00196982,0.434395,0,0,0,0,0,7.30724e-06,2.53869e-05,2.53716e-05,0.000205798,0.0343248,0.0343242,0.0103601,0.0508663,0.0508664,0.0575734,5.38949e-10,5.38897e-10,3.78343e-09,0,0,5.00891e-08,0,0,0,0,0,0,0,0
|
||||
17785000,0.982672,-0.00762044,-0.010329,0.184909,0.00100209,-0.0130674,0.0285964,0.00291266,-0.00606398,0.0558882,-1.38494e-05,-6.05075e-05,1.66106e-06,0,0,-0.00133648,0.204706,0.00196982,0.434395,0,0,0,0,0,7.26092e-06,2.2932e-05,2.29169e-05,0.000204925,0.0302947,0.0302942,0.0103017,0.044734,0.0447341,0.0572324,4.88881e-10,4.88818e-10,3.69312e-09,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
17885000,0.982679,-0.0075681,-0.0104355,0.184864,0.00318582,-0.0154,0.0280874,0.00317892,-0.00750508,0.0608739,-1.38479e-05,-6.05085e-05,1.72355e-06,0,0,-0.00133722,0.204706,0.00196982,0.434395,0,0,0,0,0,7.29567e-06,2.39701e-05,2.39538e-05,0.000205953,0.0334503,0.0334498,0.0105067,0.0506738,0.0506739,0.0582907,4.88958e-10,4.88893e-10,3.62668e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
17985000,0.982686,-0.00741032,-0.0104198,0.18484,0.00222625,-0.00917502,0.027808,0.00254655,-0.00204132,0.0609731,-1.43796e-05,-6.03588e-05,1.63684e-06,0,0,-0.0013363,0.204706,0.00196982,0.434395,0,0,0,0,0,7.25784e-06,2.16791e-05,2.16627e-05,0.000205008,0.0295559,0.0295555,0.0104383,0.0446047,0.0446048,0.0579504,4.44091e-10,4.44019e-10,3.53975e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
18085000,0.982685,-0.00749491,-0.0103823,0.184843,0.00234372,-0.00976543,0.0274329,0.00284769,-0.00301735,0.0603459,-1.43803e-05,-6.03589e-05,1.62397e-06,0,0,-0.00133509,0.204706,0.00196982,0.434395,0,0,0,0,0,7.22407e-06,2.26414e-05,2.26251e-05,0.000204043,0.0325808,0.0325804,0.0105576,0.0504739,0.050474,0.0581923,4.44161e-10,4.44088e-10,3.45483e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
18185000,0.98273,-0.00751172,-0.0104225,0.184599,0.00221645,-0.00851911,0.0281341,0.00347519,-0.00228438,0.0586577,-1.44547e-05,-6.02655e-05,2.29642e-06,0,0,-0.00133317,0.204706,0.00196982,0.434395,0,0,0,0,0,7.18576e-06,2.05053e-05,2.0489e-05,0.000203058,0.0288198,0.0288195,0.0104805,0.0444693,0.0444693,0.0578588,4.03972e-10,4.03895e-10,3.37178e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
18285000,0.982728,-0.00754739,-0.0103958,0.184611,0.0029497,-0.00930545,0.0273975,0.00367274,-0.00316135,0.0576708,-1.44546e-05,-6.02664e-05,2.32803e-06,0,0,-0.00133178,0.204706,0.00196982,0.434395,0,0,0,0,0,7.15188e-06,2.1399e-05,2.13827e-05,0.000202049,0.0317253,0.031725,0.0105919,0.0502661,0.0502662,0.0581057,4.04044e-10,4.03966e-10,3.29063e-09,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
18385000,0.982704,-0.00747388,-0.0104142,0.184736,0.00356485,-0.00834532,0.0271754,0.0053563,-0.00243739,0.0572702,-1.45058e-05,-6.00877e-05,2.09409e-06,0,0,-0.00133054,0.204706,0.00196982,0.434395,0,0,0,0,0,7.1196e-06,1.94079e-05,1.93915e-05,0.000201025,0.028104,0.0281037,0.0105066,0.0443278,0.0443278,0.057776,3.68043e-10,3.67965e-10,3.21142e-09,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
18485000,0.982714,-0.00750805,-0.0104275,0.184686,0.00637912,-0.00809538,0.0268756,0.0059369,-0.00326641,0.0598785,-1.45014e-05,-6.00921e-05,2.32691e-06,0,0,-0.00133053,0.204706,0.00196982,0.434395,0,0,0,0,0,7.15064e-06,2.02392e-05,2.02225e-05,0.000201848,0.0308968,0.0308967,0.0106971,0.0500527,0.0500528,0.058889,3.68122e-10,3.68044e-10,3.15329e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
18585000,0.982687,-0.00734841,-0.0103129,0.18484,0.00515563,-0.00748784,0.0265579,0.00480498,-0.00258611,0.0615402,-1.46263e-05,-6.01387e-05,2.09563e-06,0,0,-0.00132975,0.204706,0.00196982,0.434395,0,0,0,0,0,7.11872e-06,1.8383e-05,1.83665e-05,0.000200773,0.0274079,0.0274078,0.0106029,0.0441814,0.0441814,0.0585503,3.35859e-10,3.35782e-10,3.07736e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
18685000,0.982702,-0.00733087,-0.0102627,0.184765,0.00469419,-0.00655655,0.0250742,0.00530195,-0.00328867,0.0609469,-1.46244e-05,-6.01413e-05,2.21943e-06,0,0,-0.00132859,0.204706,0.00196982,0.434395,0,0,0,0,0,7.07786e-06,1.91564e-05,1.91398e-05,0.000199691,0.030092,0.0300918,0.0107021,0.0498339,0.0498339,0.0588143,3.35933e-10,3.35856e-10,3.00324e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
18785000,0.982704,-0.00727115,-0.0101622,0.184764,0.00369875,-0.00631482,0.0243853,0.00541385,-0.00267138,0.0575967,-1.46887e-05,-6.00987e-05,2.22038e-06,0,0,-0.00132559,0.204706,0.00196982,0.434395,0,0,0,0,0,7.03874e-06,1.7426e-05,1.741e-05,0.000198598,0.0267263,0.0267261,0.010601,0.0440301,0.0440301,0.0584742,3.07004e-10,3.06931e-10,2.93099e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
18885000,0.982695,-0.00722648,-0.0101762,0.18481,0.00268931,-0.00604587,0.022881,0.00570537,-0.00334953,0.0545401,-1.46936e-05,-6.00948e-05,1.99459e-06,0,0,-0.00132354,0.204706,0.00196982,0.434395,0,0,0,0,0,6.99781e-06,1.81471e-05,1.81307e-05,0.000197494,0.0293042,0.0293039,0.0106935,0.0496097,0.0496097,0.0587381,3.07079e-10,3.07007e-10,2.86051e-09,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
18985000,0.982673,-0.00721366,-0.0102225,0.184923,0.0012514,-0.0060594,0.0234212,0.00471868,-0.0027034,0.0573843,-1.47745e-05,-6.01137e-05,1.9499e-06,0,0,-0.00132322,0.204706,0.00196982,0.434395,0,0,0,0,0,6.96573e-06,1.65352e-05,1.65187e-05,0.000196373,0.0260647,0.0260644,0.0105864,0.0438744,0.0438744,0.0583947,2.81133e-10,2.81065e-10,2.79184e-09,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
19085000,0.98268,-0.00728883,-0.0102316,0.184887,-0.000817021,-0.00621333,0.0239108,0.00477994,-0.00327887,0.0535243,-1.47721e-05,-6.0117e-05,2.1127e-06,0,0,-0.0013209,0.204706,0.00196982,0.434395,0,0,0,0,0,6.92743e-06,1.72081e-05,1.71916e-05,0.000195247,0.0285379,0.0285375,0.0106728,0.0493817,0.0493817,0.0586559,2.8121e-10,2.81141e-10,2.72488e-09,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
19185000,0.982652,-0.00718747,-0.0103642,0.185032,-0.00208979,-0.00605339,0.0239391,0.00399507,-0.00270665,0.0535394,-1.4847e-05,-6.00976e-05,1.6901e-06,0,0,-0.00131996,0.204706,0.00196982,0.434395,0,0,0,0,0,6.94985e-06,1.57061e-05,1.56888e-05,0.000195868,0.0254181,0.0254177,0.0106476,0.0437148,0.0437148,0.0591703,2.57928e-10,2.57863e-10,2.67579e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
19285000,0.982649,-0.00712794,-0.0103163,0.185053,-0.00326538,-0.00606924,0.0242873,0.00376216,-0.00331525,0.0535872,-1.485e-05,-6.00951e-05,1.54739e-06,0,0,-0.00131908,0.204706,0.00196982,0.434395,0,0,0,0,0,6.90733e-06,1.63348e-05,1.63174e-05,0.000194712,0.0278003,0.0277999,0.0107298,0.0491497,0.0491497,0.0594343,2.58005e-10,2.57941e-10,2.61179e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
19385000,0.982643,-0.00721818,-0.0102083,0.185083,-0.00317872,-0.00256188,0.0259595,0.00324332,-0.00141494,0.0523562,-1.49735e-05,-6.00375e-05,1.32775e-06,0,0,-0.00131731,0.204706,0.00196982,0.434395,0,0,0,0,0,6.86313e-06,1.49327e-05,1.49163e-05,0.000193555,0.0247908,0.0247904,0.0106117,0.0435514,0.0435514,0.05907,2.37084e-10,2.37023e-10,2.54948e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
19485000,0.982596,-0.00726951,-0.0101113,0.185337,-0.00418249,-0.00260004,0.0252355,0.00283984,-0.00167245,0.0520703,-1.49817e-05,-6.00298e-05,9.08024e-07,0,0,-0.00131623,0.204706,0.00196982,0.434395,0,0,0,0,0,6.83066e-06,1.5521e-05,1.5505e-05,0.000192379,0.0270855,0.027085,0.0106887,0.0489142,0.0489142,0.0593271,2.37162e-10,2.37102e-10,2.48876e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
19585000,0.982573,-0.00720833,-0.0102219,0.185456,-0.00592258,-0.0052393,0.0266827,0.00347136,-0.00256935,0.0522324,-1.49115e-05,-5.99573e-05,7.82859e-07,0,0,-0.00131498,0.204706,0.00196982,0.434395,0,0,0,0,0,6.79503e-06,1.42135e-05,1.41972e-05,0.0001912,0.0241883,0.0241878,0.0105662,0.0433848,0.0433848,0.0589509,2.18349e-10,2.18294e-10,2.4296e-09,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
19685000,0.982589,-0.0072285,-0.0102362,0.185368,-0.00735454,-0.00409103,0.025929,0.00284161,-0.00304001,0.0520684,-1.49074e-05,-5.99617e-05,1.01285e-06,0,0,-0.00131389,0.204706,0.00196982,0.434395,0,0,0,0,0,6.75335e-06,1.47655e-05,1.4749e-05,0.000190028,0.0263982,0.0263977,0.0106385,0.0486767,0.0486766,0.0591997,2.18429e-10,2.18374e-10,2.37203e-09,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
19785000,0.982574,-0.00730857,-0.0102417,0.185444,-0.00760097,-0.00263142,0.0247279,0.00533094,-0.00247415,0.0490124,-1.48915e-05,-5.98056e-05,8.34609e-07,0,0,-0.00131147,0.204706,0.00196982,0.434395,0,0,0,0,0,6.77181e-06,1.35444e-05,1.35284e-05,0.00019051,0.0236104,0.0236099,0.0106034,0.0432157,0.0432157,0.0597006,2.01499e-10,2.01448e-10,2.32987e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
19885000,0.982548,-0.00731687,-0.0103321,0.185578,-0.0074016,-0.00209395,0.0244703,0.00452823,-0.00266839,0.0477953,-1.48979e-05,-5.97997e-05,5.11406e-07,0,0,-0.00131011,0.204706,0.00196982,0.434395,0,0,0,0,0,6.73171e-06,1.4063e-05,1.40465e-05,0.000189312,0.0257386,0.0257381,0.0106731,0.0484379,0.0484378,0.0599472,2.0158e-10,2.01529e-10,2.27493e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
19985000,0.982569,-0.00734034,-0.0104643,0.18546,-0.00743827,-0.00193618,0.0219268,0.00496746,-0.00113573,0.044131,-1.49444e-05,-5.96832e-05,6.09827e-07,0,0,-0.00130709,0.204706,0.00196982,0.434395,0,0,0,0,0,6.68356e-06,1.29226e-05,1.29059e-05,0.000188119,0.0230539,0.0230534,0.0105446,0.043045,0.0430449,0.0595467,1.8632e-10,1.86274e-10,2.22141e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
20085000,0.982579,-0.00734637,-0.0104751,0.185406,-0.00698802,-0.00441706,0.0220294,0.004223,-0.00148006,0.0473349,-1.49449e-05,-5.96827e-05,5.83891e-07,0,0,-0.00130746,0.204706,0.00196982,0.434395,0,0,0,0,0,6.6373e-06,1.341e-05,1.33932e-05,0.000186928,0.0251086,0.0251081,0.0106108,0.0481985,0.0481984,0.059783,1.86401e-10,1.86356e-10,2.16935e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
20185000,0.982557,-0.00734912,-0.0105774,0.185513,-0.00588554,-0.00255427,0.0228524,0.0053764,-0.00115525,0.0469352,-1.49579e-05,-5.96011e-05,2.50075e-07,-7.80525e-11,7.95054e-11,-0.00130618,0.204706,0.00196982,0.434395,0,0,0,0,0,6.59456e-06,1.23433e-05,1.23263e-05,0.000185732,0.0227717,0.0227714,0.0104815,0.0428729,0.0428728,0.0593765,1.72631e-10,1.72589e-10,2.11866e-09,4.00001e-06,4.00001e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20285000,0.982568,-0.00734147,-0.0106065,0.185454,-0.00901657,-0.00286927,0.0231725,0.00466323,-0.00135121,0.047637,-1.49599e-05,-5.95992e-05,1.4824e-07,3.31072e-09,-3.368e-09,-0.00130558,0.204706,0.00196982,0.434395,0,0,0,0,0,6.54636e-06,1.28025e-05,1.27853e-05,0.000184546,0.0257919,0.0257919,0.0105453,0.0479678,0.0479677,0.0596022,1.72714e-10,1.72671e-10,2.06936e-09,4.00002e-06,4.00002e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20385000,0.982566,-0.00729236,-0.0105989,0.18547,-0.00962035,-0.00182757,0.0222169,0.00570583,-0.00105044,0.0471084,-1.49495e-05,-5.95254e-05,4.09768e-07,-2.55265e-06,-5.36508e-08,-0.00130382,0.204706,0.00196982,0.434395,0,0,0,0,0,6.5125e-06,1.18087e-05,1.17917e-05,0.000183347,0.024739,0.0247397,0.0104168,0.0427114,0.0427113,0.0591903,1.6032e-10,1.6028e-10,2.02135e-09,3.97911e-06,3.97911e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20485000,0.982581,-0.0073051,-0.0105706,0.185388,-0.0139886,-0.00278392,0.0228266,0.00450053,-0.00125738,0.0466963,-1.49518e-05,-5.95233e-05,2.92742e-07,-2.53595e-06,-7.04975e-08,-0.00130282,0.204706,0.00196982,0.434395,0,0,0,0,0,6.5169e-06,1.2242e-05,1.2225e-05,0.00018371,0.0291166,0.0291182,0.0105702,0.0478111,0.047811,0.0603011,1.60407e-10,1.60368e-10,1.98621e-09,3.97912e-06,3.97912e-06,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
20585000,0.982622,-0.00727677,-0.0105781,0.185174,-0.0131455,-0.00353435,0.0224962,0.00566531,-0.00104886,0.0450999,-1.49247e-05,-5.9432e-05,7.75942e-07,-1.04064e-05,1.19479e-06,-0.00130094,0.204706,0.00196982,0.434395,0,0,0,0,0,6.47206e-06,1.13434e-05,1.13265e-05,0.000182508,0.0285743,0.0285769,0.0104408,0.0426102,0.0426101,0.059872,1.49477e-10,1.4944e-10,1.94043e-09,3.90078e-06,3.90078e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
20685000,0.982609,-0.00720229,-0.0105726,0.185244,-0.0151915,-0.00252303,0.0234634,0.00429319,-0.00131084,0.0454891,-1.49317e-05,-5.94256e-05,4.21705e-07,-1.03865e-05,1.17254e-06,-0.00130024,0.204706,0.00196982,0.434395,0,0,0,0,0,6.42605e-06,1.17539e-05,1.17369e-05,0.000181314,0.0340498,0.0340539,0.0105036,0.0478219,0.0478219,0.0600831,1.4956e-10,1.49526e-10,1.8959e-09,3.90079e-06,3.90079e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
20785000,0.982634,-0.00674023,-0.0105101,0.185134,-0.016251,-0.000100103,0.0111662,0.00364695,-0.00105525,0.0441328,-1.49247e-05,-5.93728e-05,5.5326e-07,-2.07279e-05,3.0627e-06,-0.00129864,0.204706,0.00196982,0.434395,0,0,0,0,0,6.37992e-06,1.09886e-05,1.09711e-05,0.000180124,0.0332245,0.0332292,0.0103754,0.0426323,0.0426323,0.0596503,1.40292e-10,1.40264e-10,1.85255e-09,3.74749e-06,3.74749e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
20885000,0.982693,0.00211918,-0.00683226,0.185102,-0.022513,0.0116014,-0.102277,0.00164132,-0.000451729,0.0385737,-1.49244e-05,-5.93729e-05,5.69032e-07,-2.06774e-05,3.0164e-06,-0.00129795,0.204706,0.00196982,0.434395,0,0,0,0,0,6.3363e-06,1.13682e-05,1.13572e-05,0.000178954,0.0396365,0.0396427,0.0104356,0.048071,0.0480712,0.0598457,1.40375e-10,1.4035e-10,1.81035e-09,3.7475e-06,3.7475e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20985000,0.982693,0.00585139,-0.00310555,0.185124,-0.0313384,0.0284187,-0.243435,0.0013644,0.000116332,0.0252432,-1.48491e-05,-5.93103e-05,5.24932e-07,-3.63523e-05,2.14499e-05,-0.0013011,0.204706,0.00196982,0.434395,0,0,0,0,0,6.29575e-06,1.07569e-05,1.07594e-05,0.000177771,0.0379333,0.037938,0.010306,0.0428238,0.0428239,0.0594101,1.32851e-10,1.3283e-10,1.76931e-09,3.52352e-06,3.52352e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21085000,0.982631,0.00442636,-0.00334905,0.18549,-0.0446361,0.0445566,-0.361105,-0.00243072,0.003819,-0.0041173,-1.48507e-05,-5.93088e-05,4.42125e-07,-3.63764e-05,2.14713e-05,-0.00130139,0.204706,0.00196982,0.434395,0,0,0,0,0,6.32841e-06,1.11362e-05,1.11349e-05,0.000178019,0.0447213,0.0447257,0.0104546,0.0485873,0.0485877,0.0605032,1.32939e-10,1.32919e-10,1.73928e-09,3.52353e-06,3.52353e-06,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
21185000,0.982579,0.00163669,-0.00494552,0.18577,-0.0449922,0.0460168,-0.486037,-0.00117918,0.00236201,-0.0377618,-1.46402e-05,-5.9227e-05,5.79312e-07,-6.41002e-05,8.08746e-05,-0.00130927,0.204706,0.00196982,0.434395,0,0,0,0,0,6.30904e-06,1.07155e-05,1.07078e-05,0.000176802,0.041507,0.0415103,0.0103248,0.0431768,0.043177,0.0600523,1.27119e-10,1.27106e-10,1.70013e-09,3.25046e-06,3.25047e-06,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
21285000,0.982525,-0.000576004,-0.00632143,0.186021,-0.0447508,0.0491527,-0.616074,-0.00569598,0.00713553,-0.0938813,-1.46464e-05,-5.92211e-05,2.67245e-07,-6.4074e-05,8.08439e-05,-0.00130892,0.204706,0.00196982,0.434395,0,0,0,0,0,6.27603e-06,1.1089e-05,1.10777e-05,0.000175603,0.0483122,0.0483161,0.0103833,0.0492678,0.0492683,0.0602347,1.27204e-10,1.27193e-10,1.66203e-09,3.25046e-06,3.25048e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
21385000,0.982479,-0.00205062,-0.00698863,0.186233,-0.0379333,0.0444261,-0.740287,-0.00401083,0.00953641,-0.155466,-1.45689e-05,-5.91346e-05,1.7885e-07,-8.83942e-05,0.000101808,-0.00131503,0.204706,0.00196982,0.434395,0,0,0,0,0,6.24665e-06,1.08449e-05,1.08328e-05,0.00017441,0.0436385,0.0436423,0.0102562,0.0436264,0.0436268,0.0597828,1.22934e-10,1.22929e-10,1.62497e-09,2.95614e-06,2.95616e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
21485000,0.982454,-0.00289468,-0.00743254,0.186335,-0.0329238,0.0412093,-0.875678,-0.00762417,0.0138522,-0.24006,-1.45653e-05,-5.91374e-05,3.4724e-07,-8.82015e-05,0.000101677,-0.00131362,0.204706,0.00196982,0.434395,0,0,0,0,0,6.2166e-06,1.12121e-05,1.11997e-05,0.000173226,0.0501727,0.0501776,0.0103148,0.05,0.0500006,0.0599568,1.23019e-10,1.23017e-10,1.58889e-09,2.95614e-06,2.95616e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21585000,0.982458,-0.00333175,-0.00742123,0.186307,-0.0244497,0.0366955,-0.998855,-0.0065338,0.0148758,-0.325268,-1.45047e-05,-5.91083e-05,4.93975e-07,-9.16205e-05,0.000100338,-0.00132157,0.204706,0.00196982,0.434395,0,0,0,0,0,6.1776e-06,1.11243e-05,1.11128e-05,0.000172062,0.0443618,0.0443664,0.0101897,0.0441019,0.0441023,0.059505,1.2002e-10,1.20022e-10,1.5538e-09,2.66524e-06,2.66526e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21685000,0.982451,-0.00368117,-0.00727497,0.186344,-0.0214299,0.0325769,-1.13225,-0.00882047,0.0183838,-0.439406,-1.44992e-05,-5.91119e-05,7.4133e-07,-9.11994e-05,0.000100067,-0.0013188,0.204706,0.00196982,0.434395,0,0,0,0,0,6.14556e-06,1.14899e-05,1.14796e-05,0.000170898,0.0504423,0.050448,0.0102484,0.0506828,0.0506837,0.0596714,1.20106e-10,1.2011e-10,1.51964e-09,2.66524e-06,2.66527e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21785000,0.982473,-0.00405201,-0.00738817,0.186216,-0.0118591,0.0275401,-1.25991,-0.00155513,0.016593,-0.552259,-1.43855e-05,-5.9041e-05,1.12015e-06,-0.000111717,9.50886e-05,-0.00132569,0.204706,0.00196982,0.434395,0,0,0,0,0,6.15453e-06,1.15321e-05,1.1522e-05,0.000171089,0.0439274,0.0439324,0.0102132,0.0445443,0.0445449,0.0601104,1.18073e-10,1.18079e-10,1.49463e-09,2.39447e-06,2.39451e-06,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
21885000,0.982461,-0.00433917,-0.00750733,0.186268,-0.00821641,0.0232481,-1.38107,-0.00258026,0.0191757,-0.691816,-1.43903e-05,-5.9035e-05,8.48308e-07,-0.000111399,9.48481e-05,-0.00132316,0.204706,0.00196982,0.434395,0,0,0,0,0,6.10964e-06,1.19021e-05,1.18923e-05,0.000169937,0.0494637,0.0494697,0.0102729,0.051248,0.051249,0.0602749,1.1816e-10,1.18168e-10,1.46204e-09,2.39447e-06,2.39451e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
21985000,0.982479,-0.00503103,-0.00780831,0.186141,-0.0072778,0.0190732,-1.36903,0.00122245,0.0158117,-0.826865,-1.4285e-05,-5.90003e-05,9.6829e-07,-9.34771e-05,7.16486e-05,-0.00132786,0.204706,0.00196982,0.434395,0,0,0,0,0,6.06394e-06,1.20447e-05,1.20354e-05,0.000168795,0.0426154,0.0426206,0.0101501,0.0449109,0.0449116,0.0598119,1.16811e-10,1.16821e-10,1.43033e-09,2.15239e-06,2.15244e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
22085000,0.982475,-0.00577099,-0.00860216,0.186104,-0.00417128,0.0154183,-1.34971,0.00058746,0.0174911,-0.968679,-1.42789e-05,-5.90039e-05,1.23484e-06,-9.3074e-05,7.14056e-05,-0.00132555,0.204706,0.00196982,0.434395,0,0,0,0,0,6.02832e-06,1.24229e-05,1.24125e-05,0.000167648,0.0475596,0.0475657,0.0102102,0.0516379,0.0516392,0.0599702,1.16898e-10,1.16911e-10,1.39946e-09,2.15239e-06,2.15244e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
22185000,0.982494,-0.00622454,-0.00890998,0.185977,0.00162424,0.0113557,-1.36458,0.00704476,0.0127939,-1.1099,-1.41493e-05,-5.89463e-05,1.4418e-06,-8.35316e-05,4.9613e-05,-0.00132336,0.204706,0.00196982,0.434395,0,0,0,0,0,5.98536e-06,1.26427e-05,1.26323e-05,0.000166519,0.0407967,0.0408021,0.0100892,0.0451774,0.0451783,0.0595042,1.16041e-10,1.16054e-10,1.36939e-09,1.9391e-06,1.93916e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22285000,0.982479,-0.00694731,-0.00915315,0.186019,0.00758157,0.00623656,-1.36259,0.00748934,0.013712,-1.25243,-1.41511e-05,-5.89422e-05,1.29956e-06,-8.31993e-05,4.938e-05,-0.0013212,0.204706,0.00196982,0.434395,0,0,0,0,0,5.94434e-06,1.30267e-05,1.30173e-05,0.0001654,0.0452247,0.0452314,0.0101499,0.0518671,0.0518686,0.0596569,1.1613e-10,1.16143e-10,1.34012e-09,1.93909e-06,1.93916e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22385000,0.982649,-0.00733559,-0.00935318,0.185093,0.00926934,-0.00321669,-1.36447,0.0127795,0.0039392,-1.39679,-1.40149e-05,-5.88849e-05,1.19548e-06,-5.43807e-05,4.14977e-05,-0.00131734,0.204181,0.00196475,0.434409,0,0,0,0,0,8.11385e-05,1.34277e-05,1.33441e-05,0.00230692,0.0387265,0.0387321,0.0101189,0.0453404,0.0453414,0.0600891,1.15591e-10,1.15603e-10,1.32583e-09,1.75455e-06,1.75462e-06,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
22485000,0.982338,-0.00749072,-0.00979986,0.186706,0.0137691,-0.00972606,-1.3692,0.0139154,0.00327686,-1.53811,-1.40142e-05,-5.88837e-05,1.19445e-06,-5.41177e-05,4.13239e-05,-0.00131569,0.204181,0.00196475,0.434409,0,0,0,0,0,5.69667e-05,1.34387e-05,1.33687e-05,0.0016194,0.0428695,0.0428763,0.0101804,0.0519066,0.0519083,0.0602416,1.15691e-10,1.15703e-10,1.32593e-09,1.75455e-06,1.75463e-06,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
22585000,0.982442,-0.00734698,-0.0103862,0.186132,0.0222098,-0.0162675,-1.36892,0.0256096,-0.00488519,-1.68092,-1.38666e-05,-5.88152e-05,1.19781e-06,-5.76646e-05,2.75601e-05,-0.00131299,0.204181,0.00196475,0.434409,0,0,0,0,0,4.39505e-05,1.34793e-05,1.34054e-05,0.00124759,0.0371812,0.0371873,0.0100618,0.045375,0.0453762,0.0597686,1.15322e-10,1.15333e-10,1.32601e-09,1.58565e-06,1.58574e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
22685000,0.982385,-0.00727617,-0.0105874,0.186426,0.0244748,-0.0211135,-1.37236,0.0279381,-0.0068031,-1.82478,-1.38654e-05,-5.88133e-05,1.19502e-06,-5.72732e-05,2.72988e-05,-0.00131059,0.204181,0.00196475,0.434409,0,0,0,0,0,3.57884e-05,1.35293e-05,1.34626e-05,0.00101471,0.0413683,0.0413756,0.0101246,0.0517513,0.0517533,0.0599167,1.15422e-10,1.15433e-10,1.32608e-09,1.58565e-06,1.58574e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
22785000,0.982334,-0.0072165,-0.0109752,0.186675,0.0274496,-0.0270889,-1.37645,0.0366672,-0.0161391,-1.9727,-1.36867e-05,-5.8706e-05,1.18899e-06,-3.6777e-05,4.19327e-06,-0.00130603,0.204181,0.00196475,0.434409,0,0,0,0,0,3.0092e-05,1.35757e-05,1.35111e-05,0.000855249,0.0362514,0.036258,0.0100091,0.0452942,0.0452957,0.0594481,1.15003e-10,1.15015e-10,1.32612e-09,1.42675e-06,1.42683e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22885000,0.982492,-0.00740506,-0.011306,0.185813,0.0305036,-0.0318074,-1.3783,0.0395266,-0.019006,-2.11697,-1.3685e-05,-5.87043e-05,1.20549e-06,-3.64177e-05,3.91917e-06,-0.00130371,0.204181,0.00196475,0.434409,0,0,0,0,0,2.59185e-05,1.36502e-05,1.35909e-05,0.000739227,0.0404136,0.0404217,0.0100733,0.0515222,0.0515246,0.0595925,1.15103e-10,1.15114e-10,1.32614e-09,1.42674e-06,1.42684e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22985000,0.982622,-0.00733241,-0.0116712,0.185105,0.0316155,-0.0352118,-1.38263,0.0481004,-0.0290401,-2.26916,-1.34908e-05,-5.85788e-05,1.22242e-06,-1.40146e-05,-1.97993e-05,-0.00129783,0.204181,0.00196475,0.434409,0,0,0,0,0,2.27481e-05,1.36927e-05,1.36339e-05,0.000651014,0.035615,0.0356225,0.00996062,0.0451537,0.0451555,0.0591289,1.14513e-10,1.14524e-10,1.32612e-09,1.27964e-06,1.27973e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23085000,0.982677,-0.00734316,-0.0119929,0.184794,0.0352542,-0.0400303,-1.37994,0.0514288,-0.032832,-2.40846,-1.34906e-05,-5.85785e-05,1.22078e-06,-1.39481e-05,-1.98425e-05,-0.00129742,0.204181,0.00196475,0.434409,0,0,0,0,0,2.08046e-05,1.37863e-05,1.37278e-05,0.000597713,0.039686,0.0396951,0.0101127,0.0512693,0.0512721,0.060162,1.14613e-10,1.14624e-10,1.32612e-09,1.27964e-06,1.27973e-06,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
23185000,0.982665,-0.00729742,-0.0121811,0.184844,0.0395682,-0.0396939,-1.38324,0.0624222,-0.0428419,-2.55574,-1.33311e-05,-5.84591e-05,1.20415e-06,-4.49146e-07,-3.31459e-05,-0.0012931,0.204181,0.00196475,0.434409,0,0,0,0,0,1.86986e-05,1.38202e-05,1.37645e-05,0.000538866,0.0350557,0.0350646,0.0100007,0.0449906,0.0449927,0.05969,1.13814e-10,1.13825e-10,1.32604e-09,1.14593e-06,1.146e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
23285000,0.982712,-0.00777067,-0.0123127,0.184567,0.0432511,-0.0442665,-1.37918,0.0664943,-0.0470845,-2.69998,-1.33294e-05,-5.84572e-05,1.21171e-06,-1.1618e-07,-3.3403e-05,-0.00129093,0.204181,0.00196475,0.434409,0,0,0,0,0,1.6994e-05,1.39242e-05,1.38758e-05,0.000490646,0.0389791,0.0389898,0.0100683,0.0510206,0.0510238,0.0598337,1.13913e-10,1.13925e-10,1.32592e-09,1.14593e-06,1.14601e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
23385000,0.982675,-0.00773461,-0.0124218,0.184761,0.0470008,-0.0427724,-1.38057,0.0773422,-0.0509405,-2.8407,-1.31308e-05,-5.83913e-05,1.1764e-06,-5.89696e-07,-6.54607e-05,-0.00128952,0.204181,0.00196475,0.434409,0,0,0,0,0,1.55671e-05,1.39546e-05,1.3909e-05,0.000450442,0.0344418,0.0344511,0.00995889,0.0448264,0.0448288,0.0593677,1.12922e-10,1.12935e-10,1.32576e-09,1.02659e-06,1.02666e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
23485000,0.982722,-0.00782656,-0.0126921,0.184487,0.0502716,-0.0440386,-1.38223,0.0821666,-0.0553131,-2.98441,-1.31289e-05,-5.83898e-05,1.20002e-06,-3.18282e-07,-6.571e-05,-0.00128752,0.204181,0.00196475,0.434409,0,0,0,0,0,1.43869e-05,1.40762e-05,1.40318e-05,0.000416394,0.0381799,0.0381912,0.0100266,0.0507875,0.0507911,0.0595044,1.13022e-10,1.13034e-10,1.32554e-09,1.02659e-06,1.02666e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23585000,0.982747,-0.00807587,-0.0126313,0.184346,0.0500133,-0.0463653,-1.38169,0.0889742,-0.065885,-3.13026,-1.30146e-05,-5.82642e-05,1.21189e-06,2.06887e-05,-7.29925e-05,-0.00128469,0.204181,0.00196475,0.434409,0,0,0,0,0,1.33717e-05,1.41064e-05,1.40674e-05,0.000387221,0.0337061,0.0337161,0.00991967,0.0446703,0.044673,0.0590448,1.11886e-10,1.11899e-10,1.32527e-09,9.21907e-07,9.21966e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
23685000,0.982754,-0.00870684,-0.0131282,0.184246,0.0475989,-0.0483411,-1.28573,0.0938696,-0.0706857,-3.26825,-1.30135e-05,-5.82635e-05,1.22804e-06,2.0827e-05,-7.31271e-05,-0.00128362,0.204181,0.00196475,0.434409,0,0,0,0,0,1.27149e-05,1.42466e-05,1.42089e-05,0.000368068,0.0371609,0.0371721,0.0100752,0.0505693,0.0505733,0.0600749,1.11986e-10,1.11998e-10,1.32506e-09,9.21908e-07,9.21971e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
23785000,0.982743,-0.0104846,-0.0158123,0.184003,0.0431805,-0.0430462,-0.968451,0.104033,-0.0747151,-3.39112,-1.28615e-05,-5.82296e-05,1.26586e-06,1.72391e-05,-9.26824e-05,-0.00127913,0.204181,0.00196475,0.434409,0,0,0,0,0,1.19326e-05,1.43138e-05,1.42631e-05,0.000345207,0.0325778,0.0325872,0.00996849,0.0445213,0.0445243,0.0596082,1.10754e-10,1.10768e-10,1.32468e-09,8.31267e-07,8.31316e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
23885000,0.98265,-0.0138296,-0.0199451,0.183873,0.0376949,-0.0422759,-0.537905,0.108044,-0.078934,-3.46952,-1.28606e-05,-5.82285e-05,1.26491e-06,1.74012e-05,-9.28052e-05,-0.00127806,0.204181,0.00196475,0.434409,0,0,0,0,0,1.12272e-05,1.45096e-05,1.44399e-05,0.000325088,0.0355629,0.0355745,0.0100396,0.050344,0.0503483,0.0597477,1.10854e-10,1.10867e-10,1.32423e-09,8.31266e-07,8.31319e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
23985000,0.982584,-0.0160929,-0.0224334,0.183759,0.0394344,-0.0391202,-0.153735,0.116872,-0.0809979,-3.53795,-1.27318e-05,-5.81948e-05,1.26292e-06,1.37974e-05,-0.000109369,-0.00125458,0.204181,0.00196475,0.434409,0,0,0,0,0,1.0597e-05,1.46114e-05,1.45325e-05,0.000307289,0.0311387,0.0311496,0.00993599,0.0443681,0.0443714,0.0592879,1.09527e-10,1.09541e-10,1.32372e-09,7.52445e-07,7.52489e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
24085000,0.982611,-0.0157343,-0.0215104,0.183756,0.0448349,-0.0464816,0.0905785,0.121029,-0.0852366,-3.54136,-1.27316e-05,-5.81933e-05,1.23339e-06,1.39592e-05,-0.000109459,-0.00125382,0.204181,0.00196475,0.434409,0,0,0,0,0,1.0036e-05,1.47598e-05,1.46925e-05,0.000291487,0.0339732,0.0339868,0.0100087,0.0501023,0.0501071,0.0594275,1.09627e-10,1.0964e-10,1.32313e-09,7.52444e-07,7.52492e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
24185000,0.982728,-0.0129508,-0.0178554,0.183735,0.0560277,-0.0511637,0.0829512,0.129247,-0.0900847,-3.55765,-1.26609e-05,-5.81487e-05,1.26172e-06,1.56348e-05,-0.000116347,-0.00123492,0.204181,0.00196475,0.434409,0,0,0,0,0,9.55182e-06,1.48171e-05,1.47705e-05,0.000277349,0.0299512,0.0299631,0.00990677,0.0442056,0.0442093,0.0589749,1.08267e-10,1.0828e-10,1.32247e-09,6.8458e-07,6.84621e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
24285000,0.982824,-0.010512,-0.0143776,0.183684,0.0588976,-0.0542095,0.0577567,0.135038,-0.0954077,-3.55387,-1.26598e-05,-5.81479e-05,1.27151e-06,1.57564e-05,-0.000116457,-0.00123399,0.204181,0.00196475,0.434409,0,0,0,0,0,9.10905e-06,1.49656e-05,1.49359e-05,0.000264604,0.0327062,0.0327197,0.00997939,0.049859,0.0498644,0.0591149,1.08366e-10,1.08379e-10,1.32172e-09,6.84579e-07,6.84624e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
24385000,0.982888,-0.00959439,-0.0132956,0.183475,0.0535064,-0.0476358,0.074209,0.142972,-0.0960518,-3.5501,-1.2567e-05,-5.81727e-05,1.31433e-06,8.65025e-06,-0.000130856,-0.00123289,0.204181,0.00196475,0.434409,0,0,0,0,0,8.80813e-06,1.50664e-05,1.50404e-05,0.000256021,0.0288253,0.028836,0.00996205,0.0440376,0.0440417,0.0595425,1.07082e-10,1.07096e-10,1.32112e-09,6.27762e-07,6.27799e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
24485000,0.982928,-0.0098143,-0.0133634,0.183245,0.0476515,-0.0429473,0.0723559,0.148012,-0.100569,-3.54223,-1.25657e-05,-5.81747e-05,1.39273e-06,8.5239e-06,-0.000130858,-0.00123304,0.204181,0.00196475,0.434409,0,0,0,0,0,8.44236e-06,1.52608e-05,1.52359e-05,0.000245251,0.0313583,0.0313701,0.010036,0.0496044,0.0496101,0.0596873,1.07181e-10,1.07194e-10,1.32022e-09,6.2776e-07,6.27802e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
24585000,0.982886,-0.0105138,-0.0134737,0.18342,0.0457267,-0.0374185,0.0677358,0.153336,-0.0976711,-3.53653,-1.24837e-05,-5.82298e-05,1.3905e-06,-7.58224e-07,-0.000146102,-0.00123191,0.204181,0.00196475,0.434409,0,0,0,0,0,8.12102e-06,1.5379e-05,1.53573e-05,0.000235424,0.0276564,0.0276658,0.00993484,0.0438605,0.0438648,0.0592353,1.05999e-10,1.06012e-10,1.31923e-09,5.80549e-07,5.80587e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
24685000,0.98287,-0.0110286,-0.013308,0.183488,0.042261,-0.0358318,0.0668843,0.157785,-0.101269,-3.52974,-1.24837e-05,-5.82297e-05,1.38521e-06,-7.50268e-07,-0.000146103,-0.0012319,0.204181,0.00196475,0.434409,0,0,0,0,0,7.81788e-06,1.55859e-05,1.55682e-05,0.000226452,0.0299904,0.0300008,0.0100092,0.0493333,0.0493392,0.0593808,1.06099e-10,1.06111e-10,1.31814e-09,5.80548e-07,5.8059e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
24785000,0.982895,-0.0111766,-0.0126751,0.183388,0.0399682,-0.0327496,0.0591981,0.161296,-0.0978647,-3.52726,-1.24211e-05,-5.82471e-05,1.39816e-06,-4.26167e-06,-0.000158683,-0.00123101,0.204181,0.00196475,0.434409,0,0,0,0,0,7.52937e-06,1.57091e-05,1.5696e-05,0.000218239,0.0264693,0.0264774,0.0099087,0.0436702,0.0436747,0.0589304,1.05041e-10,1.05053e-10,1.31694e-09,5.41673e-07,5.41712e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
24885000,0.982898,-0.0110196,-0.0121689,0.183419,0.0369759,-0.0352948,0.0488873,0.165165,-0.101273,-3.5241,-1.24197e-05,-5.82469e-05,1.42655e-06,-4.17553e-06,-0.000158786,-0.00123021,0.204181,0.00196475,0.434409,0,0,0,0,0,7.27749e-06,1.59286e-05,1.59175e-05,0.000210675,0.028624,0.0286328,0.00998322,0.049042,0.0490479,0.0590767,1.0514e-10,1.05152e-10,1.31565e-09,5.41672e-07,5.41716e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
24985000,0.982879,-0.010823,-0.0119398,0.183545,0.0299356,-0.0298434,0.0414327,0.166536,-0.0932133,-3.5216,-1.23352e-05,-5.82894e-05,1.42907e-06,-1.02178e-05,-0.000176695,-0.00122975,0.204181,0.00196475,0.434409,0,0,0,0,0,7.11406e-06,1.60633e-05,1.60523e-05,0.000205626,0.0252896,0.0252965,0.00996857,0.0434639,0.0434683,0.0595111,1.04219e-10,1.04231e-10,1.31463e-09,5.09937e-07,5.09978e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
25085000,0.982877,-0.0111612,-0.0120003,0.183534,0.025752,-0.0284281,0.038327,0.169247,-0.0961723,-3.52341,-1.23333e-05,-5.82866e-05,1.41639e-06,-9.91196e-06,-0.000176945,-0.00122772,0.204181,0.00196475,0.434409,0,0,0,0,0,6.88553e-06,1.62994e-05,1.62894e-05,0.00019907,0.0272699,0.0272774,0.0100444,0.0487283,0.048734,0.0596626,1.04318e-10,1.0433e-10,1.31314e-09,5.09936e-07,5.09981e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
25185000,0.982827,-0.01141,-0.0118546,0.183794,0.02282,-0.0223836,0.0383818,0.17135,-0.0894298,-3.52111,-1.23001e-05,-5.83393e-05,1.37606e-06,-1.71754e-05,-0.000187054,-0.0012265,0.204181,0.00196475,0.434409,0,0,0,0,0,6.68944e-06,1.64424e-05,1.64338e-05,0.000192989,0.0241221,0.024128,0.00994475,0.0432395,0.0432438,0.0592129,1.03536e-10,1.03547e-10,1.31154e-09,4.8421e-07,4.84254e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
25285000,0.982779,-0.011559,-0.0112148,0.184082,0.0167842,-0.0229564,0.0331663,0.173296,-0.0916755,-3.51854,-1.23014e-05,-5.83369e-05,1.2876e-06,-1.70567e-05,-0.000187081,-0.00122618,0.204181,0.00196475,0.434409,0,0,0,0,0,6.50397e-06,1.66888e-05,1.66837e-05,0.000187359,0.02595,0.0259565,0.0100208,0.0483912,0.0483967,0.0593653,1.03634e-10,1.03646e-10,1.30983e-09,4.84209e-07,4.84256e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
25385000,0.98278,-0.0117161,-0.0110327,0.18408,0.0101248,-0.0158583,0.0314817,0.170665,-0.0818083,-3.51938,-1.22299e-05,-5.83665e-05,1.29446e-06,-1.9929e-05,-0.000202416,-0.00122408,0.204181,0.00196475,0.434409,0,0,0,0,0,6.32405e-06,1.68392e-05,1.6835e-05,0.000182135,0.0229941,0.0229993,0.00992226,0.0429964,0.0430005,0.0589224,1.02989e-10,1.03e-10,1.30799e-09,4.63514e-07,4.63561e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
25485000,0.98277,-0.0117607,-0.0107357,0.184145,0.00388328,-0.0143515,0.0305812,0.171303,-0.0833154,-3.51804,-1.22298e-05,-5.8365e-05,1.26009e-06,-1.98157e-05,-0.000202491,-0.00122348,0.204181,0.00196475,0.434409,0,0,0,0,0,6.15705e-06,1.71006e-05,1.70973e-05,0.000177279,0.0246805,0.0246861,0.00999833,0.0480319,0.048037,0.0590757,1.03088e-10,1.03098e-10,1.30603e-09,4.63513e-07,4.63563e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
25585000,0.982756,-0.0119992,-0.0105617,0.184217,0.000503152,-0.0122422,0.0323697,0.169166,-0.0774824,-3.5164,-1.22261e-05,-5.83856e-05,1.21532e-06,-2.1812e-05,-0.000208017,-0.00122282,0.204181,0.00196475,0.434409,0,0,0,0,0,6.00095e-06,1.72575e-05,1.72551e-05,0.000172754,0.0219115,0.021916,0.00990066,0.0427349,0.0427388,0.0586392,1.02572e-10,1.02583e-10,1.30395e-09,4.46995e-07,4.47045e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
25685000,0.982767,-0.0114794,-0.0102626,0.184204,-0.00088688,-0.0112689,0.0214946,0.169144,-0.0786912,-3.51649,-1.22246e-05,-5.83847e-05,1.23317e-06,-2.16773e-05,-0.000208151,-0.00122182,0.204181,0.00196475,0.434409,0,0,0,0,0,5.90186e-06,1.75322e-05,1.75285e-05,0.000169854,0.0234809,0.0234854,0.010061,0.0476521,0.0476568,0.0596703,1.02671e-10,1.02681e-10,1.30232e-09,4.46997e-07,4.47049e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
25785000,0.982785,-0.0112891,-0.00957332,0.184158,-0.0103864,-0.0046779,0.0202683,0.1636,-0.0713744,-3.51936,-1.2195e-05,-5.83976e-05,1.23639e-06,-2.14546e-05,-0.000216396,-0.00121977,0.204181,0.00196475,0.434409,0,0,0,0,0,5.76081e-06,1.76921e-05,1.76894e-05,0.000165858,0.0208948,0.0208985,0.00996256,0.0424564,0.04246,0.0592272,1.02277e-10,1.02287e-10,1.30001e-09,4.33941e-07,4.33993e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
25885000,0.982753,-0.0113524,-0.00962086,0.184326,-0.0173383,-0.00219486,0.0226696,0.162147,-0.0716941,-3.51815,-1.21971e-05,-5.83942e-05,1.09977e-06,-2.1326e-05,-0.00021643,-0.00121944,0.204181,0.00196475,0.434409,0,0,0,0,0,5.63088e-06,1.79804e-05,1.79772e-05,0.000162121,0.0223472,0.0223514,0.0100394,0.0472546,0.0472589,0.0593866,1.02375e-10,1.02385e-10,1.29757e-09,4.33941e-07,4.33995e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
25985000,0.982745,-0.0114883,-0.00979571,0.184351,-0.0251301,0.0023087,0.0158935,0.15206,-0.0649438,-3.51841,-1.21707e-05,-5.83716e-05,1.07161e-06,-1.66655e-05,-0.000223894,-0.00121817,0.204181,0.00196475,0.434409,0,0,0,0,0,5.50991e-06,1.81466e-05,1.81423e-05,0.000158623,0.0199398,0.0199431,0.00994152,0.0421626,0.0421658,0.0589496,1.02089e-10,1.02099e-10,1.29499e-09,4.23716e-07,4.2377e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
26085000,0.982777,-0.0111922,-0.00975228,0.184199,-0.0304324,0.00321261,0.0142577,0.149258,-0.0646573,-3.51882,-1.21683e-05,-5.83724e-05,1.14977e-06,-1.66042e-05,-0.000223995,-0.00121748,0.204181,0.00196475,0.434409,0,0,0,0,0,5.39438e-06,1.8447e-05,1.84412e-05,0.000155355,0.0213004,0.021304,0.0100171,0.0468426,0.0468465,0.0591042,1.02188e-10,1.02197e-10,1.29227e-09,4.23716e-07,4.23771e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
26185000,0.982772,-0.0111746,-0.0102826,0.184196,-0.035879,0.00656749,0.00980962,0.140696,-0.0608749,-3.52218,-1.21677e-05,-5.83681e-05,1.20452e-06,-1.41021e-05,-0.000226894,-0.00121566,0.204181,0.00196475,0.434409,0,0,0,0,0,5.29289e-06,1.86152e-05,1.86065e-05,0.000152282,0.0190556,0.0190584,0.00991992,0.0418558,0.0418587,0.0586731,1.01997e-10,1.02006e-10,1.28941e-09,4.15809e-07,4.15863e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
26285000,0.98277,-0.0112426,-0.010598,0.184189,-0.0375429,0.00798826,0.0038475,0.137009,-0.060182,-3.52331,-1.2168e-05,-5.83658e-05,1.13631e-06,-1.39756e-05,-0.000226987,-0.00121502,0.204181,0.00196475,0.434409,0,0,0,0,0,5.22529e-06,1.89288e-05,1.89187e-05,0.000150447,0.0203382,0.0203409,0.0100809,0.0464199,0.0464232,0.0597117,1.02096e-10,1.02105e-10,1.28721e-09,4.15811e-07,4.15866e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
26385000,0.9828,-0.0107382,-0.010576,0.184056,-0.042904,0.0124573,0.00693984,0.124753,-0.0552529,-3.52335,-1.21533e-05,-5.83397e-05,1.09332e-06,-9.1308e-06,-0.000231504,-0.00121487,0.204181,0.00196475,0.434409,0,0,0,0,0,5.1215e-06,1.9094e-05,1.90813e-05,0.000147723,0.0182432,0.018245,0.0099823,0.041539,0.0415414,0.0592734,1.01987e-10,1.01995e-10,1.2841e-09,4.0978e-07,4.09833e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
26485000,0.982808,-0.0104936,-0.0104682,0.184035,-0.0462601,0.0155475,0.0160366,0.120298,-0.0538744,-3.52224,-1.21541e-05,-5.83387e-05,1.04621e-06,-9.1093e-06,-0.000231507,-0.00121486,0.204181,0.00196475,0.434409,0,0,0,0,0,5.02981e-06,1.94179e-05,1.94043e-05,0.000145164,0.0194453,0.019447,0.0100583,0.0459899,0.0459927,0.0594334,1.02085e-10,1.02093e-10,1.28085e-09,4.09779e-07,4.09833e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
26585000,0.982794,-0.0100081,-0.0107474,0.184121,-0.046661,0.0205937,0.0163985,0.111754,-0.0498519,-3.52254,-1.2142e-05,-5.8326e-05,9.81689e-07,-6.86961e-06,-0.000234385,-0.00121327,0.204181,0.00196475,0.434409,0,0,0,0,0,4.94861e-06,1.95811e-05,1.95643e-05,0.000142755,0.017497,0.0174979,0.0099601,0.0412147,0.0412168,0.0590005,1.02039e-10,1.02047e-10,1.27745e-09,4.05235e-07,4.05286e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
26685000,0.982786,-0.0098884,-0.0104591,0.184188,-0.0485978,0.0254453,0.0155401,0.106976,-0.04755,-3.52105,-1.21441e-05,-5.83234e-05,8.59223e-07,-6.8166e-06,-0.000234399,-0.00121323,0.204181,0.00196475,0.434409,0,0,0,0,0,4.86845e-06,1.99157e-05,1.98992e-05,0.0001405,0.0186483,0.0186488,0.0100357,0.0455565,0.0455588,0.0591606,1.02137e-10,1.02145e-10,1.27391e-09,4.05235e-07,4.05286e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
26785000,0.982806,-0.00973489,-0.00995513,0.184115,-0.0538266,0.0265612,0.0141826,0.0958797,-0.0453436,-3.52377,-1.21249e-05,-5.82977e-05,8.14849e-07,-2.64807e-06,-0.000236941,-0.00121132,0.204181,0.00196475,0.434409,0,0,0,0,0,4.78996e-06,2.00699e-05,2.0054e-05,0.000138383,0.0168345,0.0168347,0.00993797,0.0408863,0.040888,0.0587329,1.02139e-10,1.02147e-10,1.27022e-09,4.01872e-07,4.01919e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
26885000,0.982836,-0.00913354,-0.0100463,0.18398,-0.0595803,0.0292209,0.00981624,0.090174,-0.0425584,-3.52307,-1.21229e-05,-5.82995e-05,9.14536e-07,-2.6513e-06,-0.000236968,-0.00121112,0.204181,0.00196475,0.434409,0,0,0,0,0,4.72005e-06,2.04171e-05,2.03989e-05,0.000136392,0.0179408,0.017941,0.0100132,0.0451246,0.0451264,0.058893,1.02237e-10,1.02245e-10,1.26638e-09,4.01871e-07,4.01918e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
26985000,0.982829,-0.00865809,-0.0105396,0.184014,-0.065297,0.0328738,0.00783868,0.0788849,-0.0391151,-3.52757,-1.2092e-05,-5.82738e-05,8.60819e-07,8.65309e-07,-0.000240301,-0.00120874,0.204181,0.00196475,0.434409,0,0,0,0,0,4.68464e-06,2.0565e-05,2.05433e-05,0.000135352,0.0162499,0.0162498,0.00999932,0.0405575,0.0405588,0.0593377,1.0227e-10,1.02278e-10,1.26342e-09,3.99425e-07,3.99466e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
27085000,0.982829,-0.00848819,-0.0108751,0.184004,-0.0674898,0.0400227,0.0116733,0.072173,-0.0354534,-3.53095,-1.20899e-05,-5.82712e-05,8.38582e-07,1.10978e-06,-0.000240558,-0.00120715,0.204181,0.00196475,0.434409,0,0,0,0,0,4.62284e-06,2.09234e-05,2.08997e-05,0.00013357,0.0173102,0.0173095,0.0100751,0.0446982,0.0446995,0.0595023,1.02367e-10,1.02375e-10,1.25932e-09,3.99425e-07,3.99464e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
27185000,0.982835,-0.00856309,-0.0107887,0.183971,-0.0723111,0.0430942,0.0129174,0.0627116,-0.0319473,-3.53345,-1.20544e-05,-5.82514e-05,8.19729e-07,3.37962e-06,-0.000243314,-0.0012057,0.204181,0.00196475,0.434409,0,0,0,0,0,4.56368e-06,2.10566e-05,2.10329e-05,0.000131894,0.0157297,0.0157289,0.00997638,0.0402315,0.0402325,0.0590718,1.02411e-10,1.0242e-10,1.25506e-09,3.97661e-07,3.97694e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
27285000,0.982842,-0.00873009,-0.0117131,0.183869,-0.0789068,0.0489467,0.115764,0.0551922,-0.0273587,-3.53159,-1.20527e-05,-5.82502e-05,8.27168e-07,3.5259e-06,-0.000243477,-0.00120471,0.204181,0.00196475,0.434409,0,0,0,0,0,4.50626e-06,2.14271e-05,2.13999e-05,0.000130322,0.0166678,0.0166667,0.0100517,0.0442797,0.0442806,0.0592361,1.02509e-10,1.02517e-10,1.25065e-09,3.97661e-07,3.97691e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
27385000,0.982802,-0.0100954,-0.0141984,0.183839,-0.0823568,0.0536289,0.431614,0.0472977,-0.022334,-3.51337,-1.20042e-05,-5.82085e-05,8.40757e-07,6.60516e-06,-0.000247057,-0.00119979,0.204181,0.00196475,0.434409,0,0,0,0,0,4.45671e-06,2.15619e-05,2.15274e-05,0.000128828,0.0149216,0.0149205,0.00995177,0.0399042,0.0399049,0.0588047,1.02551e-10,1.02561e-10,1.24608e-09,3.96389e-07,3.96412e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
27485000,0.982746,-0.0115366,-0.0161732,0.183893,-0.0853733,0.0591358,0.75069,0.0388652,-0.0166793,-3.45575,-1.20046e-05,-5.82047e-05,7.1851e-07,6.77532e-06,-0.00024724,-0.00119886,0.204181,0.00196475,0.434409,0,0,0,0,0,4.40967e-06,2.19464e-05,2.19062e-05,0.000127429,0.0156224,0.0156208,0.0100262,0.0438374,0.043838,0.0589684,1.02649e-10,1.02658e-10,1.24138e-09,3.96389e-07,3.96409e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
27585000,0.982767,-0.0115534,-0.0151948,0.183858,-0.0784464,0.0599329,0.855289,0.031822,-0.0146414,-3.39499,-1.19328e-05,-5.8161e-05,7.28369e-07,1.04673e-05,-0.000251562,-0.00118372,0.204181,0.00196475,0.434409,0,0,0,0,0,4.38858e-06,2.20972e-05,2.20614e-05,0.000126862,0.0142014,0.0141992,0.0100115,0.0395588,0.0395591,0.0594165,1.02701e-10,1.02711e-10,1.23776e-09,3.95464e-07,3.95474e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
27685000,0.982837,-0.0104079,-0.0123048,0.183771,-0.0746751,0.0558452,0.762324,0.0242049,-0.00878931,-3.31687,-1.193e-05,-5.81602e-05,7.74208e-07,1.06451e-05,-0.000251775,-0.00118245,0.204181,0.00196475,0.434409,0,0,0,0,0,4.34264e-06,2.24741e-05,2.2447e-05,0.000125636,0.0152296,0.0152273,0.0100867,0.0433963,0.0433964,0.0595844,1.02798e-10,1.02808e-10,1.23279e-09,3.95464e-07,3.95471e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
27785000,0.982873,-0.00908454,-0.0107252,0.183749,-0.072639,0.0510956,0.749723,0.0192973,-0.00825231,-3.24308,-1.18786e-05,-5.81383e-05,8.42675e-07,1.17395e-05,-0.000253218,-0.00118359,0.204181,0.00196475,0.434409,0,0,0,0,0,4.304e-06,2.26022e-05,2.25775e-05,0.000124473,0.0140051,0.0140032,0.00998571,0.0392221,0.0392222,0.0591491,1.02815e-10,1.02826e-10,1.22765e-09,3.94762e-07,3.9476e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
27885000,0.98287,-0.00869832,-0.0108057,0.183776,-0.0790057,0.0568524,0.791383,0.0117282,-0.00290508,-3.16842,-1.18765e-05,-5.81372e-05,8.57401e-07,1.18915e-05,-0.000253402,-0.00118254,0.204181,0.00196475,0.434409,0,0,0,0,0,4.26923e-06,2.29989e-05,2.29727e-05,0.000123377,0.014913,0.0149109,0.0100607,0.0429885,0.0429883,0.0593161,1.02912e-10,1.02923e-10,1.22239e-09,3.94763e-07,3.94756e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
27985000,0.98287,-0.00916666,-0.0111981,0.183734,-0.0786755,0.0570648,0.778695,0.00751944,-0.0028222,-3.09806,-1.17936e-05,-5.8092e-05,8.81393e-07,1.44441e-05,-0.000256922,-0.00117788,0.204181,0.00196475,0.434409,0,0,0,0,0,4.2339e-06,2.3108e-05,2.30812e-05,0.000122346,0.0137649,0.0137629,0.00996049,0.0389068,0.0389066,0.0588851,1.0288e-10,1.02892e-10,1.21695e-09,3.94186e-07,3.94169e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
28085000,0.982893,-0.00950033,-0.0112067,0.183588,-0.0820022,0.0570849,0.784927,-0.000473517,0.00292244,-3.02031,-1.17904e-05,-5.80954e-05,1.05044e-06,1.44265e-05,-0.000256933,-0.00117776,0.204181,0.00196475,0.434409,0,0,0,0,0,4.20077e-06,2.35128e-05,2.34862e-05,0.000121383,0.0147078,0.0147059,0.0100346,0.0426092,0.0426087,0.0590512,1.02976e-10,1.02989e-10,1.2114e-09,3.94186e-07,3.94165e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
28185000,0.982897,-0.00901269,-0.0115134,0.183574,-0.0812717,0.0520275,0.790748,-0.00619725,0.00197413,-2.94611,-1.16998e-05,-5.80589e-05,1.06562e-06,1.66395e-05,-0.000260733,-0.00117527,0.204181,0.00196475,0.434409,0,0,0,0,0,4.17049e-06,2.35889e-05,2.356e-05,0.000120476,0.0136085,0.013607,0.00993447,0.0386143,0.0386139,0.0586243,1.0287e-10,1.02885e-10,1.20567e-09,3.93621e-07,3.93587e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
28285000,0.982919,-0.00850153,-0.0118075,0.183465,-0.0861278,0.0545668,0.791311,-0.0145213,0.00735111,-2.86946,-1.1696e-05,-5.80604e-05,1.19371e-06,1.67456e-05,-0.000260886,-0.00117436,0.204181,0.00196475,0.434409,0,0,0,0,0,4.16424e-06,2.40031e-05,2.39716e-05,0.000120292,0.0145638,0.0145623,0.0100934,0.0422626,0.0422619,0.0596662,1.02967e-10,1.02982e-10,1.20132e-09,3.93624e-07,3.93587e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
28385000,0.98291,-0.00855139,-0.0124521,0.183469,-0.0858547,0.0562142,0.792301,-0.0183864,0.00924654,-2.79669,-1.15992e-05,-5.79887e-05,1.34845e-06,2.04173e-05,-0.000265298,-0.00117172,0.204181,0.00196475,0.434409,0,0,0,0,0,4.14259e-06,2.40422e-05,2.40083e-05,0.000119479,0.0135258,0.0135244,0.00999216,0.0383477,0.0383471,0.0592307,1.02768e-10,1.02785e-10,1.19533e-09,3.92977e-07,3.92928e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
28485000,0.982907,-0.00887577,-0.0129568,0.183431,-0.0869326,0.0585604,0.793421,-0.0269918,0.0149605,-2.72204,-1.15962e-05,-5.79868e-05,1.35904e-06,2.06481e-05,-0.000265588,-0.0011701,0.204181,0.00196475,0.434409,0,0,0,0,0,4.11671e-06,2.44636e-05,2.4428e-05,0.000118728,0.0144919,0.0144904,0.0100664,0.0419529,0.0419521,0.0593995,1.02864e-10,1.02881e-10,1.18924e-09,3.92977e-07,3.92924e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
28585000,0.982943,-0.00899082,-0.0129467,0.183232,-0.0799717,0.0529609,0.790741,-0.0296321,0.0117215,-2.64652,-1.14476e-05,-5.79305e-05,1.48137e-06,2.35286e-05,-0.000271833,-0.00116844,0.204181,0.00196475,0.434409,0,0,0,0,0,4.08804e-06,2.4457e-05,2.44217e-05,0.000118026,0.0135046,0.0135034,0.00996497,0.0381105,0.0381098,0.058968,1.02552e-10,1.02571e-10,1.18298e-09,3.92167e-07,3.92101e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
28685000,0.98294,-0.00879025,-0.0123405,0.1833,-0.0794225,0.0528758,0.79158,-0.037588,0.0170393,-2.57146,-1.14451e-05,-5.79285e-05,1.4735e-06,2.37399e-05,-0.000272101,-0.00116696,0.204181,0.00196475,0.434409,0,0,0,0,0,4.0688e-06,2.48813e-05,2.48474e-05,0.000117367,0.0144872,0.0144859,0.0100375,0.0416832,0.0416822,0.05913,1.02648e-10,1.02668e-10,1.1766e-09,3.92168e-07,3.92096e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
28785000,0.982964,-0.00818285,-0.0121725,0.183213,-0.0747308,0.0518569,0.790151,-0.0395317,0.018147,-2.49928,-1.13333e-05,-5.78361e-05,1.6482e-06,2.84453e-05,-0.000277277,-0.00116348,0.204181,0.00196475,0.434409,0,0,0,0,0,4.04905e-06,2.48247e-05,2.47909e-05,0.000116749,0.0135327,0.0135318,0.00993673,0.0379049,0.0379041,0.0587025,1.02202e-10,1.02226e-10,1.17007e-09,3.91119e-07,3.91036e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
28885000,0.982993,-0.00800697,-0.0119152,0.183079,-0.0783358,0.052699,0.789452,-0.0471526,0.0233652,-2.42316,-1.13291e-05,-5.78368e-05,1.76303e-06,2.85998e-05,-0.000277488,-0.00116246,0.204181,0.00196475,0.434409,0,0,0,0,0,4.04883e-06,2.52555e-05,2.5222e-05,0.000116801,0.0145367,0.014536,0.0100953,0.0414551,0.041454,0.0597478,1.02299e-10,1.02324e-10,1.16513e-09,3.91123e-07,3.91035e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
28985000,0.982982,-0.00781704,-0.0121643,0.18313,-0.0736046,0.0484088,0.788553,-0.0461488,0.0219624,-2.35199,-1.11728e-05,-5.77367e-05,1.83886e-06,3.33463e-05,-0.000284679,-0.00115878,0.204181,0.00196475,0.434409,0,0,0,0,0,4.03523e-06,2.51455e-05,2.51115e-05,0.00011625,0.0136073,0.0136071,0.00999301,0.0377324,0.0377317,0.0593115,1.01703e-10,1.01733e-10,1.15837e-09,3.89778e-07,3.89679e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
29085000,0.982985,-0.00770617,-0.0122115,0.183119,-0.0761266,0.0496807,0.788262,-0.0536952,0.0268389,-2.2751,-1.11707e-05,-5.77366e-05,1.88016e-06,3.34442e-05,-0.000284811,-0.00115809,0.204181,0.00196475,0.434409,0,0,0,0,0,4.01932e-06,2.5581e-05,2.55467e-05,0.000115742,0.0146324,0.0146326,0.0100659,0.0412698,0.0412689,0.0594756,1.01798e-10,1.01831e-10,1.1515e-09,3.89779e-07,3.89674e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
29185000,0.983015,-0.00768802,-0.0124671,0.18294,-0.0714119,0.046867,0.782463,-0.0510419,0.0257749,-2.20667,-1.10079e-05,-5.7605e-05,2.07157e-06,3.98371e-05,-0.000292351,-0.00115336,0.204181,0.00196475,0.434409,0,0,0,0,0,4.00086e-06,2.54125e-05,2.5378e-05,0.000115269,0.0137256,0.0137261,0.00996426,0.0375943,0.0375937,0.0590433,1.0104e-10,1.01077e-10,1.14449e-09,3.88093e-07,3.87977e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
29285000,0.983001,-0.00793621,-0.0125067,0.183,-0.0725953,0.0518208,0.784867,-0.0582013,0.0307532,-2.12975,-1.10049e-05,-5.76062e-05,2.17365e-06,3.99128e-05,-0.000292463,-0.00115285,0.204181,0.00196475,0.434409,0,0,0,0,0,3.99182e-06,2.58509e-05,2.58168e-05,0.000114821,0.0147705,0.014771,0.0100368,0.0411282,0.0411275,0.0592059,1.01135e-10,1.01174e-10,1.13737e-09,3.88095e-07,3.87972e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
29385000,0.983014,-0.0084113,-0.0120327,0.182942,-0.0677885,0.049921,0.787064,-0.0562357,0.0314709,-2.05464,-1.08655e-05,-5.74968e-05,2.31478e-06,4.49725e-05,-0.000298806,-0.0011511,0.204181,0.00196475,0.434409,0,0,0,0,0,3.97915e-06,2.56182e-05,2.55876e-05,0.000114408,0.0138644,0.0138653,0.00993562,0.0374906,0.0374901,0.0587775,1.00203e-10,1.00247e-10,1.13013e-09,3.86034e-07,3.85901e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
29485000,0.983031,-0.00846384,-0.0119025,0.182857,-0.0695692,0.049744,0.788328,-0.0630553,0.0364794,-1.9779,-1.08599e-05,-5.75015e-05,2.56792e-06,4.50124e-05,-0.000298913,-0.00115038,0.204181,0.00196475,0.434409,0,0,0,0,0,3.96915e-06,2.60583e-05,2.60278e-05,0.000114022,0.0149334,0.0149347,0.0100075,0.0410286,0.0410281,0.0589387,1.003e-10,1.00343e-10,1.12279e-09,3.86036e-07,3.85898e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
29585000,0.983051,-0.00840411,-0.0119253,0.182751,-0.0646253,0.0468589,0.790141,-0.060314,0.0355825,-1.89987,-1.06963e-05,-5.73939e-05,2.73748e-06,4.9904e-05,-0.000306181,-0.00115024,0.204181,0.00196475,0.434409,0,0,0,0,0,3.97765e-06,2.57638e-05,2.57336e-05,0.000114261,0.0140303,0.0140318,0.00999056,0.0374203,0.0374199,0.0593829,9.91893e-11,9.92359e-11,1.11721e-09,3.83587e-07,3.83442e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
29685000,0.983081,-0.00847444,-0.0117225,0.182602,-0.0684355,0.0449604,0.785928,-0.0669351,0.0402104,-1.82507,-1.069e-05,-5.73972e-05,2.95945e-06,5.00397e-05,-0.000306412,-0.00114881,0.204181,0.00196475,0.434409,0,0,0,0,0,3.96549e-06,2.62042e-05,2.61745e-05,0.000113928,0.0151302,0.0151323,0.0100631,0.0409702,0.0409699,0.0595474,9.92857e-11,9.93317e-11,1.10967e-09,3.83589e-07,3.83439e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
29785000,0.983094,-0.00835976,-0.0122686,0.182501,-0.0637471,0.0369302,0.782246,-0.0621022,0.0376438,-1.75292,-1.05242e-05,-5.72639e-05,3.212e-06,5.63573e-05,-0.000313809,-0.0011459,0.204181,0.00196475,0.434409,0,0,0,0,0,3.95697e-06,2.58453e-05,2.58141e-05,0.000113611,0.0142243,0.0142268,0.0099612,0.0373827,0.0373825,0.0591142,9.79904e-11,9.80391e-11,1.10202e-09,3.80736e-07,3.80579e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
29885000,0.983103,-0.00786396,-0.012664,0.182446,-0.0633729,0.0364922,0.778575,-0.0683483,0.0412753,-1.6809,-1.05164e-05,-5.72655e-05,3.42108e-06,5.66348e-05,-0.000314209,-0.00114378,0.204181,0.00196475,0.434409,0,0,0,0,0,3.95016e-06,2.62868e-05,2.62533e-05,0.000113318,0.0153463,0.0153493,0.0100332,0.0409515,0.0409515,0.0592772,9.80856e-11,9.8136e-11,1.09428e-09,3.80739e-07,3.80576e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
29985000,0.983103,-0.00800628,-0.0127479,0.182434,-0.0578641,0.0313501,0.775538,-0.0638932,0.0369425,-1.6113,-1.0324e-05,-5.71588e-05,3.51976e-06,6.16736e-05,-0.000323108,-0.0011399,0.204181,0.00196475,0.434409,0,0,0,0,0,3.94297e-06,2.58603e-05,2.58278e-05,0.000113044,0.0144242,0.0144273,0.00993109,0.0373758,0.037376,0.0588426,9.6606e-11,9.66609e-11,1.08642e-09,3.77492e-07,3.77323e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
30085000,0.983102,-0.00816616,-0.0128959,0.182422,-0.0573268,0.0309912,0.773569,-0.069649,0.0400832,-1.53743,-1.03254e-05,-5.71545e-05,3.36033e-06,6.18271e-05,-0.000323286,-0.0011386,0.204181,0.00196475,0.434409,0,0,0,0,0,3.93072e-06,2.6299e-05,2.62663e-05,0.000112797,0.015567,0.0155707,0.0100028,0.0409685,0.040969,0.059004,9.67013e-11,9.67576e-11,1.0785e-09,3.77495e-07,3.77321e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
30185000,0.983078,-0.00816063,-0.0129252,0.18255,-0.0507566,0.0274271,0.773485,-0.0632003,0.0388077,-1.46555,-1.02306e-05,-5.70003e-05,3.23705e-06,6.87413e-05,-0.000327697,-0.00113613,0.204181,0.00196475,0.434409,0,0,0,0,0,3.94585e-06,2.58083e-05,2.57766e-05,0.000113147,0.0146222,0.0146258,0.00998592,0.0373965,0.0373971,0.0594494,9.50461e-11,9.51063e-11,1.0725e-09,3.73877e-07,3.737e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
30285000,0.983069,-0.00819959,-0.0129319,0.182594,-0.0493447,0.0263276,0.773737,-0.0681459,0.0415092,-1.39322,-1.02264e-05,-5.70001e-05,3.3158e-06,6.89567e-05,-0.000327996,-0.00113434,0.204181,0.00196475,0.434409,0,0,0,0,0,3.94249e-06,2.62435e-05,2.62119e-05,0.000112924,0.0157811,0.0157853,0.0100582,0.0410169,0.0410179,0.0596141,9.51414e-11,9.52029e-11,1.06442e-09,3.73881e-07,3.73699e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
30385000,0.983067,-0.00819685,-0.0128774,0.182611,-0.0413107,0.0205084,0.771329,-0.0601282,0.0390769,-1.32528,-1.00907e-05,-5.68271e-05,3.63966e-06,7.72907e-05,-0.000334124,-0.00113015,0.204181,0.00196475,0.434409,0,0,0,0,0,3.94357e-06,2.56916e-05,2.56615e-05,0.000112712,0.0148141,0.0148182,0.00995548,0.0374412,0.0374422,0.0591748,9.33204e-11,9.33855e-11,1.05623e-09,3.69927e-07,3.69742e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
30485000,0.983101,-0.00822208,-0.0130233,0.182415,-0.0433334,0.0194732,0.772299,-0.064309,0.0411224,-1.2535,-1.00833e-05,-5.68296e-05,3.86335e-06,7.75164e-05,-0.000334462,-0.00112822,0.204181,0.00196475,0.434409,0,0,0,0,0,3.93416e-06,2.61229e-05,2.60925e-05,0.000112526,0.0159898,0.0159945,0.0100276,0.0410919,0.0410934,0.059338,9.34158e-11,9.34821e-11,1.048e-09,3.69931e-07,3.69741e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
30585000,0.983123,-0.00854124,-0.0133242,0.182259,-0.0381443,0.0166866,0.771937,-0.0575168,0.0379834,-1.18178,-9.95402e-06,-5.66934e-05,4.12157e-06,8.39965e-05,-0.000340223,-0.00112565,0.204181,0.00196475,0.434409,0,0,0,0,0,3.9275e-06,2.55155e-05,2.54859e-05,0.000112348,0.0149947,0.0149992,0.00992578,0.037506,0.0375073,0.0589029,9.1444e-11,9.15132e-11,1.03966e-09,3.65681e-07,3.6549e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
30685000,0.983144,-0.00892344,-0.0135669,0.18211,-0.0358396,0.0141212,0.77084,-0.061271,0.0395645,-1.11071,-9.94951e-06,-5.6693e-05,4.20319e-06,8.42404e-05,-0.000340555,-0.00112349,0.204181,0.00196475,0.434409,0,0,0,0,0,3.91779e-06,2.59416e-05,2.59121e-05,0.000112187,0.0161894,0.0161945,0.00999739,0.0411887,0.0411907,0.0590647,9.15394e-11,9.16096e-11,1.03129e-09,3.65686e-07,3.65491e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
30785000,0.983175,-0.00862658,-0.0132927,0.181979,-0.0283834,0.00912103,0.769412,-0.0545717,0.039426,-1.04075,-9.94915e-06,-5.65589e-05,4.24633e-06,9.04668e-05,-0.000340634,-0.00112025,0.204181,0.00196475,0.434409,0,0,0,0,0,3.90748e-06,2.5281e-05,2.52531e-05,0.000112039,0.0151657,0.0151705,0.00989602,0.0375868,0.0375885,0.0586338,8.94337e-11,8.95061e-11,1.02282e-09,3.61188e-07,3.60993e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
30885000,0.983168,-0.00799995,-0.013161,0.182056,-0.0274628,0.00471174,0.767076,-0.0572888,0.0401681,-0.968432,-9.94792e-06,-5.6557e-05,4.21627e-06,9.06372e-05,-0.000340848,-0.00111868,0.204181,0.00196475,0.434409,0,0,0,0,0,3.92521e-06,2.57003e-05,2.56714e-05,0.000112474,0.0163771,0.0163824,0.0100522,0.0413027,0.0413052,0.0596711,8.95303e-11,8.96033e-11,1.01647e-09,3.61194e-07,3.60997e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
30985000,0.98317,-0.00817516,-0.0131233,0.182036,-0.0201211,-0.00012206,0.768546,-0.0478442,0.0343371,-0.899336,-9.81807e-06,-5.6423e-05,4.26254e-06,9.68274e-05,-0.000346821,-0.00111552,0.204181,0.00196475,0.434409,0,0,0,0,0,3.92057e-06,2.49941e-05,2.49669e-05,0.000112338,0.015317,0.0153219,0.00994984,0.03768,0.0376821,0.0592316,8.73093e-11,8.73835e-11,1.00791e-09,3.56498e-07,3.56302e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
31085000,0.983133,-0.00832635,-0.013237,0.182223,-0.0178204,-0.00326621,0.767549,-0.0496936,0.0341003,-0.825255,-9.81806e-06,-5.64213e-05,4.21383e-06,9.69282e-05,-0.000346939,-0.00111457,0.204181,0.00196475,0.434409,0,0,0,0,0,3.92335e-06,2.54064e-05,2.53792e-05,0.000112204,0.0165377,0.0165431,0.0100219,0.0414282,0.0414311,0.0593951,8.74048e-11,8.74797e-11,9.99307e-10,3.56503e-07,3.56304e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
31185000,0.983154,-0.00846111,-0.0133858,0.18209,-0.0135568,-0.00651043,0.769048,-0.0419876,0.0306317,-0.755401,-9.77366e-06,-5.63184e-05,4.53694e-06,0.000101941,-0.000348821,-0.001112,0.204181,0.00196475,0.434409,0,0,0,0,0,3.92055e-06,2.4662e-05,2.46357e-05,0.000112082,0.0154474,0.0154524,0.00992037,0.0377812,0.0377837,0.05896,8.50908e-11,8.51662e-11,9.90643e-10,3.51666e-07,3.51469e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
31285000,0.983178,-0.0087316,-0.0134705,0.181944,-0.0099135,-0.0101067,0.772953,-0.0431104,0.0298427,-0.683769,-9.76757e-06,-5.63209e-05,4.73137e-06,0.000102132,-0.000349099,-0.00111006,0.204181,0.00196475,0.434409,0,0,0,0,0,3.91485e-06,2.50661e-05,2.50403e-05,0.000111969,0.0166657,0.0166712,0.00999118,0.0415601,0.0415634,0.0591167,8.51863e-11,8.52624e-11,9.81943e-10,3.51671e-07,3.51472e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
31385000,0.98319,-0.00850604,-0.0132732,0.181902,-0.00438435,-0.0156624,0.772299,-0.0352997,0.025934,-0.610895,-9.74644e-06,-5.62425e-05,4.64075e-06,0.000105653,-0.000350238,-0.00110758,0.204181,0.00196475,0.434409,0,0,0,0,0,3.9069e-06,2.429e-05,2.42653e-05,0.000111866,0.015551,0.0155558,0.00989033,0.0378862,0.0378889,0.058686,8.28035e-11,8.28792e-11,9.73197e-10,3.46755e-07,3.46561e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
31485000,0.983175,-0.00825801,-0.0135884,0.181974,-0.00366165,-0.0202699,0.769147,-0.0357495,0.0240967,-0.535744,-9.74596e-06,-5.62419e-05,4.63495e-06,0.000105717,-0.000350315,-0.00110692,0.204181,0.00196475,0.434409,0,0,0,0,0,3.92656e-06,2.46865e-05,2.46601e-05,0.000112339,0.0167888,0.0167941,0.0100469,0.0416943,0.0416979,0.0597254,8.29002e-11,8.29763e-11,9.66648e-10,3.46762e-07,3.46566e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
31585000,0.983205,-0.00806025,-0.0140632,0.181785,0.000406088,-0.0207649,0.772767,-0.025778,0.0218013,-0.464307,-9.75744e-06,-5.61092e-05,4.85172e-06,0.000111938,-0.00034983,-0.00110422,0.204181,0.00196475,0.434409,0,0,0,0,0,3.91968e-06,2.38867e-05,2.38593e-05,0.000112243,0.0156367,0.0156413,0.00994504,0.0379922,0.0379951,0.0592861,8.04666e-11,8.05414e-11,9.57841e-10,3.41808e-07,3.41617e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
31685000,0.983235,-0.0080622,-0.0145422,0.181581,-0.000813908,-0.023195,0.769089,-0.0258082,0.0195273,-0.39481,-9.74983e-06,-5.61126e-05,5.10382e-06,0.000112182,-0.000350178,-0.00110148,0.204181,0.00196475,0.434409,0,0,0,0,0,3.91341e-06,2.42743e-05,2.42452e-05,0.000112149,0.0168746,0.0168797,0.0100166,0.0418264,0.0418302,0.0594449,8.05623e-11,8.06375e-11,9.49012e-10,3.41814e-07,3.41621e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
31785000,0.983253,-0.00821287,-0.0152085,0.181421,0.00772033,-0.0242694,0.768949,-0.0153645,0.020269,-0.323352,-9.84829e-06,-5.59487e-05,5.31725e-06,0.000119748,-0.000345912,-0.00109894,0.204181,0.00196475,0.434409,0,0,0,0,0,3.90795e-06,2.34576e-05,2.34277e-05,0.000112058,0.015703,0.0157074,0.00991542,0.0380958,0.0380989,0.0590101,7.81014e-11,7.81748e-11,9.40155e-10,3.36877e-07,3.3669e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
31885000,0.983268,-0.00798971,-0.0150143,0.181371,0.0122239,-0.0278764,0.767678,-0.014335,0.0175967,-0.254096,-9.84313e-06,-5.59502e-05,5.46607e-06,0.000119983,-0.000346218,-0.00109626,0.204181,0.00196475,0.434409,0,0,0,0,0,3.90558e-06,2.38335e-05,2.3804e-05,0.000111968,0.0169369,0.0169417,0.00998656,0.0419539,0.0419579,0.0591675,7.81971e-11,7.82709e-11,9.31282e-10,3.36883e-07,3.36695e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
31985000,0.98326,-0.0081585,-0.0145871,0.181439,0.0196165,-0.0268149,0.764353,-0.00369284,0.0169737,-0.187682,-9.92241e-06,-5.58237e-05,5.41507e-06,0.000125775,-0.000343162,-0.0010919,0.204181,0.00196475,0.434409,0,0,0,0,0,3.90343e-06,2.30025e-05,2.29762e-05,0.000111881,0.0157442,0.0157483,0.0098862,0.0381949,0.0381981,0.0587372,7.57281e-11,7.57994e-11,9.22391e-10,3.32007e-07,3.31825e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
32085000,0.983279,-0.0085422,-0.0142212,0.181348,0.020517,-0.0314731,0.766745,-0.00166212,0.0141202,-0.116769,-9.92036e-06,-5.58233e-05,5.44924e-06,0.000125947,-0.000343364,-0.00108987,0.204181,0.00196475,0.434409,0,0,0,0,0,3.89701e-06,2.3368e-05,2.3344e-05,0.000111799,0.0169704,0.0169749,0.00995716,0.0420732,0.0420772,0.0588935,7.58238e-11,7.58955e-11,9.13492e-10,3.32013e-07,3.3183e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
32185000,0.983272,-0.00868874,-0.0144894,0.181358,0.0243551,-0.032362,0.7668,0.00794614,0.0155323,-0.0476029,-1.00765e-05,-5.57174e-05,5.43483e-06,0.000130815,-0.000336967,-0.00108626,0.204181,0.00196475,0.434409,0,0,0,0,0,3.91372e-06,2.2535e-05,2.25115e-05,0.000112291,0.0157533,0.015757,0.00994078,0.0382866,0.0382898,0.0593349,7.33667e-11,7.34354e-11,9.06827e-10,3.27238e-07,3.27063e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
32285000,0.983292,-0.00861369,-0.0147496,0.181232,0.0269006,-0.0369095,0.765321,0.0105283,0.0120333,0.0214395,-1.00718e-05,-5.57191e-05,5.58433e-06,0.000131035,-0.000337237,-0.00108355,0.204181,0.00196475,0.434409,0,0,0,0,0,3.90863e-06,2.28925e-05,2.2868e-05,0.000112208,0.0169804,0.0169843,0.0100125,0.0421809,0.042185,0.0594945,7.34625e-11,7.35316e-11,8.97914e-10,3.27245e-07,3.27069e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
32385000,0.983274,-0.00860837,-0.0148514,0.181321,0.0326668,-0.0357417,0.764,0.0200932,0.0121837,0.0942107,-1.02017e-05,-5.56443e-05,5.53325e-06,0.000134463,-0.000331971,-0.00108091,0.204181,0.00196475,0.434409,0,0,0,0,0,3.90774e-06,2.20606e-05,2.20365e-05,0.000112121,0.0157501,0.0157534,0.00991187,0.0383692,0.0383724,0.0590604,7.10317e-11,7.10973e-11,8.88997e-10,3.22604e-07,3.22435e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
32485000,0.983291,-0.0115132,-0.0127894,0.181228,0.0610095,-0.10337,-0.108565,0.0252657,0.00343277,0.102762,-1.02025e-05,-5.56416e-05,5.44681e-06,0.000134499,-0.000331997,-0.00108048,0.204181,0.00196475,0.434409,0,0,0,0,0,3.89853e-06,2.24008e-05,2.23918e-05,0.000112043,0.0189838,0.0189857,0.00978657,0.0423791,0.0423832,0.0592101,7.11282e-11,7.11926e-11,8.80085e-10,0,0,0,0,0,0,0,0,0,0,0
|
||||
32585000,0.983307,-0.011399,-0.012725,0.181149,0.0592455,-0.101432,-0.109955,0.0352402,0.00328092,0.0848866,-1.0526e-05,-5.55767e-05,5.64202e-06,0.000134499,-0.000331997,-0.00108048,0.204181,0.00196475,0.434409,0,0,0,0,0,3.89523e-06,2.13883e-05,2.13791e-05,0.000111954,0.0180971,0.018099,0.0094198,0.0385723,0.0385755,0.05874,6.84058e-11,6.84605e-11,8.71166e-10,0,0,0,0,0,0,0,0,0,0,0
|
||||
32685000,0.983312,-0.0113883,-0.0125952,0.181131,0.0564341,-0.108106,-0.111748,0.0410737,-0.00720347,0.0701402,-1.05259e-05,-5.55757e-05,5.62057e-06,0.000134499,-0.000331997,-0.00108048,0.204181,0.00196475,0.434409,0,0,0,0,0,3.8906e-06,2.17223e-05,2.17129e-05,0.00011187,0.0201473,0.0201503,0.0092243,0.0427365,0.0427407,0.0588134,6.85026e-11,6.85558e-11,8.6227e-10,0,0,0,0,0,0,0,0,0,0,0
|
||||
32785000,0.983321,-0.0111366,-0.0126447,0.181097,0.052883,-0.102802,-0.112368,0.0485437,-0.00546125,0.0552821,-1.0894e-05,-5.5513e-05,5.80108e-06,0.000134499,-0.000331997,-0.00108048,0.204181,0.00196475,0.434409,0,0,0,0,0,3.90879e-06,2.05752e-05,2.05648e-05,0.000112357,0.019122,0.0191251,0.00896929,0.0388573,0.0388605,0.0591715,6.56526e-11,6.56959e-11,8.55623e-10,0,0,0,0,0,0,0,0,0,0,0
|
||||
32885000,0.983343,-0.0111123,-0.0127126,0.180976,0.0539605,-0.110506,-0.113682,0.0539387,-0.0161473,0.0416293,-1.08923e-05,-5.55145e-05,5.87942e-06,0.000134499,-0.000331997,-0.00108048,0.204181,0.00196475,0.434409,0,0,0,0,0,3.90185e-06,2.08955e-05,2.08844e-05,0.00011227,0.0212663,0.0212706,0.00879018,0.0431384,0.0431426,0.059177,6.57494e-11,6.57914e-11,8.46749e-10,3.22608e-07,3.2244e-07,5.0003e-08,0,0,0,0,0,0,0,0
|
||||
32985000,0.98336,-0.0109197,-0.0126439,0.180899,0.0495511,-0.105393,-0.112672,0.0593798,-0.0162594,0.0290239,-1.12189e-05,-5.54872e-05,6.09731e-06,0.000134555,-0.000332576,-0.00108052,0.204181,0.00196475,0.434409,0,0,0,0,0,3.89877e-06,1.96366e-05,1.96249e-05,0.000112175,0.0201158,0.0201202,0.00849555,0.0391717,0.039175,0.0586226,6.28346e-11,6.28663e-11,8.37882e-10,3.22612e-07,3.22443e-07,5.00129e-08,0,0,0,0,0,0,0,0
|
||||
33085000,0.983363,-0.0108881,-0.0126664,0.180883,0.0470059,-0.11037,-0.110439,0.0642381,-0.0270076,0.0205123,-1.12196e-05,-5.5487e-05,6.07386e-06,0.000134554,-0.000332575,-0.00108053,0.204181,0.00196475,0.434409,0,0,0,0,0,3.8939e-06,1.99414e-05,1.99292e-05,0.000112083,0.0224249,0.0224307,0.00835105,0.0435684,0.0435727,0.0585694,6.29314e-11,6.29621e-11,8.29051e-10,3.22622e-07,3.22453e-07,5.00229e-08,0,0,0,0,0,0,0,0
|
||||
33185000,0.983371,-0.0106625,-0.0125557,0.180861,0.0413632,-0.105745,-0.108844,0.0680085,-0.0261339,0.0144094,-1.15421e-05,-5.54542e-05,5.99659e-06,0.000134714,-0.000335646,-0.00108077,0.204181,0.00196475,0.434409,0,0,0,0,0,3.88657e-06,1.86033e-05,1.85906e-05,0.000111987,0.0211721,0.0211776,0.00810553,0.0395035,0.0395069,0.0579955,6.00222e-11,6.0043e-11,8.20233e-10,3.22418e-07,3.2225e-07,5.00304e-08,0,0,0,0,0,0,0,0
|
||||
33285000,0.983398,-0.0107355,-0.0125706,0.180705,0.039427,-0.108957,-0.108674,0.0719836,-0.0368735,0.00590516,-1.15377e-05,-5.54595e-05,6.23084e-06,0.000134711,-0.000335643,-0.00108079,0.204181,0.00196475,0.434409,0,0,0,0,0,3.88121e-06,1.8892e-05,1.8879e-05,0.00011189,0.0236251,0.0236323,0.00799692,0.0440161,0.0440207,0.0578955,6.01189e-11,6.01389e-11,8.11456e-10,3.22428e-07,3.2226e-07,5.00403e-08,0,0,0,0,0,0,0,0
|
||||
33385000,0.983415,-0.0104668,-0.012596,0.180629,0.0331151,-0.0970429,-0.106326,0.0727554,-0.0295934,-0.0025008,-1.19609e-05,-5.54002e-05,6.31203e-06,0.000134711,-0.000335643,-0.00108108,0.204181,0.00196475,0.434409,0,0,0,0,0,3.87483e-06,1.75128e-05,1.74992e-05,0.000111788,0.0219593,0.021966,0.00779573,0.0398439,0.0398474,0.057312,5.72836e-11,5.72945e-11,8.02699e-10,0,0,5.00418e-08,0,0,0,0,0,0,0,0
|
||||
33485000,0.983419,-0.0104532,-0.012556,0.180609,0.0294365,-0.100535,-0.106252,0.0758405,-0.0394418,-0.0132339,-1.19607e-05,-5.54003e-05,6.32053e-06,0.000134711,-0.000335643,-0.00108108,0.204181,0.00196475,0.434409,0,0,0,0,0,3.88989e-06,1.77853e-05,1.77714e-05,0.000112261,0.0241764,0.0241846,0.00778429,0.0444618,0.0444665,0.0580067,5.73811e-11,5.73916e-11,7.96183e-10,0,0,5.00515e-08,0,0,0,0,0,0,0,0
|
||||
33585000,0.983451,-0.0101607,-0.0124957,0.180455,0.0239731,-0.092944,-0.102508,0.0759841,-0.0335685,-0.019041,-1.22966e-05,-5.53536e-05,6.51779e-06,0.000134711,-0.000335643,-0.00108171,0.204181,0.00196475,0.434409,0,0,0,0,0,3.88246e-06,1.63985e-05,1.63841e-05,0.000112153,0.0223061,0.0223133,0.00762055,0.0401774,0.040181,0.0574055,5.46721e-11,5.46746e-11,7.87486e-10,0,0,5.00437e-08,0,0,0,0,0,0,0,0
|
||||
33685000,0.983462,-0.0101551,-0.01249,0.1804,0.0203589,-0.0964704,-0.104115,0.0782389,-0.0430794,-0.0275205,-1.22956e-05,-5.53548e-05,6.56963e-06,0.000134711,-0.000335643,-0.00108175,0.204181,0.00196475,0.434409,0,0,0,0,0,3.87683e-06,1.66549e-05,1.66403e-05,0.000112043,0.0244989,0.0245076,0.00757677,0.0448801,0.044885,0.0572435,5.47687e-11,5.47709e-11,7.78839e-10,0,0,5.00524e-08,0,0,0,0,0,0,0,0
|
||||
33785000,0.983473,-0.00993957,-0.0124639,0.180355,0.0145854,-0.0884617,-0.0983404,0.07963,-0.0363932,-0.0334916,-1.26086e-05,-5.52688e-05,6.49914e-06,0.000134711,-0.000335643,-0.00108248,0.204181,0.00196475,0.434409,0,0,0,0,0,3.86794e-06,1.52902e-05,1.52752e-05,0.00011193,0.0224735,0.0224811,0.00744921,0.0404865,0.0404902,0.0566501,5.22241e-11,5.22191e-11,7.70222e-10,0,0,5.00318e-08,0,0,0,0,0,0,0,0
|
||||
33885000,0.983491,-0.00997862,-0.0124262,0.180254,0.0113713,-0.0890622,-0.0979443,0.0808727,-0.0453144,-0.040764,-1.26054e-05,-5.52722e-05,6.65943e-06,0.000134711,-0.000335643,-0.00108256,0.204181,0.00196475,0.434409,0,0,0,0,0,3.86245e-06,1.55312e-05,1.55162e-05,0.00011181,0.024614,0.0246231,0.0074346,0.0452533,0.0452582,0.0564713,5.23206e-11,5.23155e-11,7.61654e-10,0,0,5.00388e-08,0,0,0,0,0,0,0,0
|
||||
33985000,0.983482,-0.00971086,-0.0125434,0.180311,0.00779909,-0.0781913,-0.0943001,0.0812242,-0.0360786,-0.0439525,-1.2931e-05,-5.51544e-05,6.54706e-06,0.000134711,-0.000335643,-0.0010835,0.204181,0.00196475,0.434409,0,0,0,0,0,3.85679e-06,1.42131e-05,1.41975e-05,0.000111686,0.0224773,0.0224851,0.00733899,0.0407593,0.0407631,0.055893,4.99651e-11,4.99539e-11,7.53129e-10,0,0,5.0005e-08,0,0,0,0,0,0,0,0
|
||||
34085000,0.983487,-0.00964657,-0.012552,0.180286,0.00448574,-0.0822623,-0.0933874,0.0818831,-0.0441331,-0.0506453,-1.29312e-05,-5.51543e-05,6.53434e-06,0.000134711,-0.000335643,-0.0010836,0.204181,0.00196475,0.434409,0,0,0,0,0,3.8703e-06,1.44399e-05,1.44239e-05,0.000112136,0.0245545,0.0245634,0.00740765,0.0455697,0.0455746,0.0565032,5.00625e-11,5.00513e-11,7.46797e-10,0,0,5.00108e-08,0,0,0,0,0,0,0,0
|
||||
34185000,0.983488,-0.00946869,-0.0125741,0.180285,-0.00017535,-0.0722999,-0.0910474,0.0827375,-0.035994,-0.0524166,-1.31966e-05,-5.50509e-05,6.58212e-06,0.000134711,-0.000335643,-0.00108437,0.204181,0.00196475,0.434409,0,0,0,0,0,3.86548e-06,1.31854e-05,1.31691e-05,0.000112002,0.0223368,0.0223444,0.00733806,0.0409881,0.0409918,0.0559298,4.79075e-11,4.78912e-11,7.38356e-10,0,0,5.00037e-08,0,0,0,0,0,0,0,0
|
||||
34285000,0.983493,-0.00935997,-0.0126394,0.18026,-6.60364e-05,-0.0753508,-0.0900134,0.0827558,-0.0434176,-0.0596775,-1.31951e-05,-5.50523e-05,6.65269e-06,0.000134711,-0.000335643,-0.00108447,0.204181,0.00196475,0.434409,0,0,0,0,0,3.86067e-06,1.33989e-05,1.33821e-05,0.000111865,0.0243403,0.024349,0.00737519,0.0458217,0.0458267,0.0557506,4.8004e-11,4.79879e-11,7.2997e-10,0,0,5.0004e-08,0,0,0,0,0,0,0,0
|
||||
34385000,0.983516,-0.00914418,-0.012633,0.180147,-0.00389648,-0.0646328,-0.0850015,0.0818782,-0.0352135,-0.0628355,-1.3438e-05,-5.49671e-05,6.64523e-06,0.000134711,-0.000335643,-0.00108594,0.204181,0.00196475,0.434409,0,0,0,0,0,3.84965e-06,1.22201e-05,1.22031e-05,0.000111729,0.0220675,0.0220749,0.00732989,0.041168,0.0411718,0.0552037,4.60514e-11,4.6031e-11,7.21636e-10,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
34485000,0.983521,-0.0092274,-0.0125676,0.180121,-0.00671781,-0.0678926,-0.0835185,0.0813478,-0.0419081,-0.0663365,-1.34364e-05,-5.49688e-05,6.71893e-06,0.000134711,-0.000335643,-0.0010863,0.204181,0.00196475,0.434409,0,0,0,0,0,3.8446e-06,1.2421e-05,1.24043e-05,0.000111583,0.0239922,0.0240005,0.00738949,0.046006,0.0460109,0.0550392,4.61478e-11,4.61278e-11,7.13361e-10,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
34585000,0.983525,-0.00903441,-0.0123775,0.18012,-0.00860108,-0.0573826,0.662392,0.0807242,-0.0350091,-0.0412134,-1.36259e-05,-5.48861e-05,6.67196e-06,0.000134711,-0.000335643,-0.00108766,0.204181,0.00196475,0.434409,0,0,0,0,0,3.8372e-06,1.13246e-05,1.13082e-05,0.000111436,0.0204659,0.0204723,0.0073626,0.041264,0.0412677,0.0545225,4.43919e-11,4.43686e-11,7.05142e-10,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
34685000,0.983531,-0.00901961,-0.0120954,0.18011,-0.011335,-0.0545756,1.65306,0.0797367,-0.0406046,0.0716389,-1.3627e-05,-5.48851e-05,6.62541e-06,0.000134711,-0.000335643,-0.00108739,0.204181,0.00196475,0.434409,0,0,0,0,0,3.82988e-06,1.15139e-05,1.14983e-05,0.000111285,0.0205706,0.0205772,0.00743913,0.0458986,0.0459033,0.0543787,4.44883e-11,4.44655e-11,6.96985e-10,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
34785000,0.983543,-0.00886936,-0.0118592,0.180065,-0.0130252,-0.0442334,2.61953,0.0795803,-0.0339029,0.233675,-1.37741e-05,-5.48068e-05,6.66632e-06,0.000134711,-0.000335643,-0.00106142,0.204181,0.00196475,0.434409,0,0,0,0,0,3.84161e-06,1.06231e-05,1.0608e-05,0.0001117,0.0173849,0.0173899,0.0074789,0.0411363,0.0411398,0.0546305,4.30817e-11,4.30565e-11,6.90925e-10,0,0,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
34885000,0.983548,-0.00885333,-0.0115784,0.180057,-0.0156975,-0.0414113,3.6051,0.0781947,-0.0381599,0.523529,-1.37758e-05,-5.48053e-05,6.62157e-06,0.000134711,-0.000335643,-0.00105918,0.204181,0.00196475,0.434409,0,0,0,0,0,3.83398e-06,1.08041e-05,1.07897e-05,0.000111539,0.0174924,0.0174975,0.00757315,0.045452,0.0454565,0.0545093,4.31781e-11,4.31535e-11,6.82874e-10,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
385000,0.982906,-0.00775222,-0.0134292,0.183453,0.000445835,0.000257906,-0.00515775,3.74516e-06,5.43776e-06,-7.479e-05,0,0,0,0,0,0,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,0.000168954,0.00247418,0.00247368,0.00483312,25.0004,25.0004,0.562573,0.259374,0.259374,4.00051,1e-06,1e-06,1e-06,0,0,4e-06,0,0,0,0,0,0,0,0
|
||||
485000,0.983207,-0.00779267,-0.0137988,0.181806,0.00149516,0.000487556,-0.0226199,0.000128857,3.88731e-05,0.012004,3.89716e-08,1.3818e-10,1.63937e-06,0,0,5.50648e-08,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,9.05599e-05,0.00251394,0.0025137,0.00257812,25.0144,25.0144,0.56266,0.609418,0.609418,0.802449,9.99999e-07,1e-06,9.98121e-07,0,0,4.00001e-06,0,0,0,0,0,0,0,0
|
||||
585000,0.983235,-0.00781283,-0.0140176,0.181633,0.000142817,0.000425494,-0.0407873,4.57242e-05,1.65576e-05,0.00559437,4.92314e-08,-1.10894e-10,2.06611e-06,0,0,1.69579e-07,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,6.31735e-05,0.00260317,0.00260303,0.00179033,7.81663,7.81663,0.561469,0.228172,0.228172,0.451638,9.99994e-07,9.99999e-07,9.91443e-07,0,0,4e-06,0,0,0,0,0,0,0,0
|
||||
685000,0.983166,-0.00784229,-0.0143846,0.181978,0.00273131,0.00149319,-0.0490414,0.00022836,0.000116917,0.0168581,1.00722e-08,-3.07713e-10,4.61971e-07,0,0,-3.88273e-07,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,4.99495e-05,0.00274313,0.00274301,0.00140913,7.85794,7.85794,0.557235,0.486139,0.486139,0.322026,9.99986e-07,9.99999e-07,9.77538e-07,0,0,3.99989e-06,0,0,0,0,0,0,0,0
|
||||
785000,0.983129,-0.00784217,-0.0146116,0.18216,0.00372337,0.00338268,-0.0598125,0.000120916,8.73527e-05,0.0131548,-2.03628e-08,-5.71334e-09,-8.2648e-07,0,0,-6.61608e-07,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,4.27471e-05,0.00292596,0.00292585,0.00120115,2.60141,2.60142,0.548782,0.195736,0.195736,0.259034,9.99886e-07,9.99914e-07,9.55188e-07,0,0,3.99951e-06,0,0,0,0,0,0,0,0
|
||||
885000,0.983035,-0.0078867,-0.0149611,0.182637,0.00537375,0.00623852,-0.0766231,0.000540952,0.000537906,-0.000216641,-1.6477e-07,-9.61095e-09,-6.50679e-06,0,0,9.87685e-08,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.87062e-05,0.00316568,0.00316556,0.00108283,2.66545,2.66547,0.534816,0.329581,0.329582,0.225286,9.99866e-07,9.99914e-07,9.23082e-07,0,0,3.99856e-06,0,0,0,0,0,0,0,0
|
||||
985000,0.982858,-0.00782901,-0.0152572,0.183566,0.00823652,0.00902617,-0.0901081,0.00123165,0.00123919,-0.00832501,-4.8827e-07,-1.48091e-08,-1.91202e-05,0,0,-1.56205e-07,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.82301e-05,0.0034554,0.00345523,0.00106637,2.75673,2.75676,0.52163,0.517615,0.517616,0.218362,9.99846e-07,9.99914e-07,8.92597e-07,0,0,3.99721e-06,0,0,0,0,0,0,0,0
|
||||
1085000,0.982942,-0.00793611,-0.0154438,0.183097,0.0140873,0.00748821,-0.109262,0.0013254,0.00114805,-0.0271139,-2.76351e-07,-7.16624e-08,-1.192e-05,0,0,2.02263e-06,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.69741e-05,0.00376377,0.00376358,0.00102686,1.29637,1.2964,0.497698,0.244345,0.244346,0.207776,9.98973e-07,9.99074e-07,8.44402e-07,0,0,3.99418e-06,0,0,0,0,0,0,0,0
|
||||
1185000,0.982986,-0.00789683,-0.0157172,0.182837,0.0200033,0.00774763,-0.10944,0.00300045,0.00190009,-0.0224507,-1.67147e-07,-5.74795e-08,-7.66274e-06,0,0,-3.17894e-06,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.6438e-05,0.00415182,0.00415156,0.00100717,1.42437,1.42443,0.469195,0.352138,0.352141,0.202802,9.98935e-07,9.99074e-07,7.89548e-07,0,0,3.98936e-06,0,0,0,0,0,0,0,0
|
||||
1285000,0.983228,-0.0078191,-0.0159541,0.181511,0.0248719,0.00741285,-0.118106,0.00314531,0.00131956,-0.0274477,4.83598e-07,-3.64062e-07,1.44699e-05,0,0,-5.99276e-06,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.61689e-05,0.00448529,0.00448496,0.000997099,0.899466,0.899538,0.437028,0.197243,0.197244,0.200584,9.94637e-07,9.94818e-07,7.29674e-07,0,0,3.98218e-06,0,0,0,0,0,0,0,0
|
||||
1385000,0.983298,-0.00779835,-0.0161705,0.181118,0.0336815,0.00815884,-0.117744,0.00609985,0.00212856,-0.0250338,6.08962e-07,-3.33022e-07,1.90582e-05,0,0,-1.3188e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.60416e-05,0.00496644,0.00496602,0.000990509,1.07437,1.07449,0.402818,0.274389,0.274394,0.199431,9.9459e-07,9.94818e-07,6.67293e-07,0,0,3.97225e-06,0,0,0,0,0,0,0,0
|
||||
1485000,0.983221,-0.00778091,-0.0161964,0.181532,0.0329266,0.0073408,-0.131168,0.0054041,0.00161758,-0.0377952,3.2572e-07,-1.54916e-06,1.05507e-05,0,0,-1.32214e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.58842e-05,0.00520925,0.0052088,0.000984313,0.83815,0.838271,0.368574,0.171805,0.171809,0.198527,9.80091e-07,9.80363e-07,6.05295e-07,0,0,3.95945e-06,0,0,0,0,0,0,0,0
|
||||
1585000,0.983218,-0.00787221,-0.0165617,0.181513,0.0407795,0.00829228,-0.142897,0.00908255,0.00236705,-0.0487388,3.18933e-07,-1.53709e-06,1.02505e-05,0,0,-1.50662e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.74389e-05,0.00576907,0.0057685,0.00102231,1.06615,1.06633,0.345439,0.239486,0.239496,0.207552,9.80056e-07,9.80363e-07,5.60027e-07,0,0,3.94785e-06,0,0,0,0,0,0,0,0
|
||||
1685000,0.983244,-0.00798178,-0.0164415,0.181374,0.0397497,0.00800314,-0.149395,0.00739773,0.0017971,-0.0545586,4.61734e-08,-4.39663e-06,1.25191e-05,0,0,-2.08158e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.70139e-05,0.00572878,0.00572829,0.00100996,0.909048,0.909225,0.31373,0.160449,0.160456,0.205397,9.44133e-07,9.44473e-07,5.02322e-07,0,0,3.92954e-06,0,0,0,0,0,0,0,0
|
||||
1785000,0.983211,-0.00812528,-0.0167314,0.181525,0.0500155,0.00828673,-0.150961,0.0119333,0.00261026,-0.0574122,-6.28698e-08,-4.33172e-06,8.13448e-06,0,0,-2.95761e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.6751e-05,0.00633744,0.0063368,0.00099398,1.18509,1.18535,0.284488,0.229233,0.22925,0.202407,9.44093e-07,9.44472e-07,4.48612e-07,0,0,3.90791e-06,0,0,0,0,0,0,0,0
|
||||
1885000,0.983329,-0.008071,-0.0162732,0.180926,0.0439593,0.00901281,-0.152979,0.00905303,0.00190364,-0.0623795,-6.43546e-07,-9.51366e-06,1.69775e-05,0,0,-3.75596e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.5861e-05,0.00582732,0.00582687,0.000975149,0.997288,0.997511,0.258348,0.157537,0.157547,0.198874,8.7715e-07,8.7754e-07,3.99727e-07,0,0,3.88319e-06,0,0,0,0,0,0,0,0
|
||||
1985000,0.983356,-0.00817263,-0.0166403,0.18074,0.0524564,0.0100551,-0.151652,0.0138998,0.00281358,-0.06169,-5.7498e-07,-9.39287e-06,1.86412e-05,0,0,-5.10333e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.54405e-05,0.00644038,0.00643976,0.000953698,1.3017,1.30203,0.235189,0.231153,0.231176,0.194764,8.77119e-07,8.77537e-07,3.55597e-07,0,0,3.85509e-06,0,0,0,0,0,0,0,0
|
||||
2085000,0.983278,-0.00824902,-0.0159797,0.181223,0.0423133,0.00766312,-0.150052,0.00962687,0.00189525,-0.0592162,-1.97348e-06,-1.64932e-05,1.03484e-05,0,0,-6.74509e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.41819e-05,0.00545387,0.00545357,0.00093044,1.032,1.03222,0.215119,0.157316,0.157327,0.190412,7.81977e-07,7.8238e-07,3.16277e-07,0,0,3.82386e-06,0,0,0,0,0,0,0,0
|
||||
2185000,0.983296,-0.00821787,-0.0163173,0.181093,0.0499701,0.00842154,-0.151875,0.014255,0.00276072,-0.0637415,-1.93577e-06,-1.63949e-05,1.09399e-05,0,0,-7.80002e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.36455e-05,0.00602725,0.00602677,0.000905952,1.33556,1.33587,0.197791,0.234208,0.234233,0.185808,7.81957e-07,7.82377e-07,2.81393e-07,0,0,3.78909e-06,0,0,0,0,0,0,0,0
|
||||
2285000,0.983449,-0.00829695,-0.0155482,0.180329,0.0363964,0.00624904,-0.149364,0.00912446,0.00173221,-0.063107,-3.09466e-06,-2.41594e-05,2.03216e-05,0,0,-9.4551e-05,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.34007e-05,0.00478278,0.00478264,0.000917771,0.993008,0.993187,0.188685,0.15558,0.155591,0.189826,6.74558e-07,6.74939e-07,2.57848e-07,0,0,3.76059e-06,0,0,0,0,0,0,0,0
|
||||
2385000,0.983469,-0.00835843,-0.0157261,0.1802,0.0434517,0.00562692,-0.149239,0.0131525,0.00231492,-0.0614991,-3.04487e-06,-2.40115e-05,2.09e-05,0,0,-0.000112629,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.26697e-05,0.00529045,0.00529021,0.000890197,1.27336,1.27361,0.175646,0.231693,0.231716,0.184795,6.74544e-07,6.74936e-07,2.2987e-07,0,0,3.71943e-06,0,0,0,0,0,0,0,0
|
||||
2485000,0.983603,-0.00828275,-0.0150001,0.17953,0.0292549,0.00376069,-0.150956,0.00801574,0.00132731,-0.0648773,-4.27572e-06,-3.10751e-05,2.9068e-05,0,0,-0.00012596,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.10764e-05,0.00405366,0.00405363,0.000862728,0.907778,0.907909,0.164702,0.151099,0.151107,0.179987,5.71591e-07,5.71939e-07,2.05298e-07,0,0,3.67475e-06,0,0,0,0,0,0,0,0
|
||||
2585000,0.983643,-0.00840973,-0.0151349,0.179296,0.0323445,0.00229609,-0.153885,0.0110928,0.00167313,-0.0690113,-4.24891e-06,-3.09813e-05,2.90747e-05,0,0,-0.000139431,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,3.02737e-05,0.00449091,0.00449082,0.000835868,1.15351,1.15368,0.155525,0.223054,0.223072,0.175338,5.71581e-07,5.71935e-07,1.83745e-07,0,0,3.62597e-06,0,0,0,0,0,0,0,0
|
||||
2685000,0.98371,-0.00847264,-0.0145357,0.178976,0.0217589,0.00156794,-0.153275,0.00655818,0.000880251,-0.0681833,-5.45806e-06,-3.64499e-05,3.15736e-05,0,0,-0.000161172,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.87534e-05,0.0034129,0.00341296,0.000809218,0.808184,0.808273,0.147822,0.144645,0.144652,0.170893,4.81468e-07,4.81778e-07,1.64742e-07,0,0,3.57283e-06,0,0,0,0,0,0,0,0
|
||||
2785000,0.98369,-0.00842791,-0.0146958,0.17907,0.0271297,0.00123464,-0.150514,0.00913908,0.00102508,-0.0647032,-5.47649e-06,-3.62672e-05,2.79766e-05,0,0,-0.000187637,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.79812e-05,0.0037871,0.0037871,0.000783899,1.01999,1.02011,0.141515,0.210823,0.210837,0.166798,4.81461e-07,4.81775e-07,1.48141e-07,0,0,3.51578e-06,0,0,0,0,0,0,0,0
|
||||
2885000,0.983783,-0.00844618,-0.0142704,0.178596,0.0195799,-0.00138268,-0.152024,0.00545395,0.000471638,-0.0659929,-6.61286e-06,-4.04882e-05,3.07906e-05,0,0,-0.000207842,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.75284e-05,0.00290067,0.00290076,0.000786818,0.714773,0.714835,0.139977,0.137385,0.13739,0.169975,4.0533e-07,4.05602e-07,1.36974e-07,0,0,3.47018e-06,0,0,0,0,0,0,0,0
|
||||
2985000,0.983855,-0.00848407,-0.0143674,0.178188,0.022551,-0.00288663,-0.155036,0.0076676,0.000275071,-0.0702124,-6.52766e-06,-4.04353e-05,3.35938e-05,0,0,-0.000224418,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.6763e-05,0.00322221,0.00322227,0.000761629,0.897624,0.897706,0.135474,0.197572,0.197582,0.16618,4.05324e-07,4.056e-07,1.23686e-07,0,0,3.40536e-06,0,0,0,0,0,0,0,0
|
||||
3085000,0.983807,-0.00852936,-0.0145495,0.178437,0.0282543,-0.00545783,-0.158896,0.0102479,-0.000189074,-0.0749499,-6.53549e-06,-4.03283e-05,3.13233e-05,0,0,-0.000241949,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.61133e-05,0.00356402,0.00356404,0.00073738,1.11474,1.11485,0.13174,0.282393,0.282411,0.162668,4.0532e-07,4.05597e-07,1.11949e-07,0,0,3.3358e-06,0,0,0,0,0,0,0,0
|
||||
3185000,0.983688,-0.00848064,-0.0142268,0.179119,0.0219763,-0.0076047,-0.160674,0.00671651,-0.000757081,-0.0803086,-8.02997e-06,-4.35435e-05,2.31909e-05,0,0,-0.000259182,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.48988e-05,0.00278003,0.00278011,0.000714218,0.794681,0.79474,0.128671,0.18485,0.184857,0.159519,3.41212e-07,3.41452e-07,1.01559e-07,0,0,3.26218e-06,0,0,0,0,0,0,0,0
|
||||
3285000,0.983703,-0.00851014,-0.0142393,0.179036,0.0249532,-0.00855827,-0.164702,0.00909611,-0.00161782,-0.0887621,-8.00249e-06,-4.34856e-05,2.31214e-05,0,0,-0.000272957,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.42596e-05,0.00307506,0.00307511,0.000692208,0.983631,0.983715,0.126108,0.261342,0.261356,0.156631,3.41208e-07,3.4145e-07,9.23741e-08,0,0,3.18391e-06,0,0,0,0,0,0,0,0
|
||||
3385000,0.983642,-0.00821894,-0.0139273,0.179407,0.0181044,-0.00707569,-0.163835,0.00592436,-0.00141375,-0.0871287,-9.65931e-06,-4.59988e-05,1.85514e-05,0,0,-0.000306305,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.31924e-05,0.00242843,0.00242851,0.000671221,0.711268,0.711319,0.12397,0.173306,0.173312,0.154065,2.86717e-07,2.86926e-07,8.42021e-08,0,0,3.10184e-06,0,0,0,0,0,0,0,0
|
||||
3485000,0.983566,-0.00821415,-0.0139639,0.179822,0.0229659,-0.00561832,-0.162853,0.00807938,-0.00205976,-0.0876644,-9.69255e-06,-4.58423e-05,1.37131e-05,0,0,-0.000336241,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.26105e-05,0.00268393,0.00268399,0.000651288,0.878358,0.878443,0.122128,0.242741,0.242753,0.151721,2.86714e-07,2.86924e-07,7.69474e-08,0,0,3.01547e-06,0,0,0,0,0,0,0,0
|
||||
3585000,0.983571,-0.00802001,-0.0135971,0.179831,0.0184667,-0.0050487,-0.169073,0.00551618,-0.00140348,-0.0958646,-1.12525e-05,-4.80171e-05,1.26142e-05,0,0,-0.000352528,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.23006e-05,0.00213816,0.00213826,0.000651169,0.643571,0.643624,0.123406,0.163107,0.163112,0.155467,2.39918e-07,2.40097e-07,7.19937e-08,0,0,2.94807e-06,0,0,0,0,0,0,0,0
|
||||
3685000,0.983675,-0.00805637,-0.0136608,0.179254,0.0202823,-0.00578337,-0.166136,0.00759576,-0.00196567,-0.0948424,-1.11054e-05,-4.79779e-05,1.71326e-05,0,0,-0.000388319,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.17436e-05,0.00235938,0.00235947,0.000632041,0.792728,0.792799,0.121856,0.226633,0.226643,0.153422,2.39916e-07,2.40095e-07,6.60402e-08,0,0,2.85524e-06,0,0,0,0,0,0,0,0
|
||||
3785000,0.983643,-0.00788793,-0.013498,0.179449,0.0143059,-0.00145485,-0.168315,0.00501934,-0.00114754,-0.10056,-1.25255e-05,-4.99104e-05,1.48531e-05,0,0,-0.000410305,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.09118e-05,0.00188822,0.00188834,0.000613846,0.586864,0.586916,0.12042,0.154123,0.154128,0.151619,1.99511e-07,1.99664e-07,6.06919e-08,0,0,2.7598e-06,0,0,0,0,0,0,0,0
|
||||
3885000,0.983686,-0.00787386,-0.0135661,0.179208,0.0149645,-0.00143833,-0.166856,0.00661423,-0.00123586,-0.1024,-1.24461e-05,-4.98726e-05,1.67548e-05,0,0,-0.000440564,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,2.04142e-05,0.00207907,0.00207919,0.000596573,0.720757,0.720826,0.119002,0.212622,0.212632,0.149954,1.99509e-07,1.99663e-07,5.59052e-08,0,0,2.66146e-06,0,0,0,0,0,0,0,0
|
||||
3985000,0.983582,-0.00782581,-0.0133634,0.179795,0.0130527,-0.000886668,-0.166908,0.00436819,-0.000741624,-0.1024,-1.35171e-05,-5.14499e-05,1.19717e-05,0,0,-0.000476214,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.96831e-05,0.0016659,0.00166605,0.000579989,0.538211,0.538256,0.117541,0.146154,0.146159,0.148396,1.64686e-07,1.64815e-07,5.1572e-08,0,0,2.56072e-06,0,0,0,0,0,0,0,0
|
||||
4085000,0.983524,-0.00779301,-0.0133144,0.18012,0.0153952,-0.0018817,-0.156313,0.00596055,-0.000878672,-0.092104,-1.34963e-05,-5.13149e-05,9.32824e-06,0,0,-0.000532875,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.92251e-05,0.0018296,0.00182975,0.000564366,0.658725,0.658784,0.116075,0.20032,0.200329,0.147005,1.64685e-07,1.64814e-07,4.76888e-08,0,0,2.4589e-06,0,0,0,0,0,0,0,0
|
||||
4185000,0.983562,-0.00785847,-0.0130832,0.179923,0.0116708,-0.00229855,-0.158783,0.00399179,-0.000607036,-0.0991935,-1.43023e-05,-5.28072e-05,1.02072e-05,0,0,-0.000551464,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.90331e-05,0.00146433,0.00146451,0.000563687,0.494379,0.494414,0.117305,0.138992,0.138996,0.151261,1.34884e-07,1.34992e-07,4.50059e-08,0,0,2.38191e-06,0,0,0,0,0,0,0,0
|
||||
4285000,0.983622,-0.0079323,-0.0131452,0.179588,0.0149484,-0.00200565,-0.161877,0.00540755,-0.000838374,-0.105808,-1.424e-05,-5.28123e-05,1.24589e-05,0,0,-0.000571861,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.85919e-05,0.00160372,0.00160392,0.000548789,0.602968,0.603015,0.115631,0.189299,0.189306,0.149954,1.34882e-07,1.34991e-07,4.17452e-08,0,0,2.27865e-06,0,0,0,0,0,0,0,0
|
||||
4385000,0.983699,-0.00782217,-0.0130172,0.179182,0.0129091,-0.00344811,-0.15375,0.00382947,-0.000663135,-0.0968797,-1.49164e-05,-5.41e-05,1.4685e-05,0,0,-0.000625173,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.79691e-05,0.00128059,0.00128078,0.000534511,0.454423,0.45445,0.113817,0.132457,0.13246,0.14867,1.09661e-07,1.09751e-07,3.87687e-08,0,0,2.17514e-06,0,0,0,0,0,0,0,0
|
||||
4485000,0.983699,-0.00788973,-0.0129821,0.179178,0.0147312,-0.0015472,-0.15089,0.00531367,-0.000872498,-0.0961357,-1.4889e-05,-5.40627e-05,1.45279e-05,0,0,-0.000659592,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.75591e-05,0.00139844,0.00139865,0.000521001,0.551713,0.551752,0.111927,0.179252,0.179258,0.147471,1.0966e-07,1.0975e-07,3.60807e-08,0,0,2.07269e-06,0,0,0,0,0,0,0,0
|
||||
4585000,0.983643,-0.0078497,-0.0128659,0.1795,0.0120531,-0.00300688,-0.150867,0.00368754,-0.000620436,-0.0995373,-1.56101e-05,-5.52142e-05,1.22245e-05,0,0,-0.000685024,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.70227e-05,0.00111385,0.00111404,0.000508017,0.416979,0.417,0.109892,0.126413,0.126415,0.14626,8.85881e-08,8.86612e-08,3.36172e-08,0,0,1.97112e-06,0,0,0,0,0,0,0,0
|
||||
4685000,0.983711,-0.0078257,-0.0128314,0.179128,0.0124528,-0.00328018,-0.142686,0.00504532,-0.000870735,-0.0940305,-1.55456e-05,-5.52057e-05,1.39888e-05,0,0,-0.000728593,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.66305e-05,0.00121282,0.00121303,0.000495743,0.503725,0.503751,0.10778,0.169948,0.169953,0.145101,8.85874e-08,8.86607e-08,3.13835e-08,0,0,1.87163e-06,0,0,0,0,0,0,0,0
|
||||
4785000,0.98367,-0.00765319,-0.0127624,0.179364,0.0041315,-0.00243863,-0.141588,0.00323701,-0.000626159,-0.0959561,-1.61673e-05,-5.61615e-05,1.24285e-05,0,0,-0.000755014,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.61511e-05,0.000964025,0.00096421,0.000483915,0.381715,0.381728,0.105532,0.120761,0.120763,0.143905,7.12094e-08,7.12684e-08,2.93288e-08,0,0,1.77398e-06,0,0,0,0,0,0,0,0
|
||||
4885000,0.983704,-0.00761045,-0.0127964,0.179175,0.00540047,-0.00498613,-0.138381,0.00374832,-0.00101174,-0.0969365,-1.61295e-05,-5.61654e-05,1.35874e-05,0,0,-0.000782404,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.61524e-05,0.00104668,0.00104687,0.000483172,0.45891,0.458923,0.105757,0.161249,0.161252,0.14802,7.1209e-08,7.12681e-08,2.79087e-08,0,0,1.70226e-06,0,0,0,0,0,0,0,0
|
||||
4985000,0.983694,-0.00753245,-0.0126973,0.179243,0.00451084,-0.00351981,-0.131602,0.00239291,-0.000799273,-0.0932227,-1.66424e-05,-5.67613e-05,1.26186e-05,0,0,-0.000818227,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.56908e-05,0.000830994,0.000831164,0.000471894,0.348614,0.348623,0.103268,0.115446,0.115448,0.14671,5.70454e-08,5.70925e-08,2.61444e-08,0,0,1.60914e-06,0,0,0,0,0,0,0,0
|
||||
5085000,0.983647,-0.00741243,-0.0126384,0.179509,0.00550148,-0.00363451,-0.127285,0.00294962,-0.00120439,-0.0895949,-1.66556e-05,-5.67204e-05,1.1033e-05,0,0,-0.000852154,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.53624e-05,0.000899735,0.000899913,0.000461169,0.417163,0.417174,0.100737,0.153075,0.153077,0.145416,5.70449e-08,5.7092e-08,2.45337e-08,0,0,1.51945e-06,0,0,0,0,0,0,0,0
|
||||
5185000,0.983641,-0.00727397,-0.012687,0.179544,0.00366792,-0.00152415,-0.124138,0.00342082,-0.00147238,-0.0875631,-1.66448e-05,-5.67036e-05,1.07873e-05,0,0,-0.000881857,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.50496e-05,0.000971328,0.000971511,0.000450877,0.495393,0.495409,0.0981218,0.202288,0.202292,0.144061,5.70444e-08,5.70916e-08,2.30502e-08,0,0,1.43285e-06,0,0,0,0,0,0,0,0
|
||||
5285000,0.983651,-0.00713119,-0.0125976,0.179506,0.00249029,0.000246316,-0.113363,0.00211946,-0.000825742,-0.0813375,-1.70401e-05,-5.71255e-05,1.09746e-05,0,0,-0.000918189,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.46551e-05,0.000771224,0.000771377,0.000440953,0.378358,0.378369,0.0954424,0.145393,0.145395,0.142645,4.56124e-08,4.56497e-08,2.1675e-08,0,0,1.34957e-06,0,0,0,0,0,0,0,0
|
||||
5385000,0.983636,-0.00704013,-0.0126093,0.179586,0.000294713,0.00232867,-0.108653,0.00230825,-0.000750371,-0.0762985,-1.70448e-05,-5.70992e-05,1.00672e-05,0,0,-0.000949942,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.4354e-05,0.000830518,0.000830677,0.000431516,0.447235,0.447251,0.0927603,0.190825,0.190828,0.141237,4.5612e-08,4.56494e-08,2.04136e-08,0,0,1.27022e-06,0,0,0,0,0,0,0,0
|
||||
5485000,0.98362,-0.00703458,-0.012634,0.179672,-0.000395593,0.00549096,-0.10557,0.00121387,-5.95082e-05,-0.0771074,-1.72646e-05,-5.73536e-05,9.28172e-06,0,0,-0.000969246,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.42716e-05,0.000659973,0.000660106,0.000430797,0.3429,0.342913,0.0923274,0.138168,0.13817,0.1449,3.64558e-08,3.64852e-08,1.95252e-08,0,0,1.21315e-06,0,0,0,0,0,0,0,0
|
||||
5585000,0.983619,-0.00705725,-0.0126702,0.179677,-0.000705563,0.00840564,-0.0974006,0.00124491,0.000631907,-0.0694878,-1.72672e-05,-5.73365e-05,8.67208e-06,0,0,-0.00100262,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.39784e-05,0.000709017,0.000709159,0.000421764,0.403323,0.403342,0.0895481,0.180104,0.180107,0.143333,3.64555e-08,3.64849e-08,1.84245e-08,0,0,1.14023e-06,0,0,0,0,0,0,0,0
|
||||
5685000,0.983592,-0.00704666,-0.0125437,0.179834,-0.00115333,0.0100725,-0.0972899,0.00056405,0.00107907,-0.0690068,-1.72447e-05,-5.74888e-05,7.04767e-06,0,0,-0.00102139,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.36298e-05,0.000564428,0.000564546,0.000413047,0.310633,0.310648,0.086761,0.131397,0.131398,0.14171,2.91608e-08,2.91839e-08,1.73994e-08,0,0,1.0709e-06,0,0,0,0,0,0,0,0
|
||||
5785000,0.98364,-0.00692039,-0.0125231,0.179577,-0.000937028,0.0119372,-0.0911111,0.00050089,0.00215692,-0.0629593,-1.72235e-05,-5.75018e-05,7.87892e-06,0,0,-0.00104929,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.33559e-05,0.000604994,0.000605116,0.000404722,0.363781,0.363799,0.0840192,0.17011,0.170113,0.140101,2.91605e-08,2.91837e-08,1.64533e-08,0,0,1.0055e-06,0,0,0,0,0,0,0,0
|
||||
5885000,0.983625,-0.00691013,-0.0125665,0.179656,0.00109704,0.0112451,-0.0875393,0.000322525,0.00220105,-0.0644421,-1.69679e-05,-5.76525e-05,7.38499e-06,0,0,-0.00106242,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.30595e-05,0.000482859,0.000482958,0.000396661,0.281197,0.28121,0.0812936,0.125064,0.125066,0.138444,2.33679e-08,2.33862e-08,1.55701e-08,0,0,9.43612e-07,0,0,0,0,0,0,0,0
|
||||
5985000,0.983579,-0.00686289,-0.0126868,0.179903,0.00181974,0.0123204,-0.0805734,0.00050415,0.00335485,-0.0585752,-1.6999e-05,-5.76191e-05,5.73915e-06,0,0,-0.00108725,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.28141e-05,0.000516443,0.000516546,0.000388956,0.327825,0.327841,0.0786303,0.160807,0.16081,0.136806,2.33677e-08,2.3386e-08,1.47527e-08,0,0,8.8547e-07,0,0,0,0,0,0,0,0
|
||||
6085000,0.983538,-0.00692464,-0.0126093,0.180129,0.000832564,0.0109612,-0.0770677,0.000385107,0.00283614,-0.056763,-1.66831e-05,-5.77748e-05,3.39589e-06,0,0,-0.00110366,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.25148e-05,0.000413537,0.000413621,0.000381523,0.254705,0.254716,0.0760007,0.119145,0.119146,0.13513,1.87759e-08,1.87904e-08,1.39879e-08,0,0,8.30646e-07,0,0,0,0,0,0,0,0
|
||||
6185000,0.98351,-0.00695142,-0.0125686,0.180281,0.000128474,0.0125409,-0.07557,0.000485882,0.00403041,-0.0563873,-1.66996e-05,-5.77584e-05,2.57348e-06,0,0,-0.00111721,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.25079e-05,0.000441392,0.000441483,0.000380912,0.295784,0.295797,0.0752293,0.152173,0.152175,0.138085,1.87758e-08,1.87903e-08,1.34502e-08,0,0,7.91664e-07,0,0,0,0,0,0,0,0
|
||||
6285000,0.983486,-0.00698955,-0.0125771,0.180411,-0.0016406,0.0116774,-0.0764566,0.000224294,0.0032702,-0.0601462,-1.6311e-05,-5.7945e-05,2.01436e-06,0,0,-0.00112346,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.22601e-05,0.000354779,0.000354851,0.000373741,0.231022,0.231031,0.0726393,0.113631,0.113633,0.136287,1.51364e-08,1.51478e-08,1.2773e-08,0,0,7.42516e-07,0,0,0,0,0,0,0,0
|
||||
6385000,0.983509,-0.00694116,-0.0125178,0.180295,-0.00049841,0.0131742,-0.0755624,7.5816e-05,0.00450375,-0.0614801,-1.63015e-05,-5.79543e-05,2.48834e-06,0,0,-0.00113336,0.203406,-9.31323e-10,0.43452,0,0,0,0,0,1.20449e-05,0.000377939,0.000378015,0.000366867,0.267187,0.267197,0.070135,0.144185,0.144187,0.134521,1.51362e-08,1.51477e-08,1.21428e-08,0,0,6.96586e-07,0,0,0,0,0,0,0,0
|
||||
6485000,0.983183,-0.00694596,-0.0125173,0.182061,-0.00279061,0.00895076,-0.0715186,-6.99224e-05,0.00344684,-0.058252,-1.58941e-05,-5.81061e-05,2.1462e-06,0,0,-0.00114967,0.204181,4.65661e-10,0.433701,0,0,0,0,0,8.36299e-05,0.000301614,0.000301436,0.00246491,0.203869,0.203875,0.0676886,0.108482,0.108484,0.132734,1.22484e-08,1.22576e-08,1.16947e-08,0,0,6.53487e-07,0,0,0,0,0,0,0,0
|
||||
6585000,0.9831,-0.00690329,-0.0124773,0.182514,-0.00344532,0.010076,-0.0725613,-0.000358351,0.00435148,-0.060045,-1.58947e-05,-5.81062e-05,2.13884e-06,0,0,-0.00115791,0.204181,4.65661e-10,0.433701,0,0,0,0,0,5.75402e-05,0.000301976,0.000301881,0.0016966,0.2062,0.206207,0.0653048,0.135566,0.135567,0.130934,1.22485e-08,1.22577e-08,1.16945e-08,0,0,6.13094e-07,0,0,0,0,0,0,0,0
|
||||
6685000,0.983048,-0.00681051,-0.0124523,0.1828,-0.00648025,0.0103135,-0.0737938,-0.000604185,0.00340564,-0.0598126,-1.55141e-05,-5.81884e-05,2.09567e-06,0,0,-0.00116916,0.204181,4.65661e-10,0.433701,0,0,0,0,0,4.38654e-05,0.000302529,0.000302475,0.00129389,0.146946,0.146951,0.0630121,0.101684,0.101685,0.129174,1.0035e-08,1.00423e-08,1.1692e-08,0,0,5.75436e-07,0,0,0,0,0,0,0,0
|
||||
6785000,0.983032,-0.00684809,-0.0123882,0.182889,-0.00536457,0.0117271,-0.0704555,-0.00124006,0.00447012,-0.0592443,-1.55151e-05,-5.81886e-05,2.08436e-06,0,0,-0.00118029,0.204181,4.65661e-10,0.433701,0,0,0,0,0,3.72508e-05,0.000303825,0.000303794,0.00109902,0.154911,0.154917,0.0622365,0.123703,0.123705,0.131649,1.00351e-08,1.00424e-08,1.16904e-08,0,0,5.48835e-07,0,0,0,0,0,0,0,0
|
||||
6885000,0.983026,-0.00667298,-0.0123047,0.182933,-0.0049002,0.00904224,-0.0668896,-0.00113637,0.00351828,-0.0579718,-1.5152e-05,-5.82085e-05,2.06344e-06,0,0,-0.00119167,0.204181,4.65661e-10,0.433701,0,0,0,0,0,3.10194e-05,0.000303275,0.000303261,0.000915618,0.120509,0.120512,0.0600307,0.0940152,0.094016,0.129809,8.41457e-09,8.42049e-09,1.16858e-08,0,0,5.15376e-07,0,0,0,0,0,0,0,0
|
||||
6985000,0.983069,-0.00663134,-0.0122667,0.182704,-0.00577645,0.00983905,-0.0629465,-0.00171782,0.00445596,-0.0551112,-1.5152e-05,-5.82094e-05,2.09931e-06,0,0,-0.00120447,0.204181,4.65661e-10,0.433701,0,0,0,0,0,2.66025e-05,0.000304928,0.000304927,0.000785283,0.133121,0.133124,0.0578956,0.112545,0.112546,0.12797,8.41466e-09,8.42059e-09,1.16802e-08,0,0,4.84086e-07,0,0,0,0,0,0,0,0
|
||||
7085000,0.983052,-0.00655397,-0.0121744,0.182804,-0.0059008,0.0127082,-0.0626768,-0.00153761,0.00375205,-0.0560241,-1.48072e-05,-5.81998e-05,2.08137e-06,0,0,-0.00121164,0.204181,4.65661e-10,0.433701,0,0,0,0,0,2.33264e-05,0.00030093,0.000300938,0.000688055,0.113243,0.113245,0.055852,0.0872969,0.0872976,0.126181,7.23279e-09,7.23774e-09,1.16716e-08,0,0,4.54959e-07,0,0,0,0,0,0,0,0
|
||||
7185000,0.983031,-0.00649565,-0.0122412,0.182917,-0.006951,0.014394,-0.0611049,-0.00222956,0.00516143,-0.0577489,-1.48086e-05,-5.81986e-05,2.02657e-06,0,0,-0.00121758,0.204181,4.65661e-10,0.433701,0,0,0,0,0,2.07801e-05,0.000302558,0.000302571,0.000612913,0.129671,0.129673,0.053878,0.103849,0.10385,0.124397,7.23288e-09,7.23784e-09,1.16612e-08,0,0,4.27733e-07,0,0,0,0,0,0,0,0
|
||||
7285000,0.98305,-0.00647744,-0.0122486,0.182817,-0.00664435,0.0172145,-0.0568324,-0.00298324,0.00672417,-0.0530896,-1.48085e-05,-5.81985e-05,2.05726e-06,0,0,-0.00123102,0.204181,4.65661e-10,0.433701,0,0,0,0,0,1.87548e-05,0.000304548,0.000304568,0.000553236,0.148828,0.14883,0.0519914,0.123563,0.123564,0.122664,7.23298e-09,7.23793e-09,1.1648e-08,0,0,4.02397e-07,0,0,0,0,0,0,0,0
|
||||
7385000,0.983078,-0.00645403,-0.0122442,0.182662,-0.00779281,0.0176512,-0.0533844,-0.00262852,0.00616266,-0.0496057,-1.44472e-05,-5.81789e-05,2.08665e-06,0,0,-0.00124229,0.204181,4.65661e-10,0.433701,0,0,0,0,0,1.71053e-05,0.000294147,0.000294168,0.000504815,0.13654,0.136541,0.050172,0.098002,0.0980028,0.120941,6.37202e-09,6.37628e-09,1.16309e-08,0,0,3.78714e-07,0,0,0,0,0,0,0,0
|
||||
7485000,0.98312,-0.00641682,-0.0122776,0.182437,-0.00579403,0.0203021,-0.0488513,-0.00330605,0.00807323,-0.0460061,-1.44442e-05,-5.81808e-05,2.23697e-06,0,0,-0.00125293,0.204181,4.65661e-10,0.433701,0,0,0,0,0,1.61011e-05,0.000295795,0.000295819,0.000474994,0.158483,0.158483,0.0495032,0.117248,0.117249,0.122934,6.37212e-09,6.37637e-09,1.16163e-08,0,0,3.61984e-07,0,0,0,0,0,0,0,0
|
||||
7585000,0.983147,-0.00657502,-0.0122558,0.182286,-0.00418596,0.0195106,-0.0443836,-0.0026674,0.00716709,-0.0396896,-1.40703e-05,-5.81725e-05,2.31e-06,0,0,-0.00126597,0.204181,4.65661e-10,0.433701,0,0,0,0,0,1.49173e-05,0.000277849,0.000277874,0.000440137,0.147644,0.147643,0.0477771,0.0947652,0.0947658,0.121171,5.75639e-09,5.76015e-09,1.1593e-08,0,0,3.4099e-07,0,0,0,0,0,0,0,0
|
||||
7685000,0.983153,-0.00660154,-0.0123176,0.182248,-0.00473827,0.0227288,-0.0424073,-0.00312224,0.00933428,-0.033002,-1.40701e-05,-5.817e-05,2.29993e-06,0,0,-0.00127874,0.204181,4.65661e-10,0.433701,0,0,0,0,0,1.39218e-05,0.000279011,0.000279039,0.00041074,0.171442,0.171441,0.0461312,0.114462,0.114462,0.119463,5.75648e-09,5.76024e-09,1.15663e-08,0,0,3.21447e-07,0,0,0,0,0,0,0,0
|
||||
7785000,0.983148,-0.00658573,-0.0123348,0.182278,-0.00226497,0.0205997,-0.0439904,-0.00240329,0.00811041,-0.0370107,-1.37169e-05,-5.81857e-05,2.245e-06,0,0,-0.001279,0.204181,4.65661e-10,0.433701,0,0,0,0,0,1.30719e-05,0.000253257,0.000253279,0.000385695,0.158201,0.158199,0.0445474,0.0935312,0.0935316,0.117771,5.33555e-09,5.33898e-09,1.1535e-08,0,0,3.03175e-07,0,0,0,0,0,0,0,0
|
||||
7885000,0.983136,-0.00661292,-0.0124083,0.182335,-0.00381577,0.024156,-0.0435015,-0.00279765,0.0103331,-0.0396533,-1.37169e-05,-5.8185e-05,2.23829e-06,0,0,-0.00128089,0.204181,4.65661e-10,0.433701,0,0,0,0,0,1.2358e-05,0.000253914,0.000253939,0.000364186,0.182472,0.18247,0.0430248,0.114101,0.114101,0.116098,5.33564e-09,5.33907e-09,1.14993e-08,0,0,2.8609e-07,0,0,0,0,0,0,0,0
|
||||
7985000,0.983142,-0.00667064,-0.0123308,0.182306,-0.00268078,0.0215112,-0.0392963,-0.00217072,0.00880342,-0.0358012,-1.3404e-05,-5.82165e-05,2.31206e-06,0,0,-0.00128965,0.204181,4.65661e-10,0.433701,0,0,0,0,0,1.17322e-05,0.000221908,0.000221927,0.000345607,0.164349,0.164347,0.0415736,0.0934547,0.0934549,0.114479,5.06871e-09,5.07193e-09,1.14589e-08,0,0,2.70174e-07,0,0,0,0,0,0,0,0
|
||||
8085000,0.98312,-0.00656392,-0.0123292,0.182429,-0.00175605,0.0245409,-0.0395257,-0.00235715,0.0110873,-0.0382661,-1.3409e-05,-5.82106e-05,2.06105e-06,0,0,-0.00129127,0.204181,4.65661e-10,0.433701,0,0,0,0,0,1.13564e-05,0.000222156,0.000222175,0.000334555,0.187942,0.18794,0.0410306,0.114855,0.114855,0.116192,5.06879e-09,5.07202e-09,1.14255e-08,0,0,2.58933e-07,0,0,0,0,0,0,0,0
|
||||
8185000,0.983107,-0.00674615,-0.0122585,0.182496,-0.000516106,0.0248093,-0.0356894,-0.0016496,0.00940553,-0.0334885,-1.31594e-05,-5.82469e-05,1.94036e-06,0,0,-0.00130025,0.204181,4.65661e-10,0.433701,0,0,0,0,0,1.08633e-05,0.000187028,0.000187043,0.000320061,0.164327,0.164326,0.039661,0.0936527,0.0936527,0.114553,4.91648e-09,4.91959e-09,1.13763e-08,0,0,2.4479e-07,0,0,0,0,0,0,0,0
|
||||
8285000,0.983117,-0.00673722,-0.012245,0.182441,0.00174055,0.0272346,-0.0329186,-0.0016061,0.0119881,-0.0319919,-1.31594e-05,-5.82437e-05,1.89265e-06,0,0,-0.00130513,0.204181,4.65661e-10,0.433701,0,0,0,0,0,1.04307e-05,0.000187041,0.000187057,0.000307405,0.186136,0.186136,0.0383456,0.115494,0.115494,0.112936,4.91656e-09,4.91966e-09,1.13219e-08,0,0,2.31551e-07,0,0,0,0,0,0,0,0
|
||||
8385000,0.983119,-0.00683782,-0.0122332,0.182431,-0.000197795,0.0231938,-0.0309736,-0.000994347,0.009869,-0.0282561,-1.29696e-05,-5.8289e-05,1.92548e-06,0,0,-0.00131195,0.204181,4.65661e-10,0.433701,0,0,0,0,0,1.00547e-05,0.000152455,0.000152465,0.000296304,0.158093,0.158092,0.0370924,0.0934311,0.0934312,0.111374,4.84088e-09,4.84393e-09,1.12621e-08,0,0,2.19201e-07,0,0,0,0,0,0,0,0
|
||||
8485000,0.983147,-0.00675064,-0.012232,0.182281,-0.000560782,0.0258229,-0.031436,-0.00100641,0.01228,-0.0322829,-1.2963e-05,-5.82964e-05,2.25442e-06,0,0,-0.00131101,0.204181,4.65661e-10,0.433701,0,0,0,0,0,9.73161e-06,0.000152444,0.000152454,0.000286559,0.177457,0.177456,0.0358891,0.115159,0.115159,0.109833,4.84095e-09,4.844e-09,1.11968e-08,0,0,2.07629e-07,0,0,0,0,0,0,0,0
|
||||
8585000,0.983158,-0.00684224,-0.0123253,0.182212,0.00068041,0.0221066,-0.0259985,-0.000679101,0.00989531,-0.0268823,-1.28382e-05,-5.83282e-05,2.23776e-06,0,0,-0.0013188,0.204181,4.65661e-10,0.433701,0,0,0,0,0,9.43339e-06,0.000121393,0.000121397,0.000277998,0.147028,0.147028,0.0347426,0.0924249,0.092425,0.108345,4.8097e-09,4.81273e-09,1.1126e-08,0,0,1.96824e-07,0,0,0,0,0,0,0,0
|
||||
8685000,0.983189,-0.00688971,-0.0124131,0.18204,0.0006507,0.0227217,-0.0271254,-0.000651164,0.012124,-0.0285424,-1.28341e-05,-5.83316e-05,2.42658e-06,0,0,-0.00131963,0.204181,4.65661e-10,0.433701,0,0,0,0,0,9.17508e-06,0.000121553,0.000121557,0.000270467,0.16367,0.16367,0.0336415,0.113491,0.113491,0.106878,4.80977e-09,4.81279e-09,1.10494e-08,0,0,1.86692e-07,0,0,0,0,0,0,0,0
|
||||
8785000,0.983187,-0.00697112,-0.0123633,0.182051,0.00182268,0.018825,-0.0259462,-0.000390814,0.00948142,-0.0250908,-1.27676e-05,-5.83475e-05,2.30126e-06,0,0,-0.00132517,0.204181,4.65661e-10,0.433701,0,0,0,0,0,9.05622e-06,9.57133e-05,9.57129e-05,0.000267075,0.133242,0.133242,0.0332254,0.0905757,0.0905757,0.108316,4.80001e-09,4.80302e-09,1.09881e-08,0,0,1.79512e-07,0,0,0,0,0,0,0,0
|
||||
8885000,0.983223,-0.007036,-0.0123589,0.181854,0.00220789,0.0205485,-0.0223639,-0.000168023,0.0114739,-0.0192428,-1.27571e-05,-5.83494e-05,2.67696e-06,0,0,-0.0013325,0.204181,4.65661e-10,0.433701,0,0,0,0,0,8.85461e-06,9.61926e-05,9.61933e-05,0.000261097,0.14717,0.147171,0.0321885,0.110563,0.110563,0.106843,4.80007e-09,4.80308e-09,1.09014e-08,0,0,1.70466e-07,0,0,0,0,0,0,0,0
|
||||
8985000,0.98326,-0.00706046,-0.0122733,0.18166,0.00135293,0.018299,-0.0203378,-3.35603e-05,0.00893342,-0.0208624,-1.27189e-05,-5.83707e-05,3.2067e-06,0,0,-0.00133286,0.204181,4.65661e-10,0.433701,0,0,0,0,0,8.67748e-06,7.59681e-05,7.59655e-05,0.000255842,0.118439,0.11844,0.0312003,0.0880246,0.0880246,0.10542,4.79831e-09,4.80132e-09,1.08092e-08,0,0,1.62004e-07,0,0,0,0,0,0,0,0
|
||||
9085000,0.98331,-0.00708759,-0.0123436,0.181378,0.00182521,0.0208407,-0.0215808,0.000118987,0.0108438,-0.0204797,-1.27057e-05,-5.8381e-05,3.8045e-06,0,0,-0.0013349,0.204181,4.65661e-10,0.433701,0,0,0,0,0,8.51986e-06,7.68661e-05,7.68636e-05,0.000251232,0.129977,0.129979,0.0302513,0.10667,0.10667,0.104021,4.79837e-09,4.80137e-09,1.07112e-08,0,0,1.54055e-07,0,0,0,0,0,0,0,0
|
||||
9185000,0.983343,-0.00716545,-0.0123713,0.181197,0.00472653,0.016782,-0.019592,0.000283986,0.00859223,-0.0202336,-1.26905e-05,-5.8392e-05,4.33755e-06,0,0,-0.00133681,0.204181,4.65661e-10,0.433701,0,0,0,0,0,8.38392e-06,6.18206e-05,6.18155e-05,0.000247177,0.104091,0.104093,0.0293396,0.0849866,0.0849867,0.102644,4.79839e-09,4.80139e-09,1.06075e-08,0,0,1.46585e-07,0,0,0,0,0,0,0,0
|
||||
9285000,0.983367,-0.0070295,-0.0121977,0.181082,0.00695741,0.0179991,-0.0177572,0.000925603,0.0103105,-0.0174082,-1.26824e-05,-5.83944e-05,4.64896e-06,0,0,-0.00134061,0.204181,4.65661e-10,0.433701,0,0,0,0,0,8.26698e-06,6.31897e-05,6.31852e-05,0.000243635,0.113583,0.113585,0.0284707,0.102182,0.102182,0.101313,4.79844e-09,4.80143e-09,1.04985e-08,0,0,1.39586e-07,0,0,0,0,0,0,0,0
|
||||
9385000,0.98336,-0.00693635,-0.0122383,0.181121,0.00711911,0.0186237,-0.01616,0.00166448,0.0121574,-0.0171829,-1.26869e-05,-5.83877e-05,4.39572e-06,0,0,-0.00134211,0.204181,4.65661e-10,0.433701,0,0,0,0,0,8.25446e-06,6.48002e-05,6.4795e-05,0.000243235,0.123518,0.12352,0.0281488,0.122375,0.122375,0.102593,4.7985e-09,4.80149e-09,1.04133e-08,0,0,1.3462e-07,0,0,0,0,0,0,0,0
|
||||
9485000,0.983388,-0.00704946,-0.0122897,0.18096,0.00622843,0.0143603,-0.0137522,0.0017027,0.00953521,-0.0131019,-1.2687e-05,-5.83845e-05,4.67073e-06,0,0,-0.00134646,0.204181,4.65661e-10,0.433701,0,0,0,0,0,8.15617e-06,5.4363e-05,5.43561e-05,0.000240479,0.0988742,0.0988757,0.02733,0.0974248,0.0974251,0.101262,4.79836e-09,4.80135e-09,1.0295e-08,0,0,1.28339e-07,0,0,0,0,0,0,0,0
|
||||
9585000,0.983362,-0.00708732,-0.0122672,0.181103,0.00569397,0.0134293,-0.0143235,0.00222377,0.0109115,-0.0160444,-1.2696e-05,-5.83781e-05,4.26694e-06,0,0,-0.00134523,0.204181,4.65661e-10,0.433701,0,0,0,0,0,8.08161e-06,5.64673e-05,5.64611e-05,0.000238071,0.10716,0.107161,0.0265433,0.115774,0.115774,0.0999546,4.79841e-09,4.80139e-09,1.01715e-08,0,0,1.22426e-07,0,0,0,0,0,0,0,0
|
||||
9685000,0.983374,-0.0071483,-0.0122006,0.181039,0.00486136,0.0107891,-0.0110384,0.00205612,0.00850527,-0.0135156,-1.27058e-05,-5.83673e-05,4.1795e-06,0,0,-0.00134811,0.204181,4.65661e-10,0.433701,0,0,0,0,0,8.0058e-06,4.94879e-05,4.9481e-05,0.000235995,0.0862568,0.0862582,0.0257927,0.0926517,0.092652,0.098691,4.79812e-09,4.8011e-09,1.00435e-08,0,0,1.16874e-07,0,0,0,0,0,0,0,0
|
||||
9785000,0.983361,-0.00713181,-0.012153,0.181112,0.00613526,0.0122318,-0.0115416,0.00262875,0.00967409,-0.0138338,-1.27174e-05,-5.83549e-05,3.59574e-06,0,0,-0.00134876,0.204181,4.65661e-10,0.433701,0,0,0,0,0,7.94159e-06,5.20894e-05,5.2083e-05,0.000234196,0.093328,0.09333,0.0250713,0.109292,0.109293,0.0974491,4.79816e-09,4.80113e-09,9.91075e-09,0,0,1.11641e-07,0,0,0,0,0,0,0,0
|
||||
9885000,0.983379,-0.00714936,-0.0120775,0.18102,0.00755446,0.00904383,-0.00984279,0.00237582,0.00742248,-0.0139234,-1.27151e-05,-5.83578e-05,3.93562e-06,0,0,-0.00134946,0.204181,4.65661e-10,0.433701,0,0,0,0,0,7.89205e-06,4.77469e-05,4.774e-05,0.00023264,0.0758719,0.0758736,0.0243828,0.0880402,0.0880405,0.0962487,4.79809e-09,4.80105e-09,9.77392e-09,0,0,1.06722e-07,0,0,0,0,0,0,0,0
|
||||
9985000,0.983354,-0.00714698,-0.012153,0.181153,0.009057,0.00844333,-0.00874692,0.00318377,0.00823872,-0.0149432,-1.27264e-05,-5.83469e-05,3.38674e-06,0,0,-0.00134943,0.204181,4.65661e-10,0.433701,0,0,0,0,0,7.85016e-06,5.08377e-05,5.08305e-05,0.000231296,0.0820963,0.0820984,0.0237205,0.103155,0.103155,0.0950687,4.79813e-09,4.80109e-09,9.6329e-09,0,0,1.02082e-07,0,0,0,0,0,0,0,0
|
||||
10085000,0.983347,-0.00713168,-0.0122924,0.181184,0.00717706,0.00377795,-0.00754102,0.00292303,0.00617928,-0.0133467,-1.27312e-05,-5.83395e-05,2.99587e-06,0,0,-0.00135111,0.204181,4.65661e-10,0.433701,0,0,0,0,0,7.89214e-06,4.8459e-05,4.845e-05,0.000232609,0.0676696,0.0676711,0.0234817,0.0837076,0.0837081,0.0961861,4.79812e-09,4.80108e-09,9.52461e-09,0,0,9.87759e-08,0,0,0,0,0,0,0,0
|
||||
10185000,0.98331,-0.00710592,-0.0122117,0.18139,0.00501755,0.00412511,-0.0058503,0.00351235,0.00658947,-0.0133606,-1.2748e-05,-5.83222e-05,2.16418e-06,0,0,-0.0013516,0.204181,4.65661e-10,0.433701,0,0,0,0,0,7.86197e-06,5.20229e-05,5.20145e-05,0.000231593,0.0733953,0.0733973,0.022857,0.0975022,0.0975028,0.09501,4.79816e-09,4.80111e-09,9.37718e-09,0,0,9.45861e-08,0,0,0,0,0,0,0,0
|
||||
10285000,0.983341,-0.00717174,-0.0121188,0.181227,0.00448316,0.00274045,-0.00689194,0.00284077,0.00488052,-0.0132469,-1.27298e-05,-5.83415e-05,2.61415e-06,0,0,-0.00135206,0.204181,4.65661e-10,0.433701,0,0,0,0,0,7.83233e-06,5.10706e-05,5.10625e-05,0.000230728,0.0615526,0.0615545,0.0222603,0.0797326,0.0797331,0.0938728,4.797e-09,4.79994e-09,9.22678e-09,0,0,9.06396e-08,0,0,0,0,0,0,0,0
|
||||
10385000,0.98249,-0.00712816,-0.0120529,0.185789,0.00719306,0.00200988,-0.00298336,0.00077468,2.98472e-05,-0.0114183,-1.27287e-05,-5.83394e-05,2.62442e-06,0,0,-0.00135338,0.204706,0.00196981,0.434395,0,0,0,0,0,6.39335e-05,5.22105e-05,5.20491e-05,0.00177858,0.034724,0.0347241,0.0374564,0.12528,0.12528,0.0867795,4.7971e-09,4.80003e-09,9.2268e-09,0,0,8.7102e-08,0,0,0,0,0,0,0,0
|
||||
10485000,0.982349,-0.00703601,-0.0120072,0.18654,0.00748085,0.00135394,-0.00193103,0.0015003,0.000194953,-0.00675977,-1.27269e-05,-5.83332e-05,2.60453e-06,0,0,-0.0013566,0.204706,0.00196981,0.434395,0,0,0,0,0,4.81415e-05,5.2511e-05,5.23915e-05,0.00134012,0.0353688,0.0353688,0.0375609,0.126252,0.126252,0.0808889,4.7972e-09,4.80012e-09,9.22638e-09,0,0,8.41239e-08,0,0,0,0,0,0,0,0
|
||||
10585000,0.982488,-0.00699466,-0.0119472,0.185813,0.0061154,0.00061665,-0.000628709,0.0011734,-0.00345086,-0.00580301,-1.27279e-05,-5.83433e-05,2.66119e-06,0,0,-0.00135713,0.204706,0.00196981,0.434395,0,0,0,0,0,3.86542e-05,5.29436e-05,5.28497e-05,0.00107544,0.0318294,0.0318293,0.0352724,0.084859,0.084859,0.0763582,4.79721e-09,4.80012e-09,9.22522e-09,0,0,8.15804e-08,0,0,0,0,0,0,0,0
|
||||
10685000,0.98249,-0.00695664,-0.0119826,0.185799,0.00660943,-0.00174939,-0.000519142,0.00180228,-0.00351192,-0.00490479,-1.27277e-05,-5.8342e-05,2.65081e-06,0,0,-0.00135773,0.204706,0.00196981,0.434395,0,0,0,0,0,3.36601e-05,5.37704e-05,5.36882e-05,0.000937319,0.0331943,0.0331941,0.0353182,0.0865709,0.0865709,0.0744969,4.79731e-09,4.80022e-09,9.22375e-09,0,0,7.991e-08,0,0,0,0,0,0,0,0
|
||||
10785000,0.982489,-0.00696168,-0.0120897,0.1858,0.00737693,-0.00300671,0.000364274,0.00171922,-0.00316179,-0.00196128,-1.27197e-05,-5.83522e-05,2.63948e-06,0,0,-0.00135951,0.204706,0.00196981,0.434395,0,0,0,0,0,2.87298e-05,5.43155e-05,5.4244e-05,0.000800522,0.0306284,0.0306282,0.0331911,0.0656959,0.0656959,0.0717266,4.79682e-09,4.79973e-09,9.22071e-09,0,0,7.79345e-08,0,0,0,0,0,0,0,0
|
||||
10885000,0.982591,-0.0069498,-0.0121354,0.185254,0.00791893,-0.00305568,0.000567742,0.00248569,-0.00352073,-0.00133609,-1.2717e-05,-5.8354e-05,2.76393e-06,0,0,-0.00135984,0.204706,0.00196981,0.434395,0,0,0,0,0,2.51025e-05,5.56213e-05,5.55589e-05,0.000699049,0.0326576,0.0326572,0.0330678,0.0679669,0.0679669,0.0700812,4.79692e-09,4.79982e-09,9.21627e-09,0,0,7.62143e-08,0,0,0,0,0,0,0,0
|
||||
10985000,0.982595,-0.00694933,-0.0122443,0.185227,0.00628733,0.00238806,0.00257041,0.00225656,-0.00267845,0.00149554,-1.2733e-05,-5.83678e-05,2.73824e-06,0,0,-0.00136101,0.204706,0.00196981,0.434395,0,0,0,0,0,2.22808e-05,5.60447e-05,5.59883e-05,0.000620952,0.0306189,0.0306188,0.0310545,0.0551375,0.0551375,0.0684182,4.79467e-09,4.79756e-09,9.2103e-09,0,0,7.47027e-08,0,0,0,0,0,0,0,0
|
||||
11085000,0.982497,-0.00707952,-0.0122305,0.185741,0.00715693,0.0046236,0.00444639,0.00290041,-0.00238894,0.00415305,-1.27358e-05,-5.83621e-05,2.55928e-06,0,0,-0.00136225,0.204706,0.00196981,0.434395,0,0,0,0,0,2.0069e-05,5.78182e-05,5.77701e-05,0.000559054,0.033265,0.0332649,0.0307898,0.0579097,0.0579096,0.067839,4.79477e-09,4.79765e-09,9.20252e-09,0,0,7.33785e-08,0,0,0,0,0,0,0,0
|
||||
11185000,0.982475,-0.00710064,-0.0121894,0.185863,0.00690957,0.00638766,0.00768226,0.00329391,-0.00169445,0.00882444,-1.27138e-05,-5.83549e-05,2.46336e-06,0,0,-0.0013639,0.204706,0.00196981,0.434395,0,0,0,0,0,1.82501e-05,5.79163e-05,5.78744e-05,0.000508937,0.0314287,0.0314287,0.0288869,0.0489589,0.0489589,0.0667996,4.78834e-09,4.79122e-09,9.19282e-09,0,0,7.2209e-08,0,0,0,0,0,0,0,0
|
||||
11285000,0.982457,-0.00711106,-0.0122252,0.185954,0.00609512,0.00591765,0.0087445,0.00390196,-0.00102332,0.00862245,-1.27152e-05,-5.83549e-05,2.41227e-06,0,0,-0.00136343,0.204706,0.00196981,0.434395,0,0,0,0,0,1.67693e-05,6.01376e-05,6.00997e-05,0.000467581,0.0346486,0.0346486,0.0285001,0.0522161,0.0522161,0.0668728,4.78843e-09,4.79131e-09,9.18093e-09,0,0,7.1182e-08,0,0,0,0,0,0,0,0
|
||||
11385000,0.982455,-0.00703083,-0.0122149,0.185967,0.00497086,0.00647411,0.00783481,0.00331087,-0.000626813,0.00676149,-1.26982e-05,-5.84176e-05,2.38471e-06,0,0,-0.00136216,0.204706,0.00196981,0.434395,0,0,0,0,0,1.58396e-05,5.97464e-05,5.97105e-05,0.000441791,0.0327609,0.0327609,0.0268624,0.0453284,0.0453284,0.0672753,4.77431e-09,4.77718e-09,9.17047e-09,0,0,7.04911e-08,0,0,0,0,0,0,0,0
|
||||
11485000,0.98249,-0.00694939,-0.0121942,0.185786,0.00358362,0.0057815,0.00950902,0.00368955,8.14812e-06,0.00997281,-1.26965e-05,-5.84165e-05,2.43221e-06,0,0,-0.00136316,0.204706,0.00196981,0.434395,0,0,0,0,0,1.47347e-05,6.23835e-05,6.23504e-05,0.000411338,0.0365067,0.0365068,0.0263984,0.0490658,0.0490658,0.0677352,4.7744e-09,4.77727e-09,9.15431e-09,0,0,6.96676e-08,0,0,0,0,0,0,0,0
|
||||
11585000,0.982489,-0.00704469,-0.0121654,0.185792,0.00519957,0.0056357,0.0100202,0.00321801,0.000131853,0.0113263,-1.26591e-05,-5.84768e-05,2.39705e-06,0,0,-0.00136394,0.204706,0.00196981,0.434395,0,0,0,0,0,1.38004e-05,6.13717e-05,6.13422e-05,0.000385356,0.0343497,0.03435,0.0247436,0.043299,0.043299,0.0671541,4.74828e-09,4.75113e-09,9.13557e-09,0,0,6.89377e-08,0,0,0,0,0,0,0,0
|
||||
11685000,0.982502,-0.00700969,-0.0121155,0.185726,0.0056429,0.00798338,0.0117565,0.00376926,0.000810118,0.0115515,-1.26583e-05,-5.84784e-05,2.44432e-06,0,0,-0.00136359,0.204706,0.00196981,0.434395,0,0,0,0,0,1.29983e-05,6.43858e-05,6.4359e-05,0.000363002,0.0385529,0.0385534,0.0242157,0.0475072,0.0475072,0.0677989,4.74837e-09,4.75122e-09,9.11396e-09,0,0,6.82974e-08,0,0,0,0,0,0,0,0
|
||||
11785000,0.98254,-0.00710708,-0.0120829,0.185523,0.00425649,0.00844395,0.0125789,0.00312157,-9.5034e-05,0.0143238,-1.24727e-05,-5.86325e-05,2.66369e-06,0,0,-0.00136417,0.204706,0.00196981,0.434395,0,0,0,0,0,1.23073e-05,6.26902e-05,6.2666e-05,0.000343626,0.0359859,0.0359866,0.0226935,0.04231,0.04231,0.0672499,4.70592e-09,4.70875e-09,9.08929e-09,0,0,6.77289e-08,0,0,0,0,0,0,0,0
|
||||
11885000,0.982525,-0.00718949,-0.0119859,0.185603,0.00702334,0.00877226,0.0116123,0.00361335,0.00072106,0.0156469,-1.24759e-05,-5.86294e-05,2.50206e-06,0,0,-0.00136418,0.204706,0.00196981,0.434395,0,0,0,0,0,1.16982e-05,6.60338e-05,6.60131e-05,0.00032675,0.0405992,0.0406003,0.0221328,0.0469683,0.0469684,0.0679447,4.70601e-09,4.70884e-09,9.0616e-09,0,0,6.72309e-08,0,0,0,0,0,0,0,0
|
||||
11985000,0.982543,-0.00727689,-0.0120285,0.185503,0.00792954,0.0099421,0.0107359,0.00400552,-0.000104232,0.0131015,-1.2434e-05,-5.86194e-05,2.53617e-06,0,0,-0.00136328,0.204706,0.00196981,0.434395,0,0,0,0,0,1.13232e-05,6.36426e-05,6.3624e-05,0.000316521,0.0375187,0.0375199,0.0209318,0.0419943,0.0419943,0.0685376,4.64342e-09,4.64623e-09,9.03869e-09,0,0,6.68942e-08,0,0,0,0,0,0,0,0
|
||||
12085000,0.982523,-0.00719571,-0.0120869,0.18561,0.00962066,0.00976398,0.0133344,0.00488768,0.000842388,0.0198665,-1.24355e-05,-5.86131e-05,2.40944e-06,0,0,-0.00136494,0.204706,0.00196981,0.434395,0,0,0,0,0,1.08491e-05,6.72643e-05,6.72463e-05,0.000303145,0.0424517,0.0424532,0.0203709,0.0470683,0.0470685,0.0692194,4.64351e-09,4.64632e-09,9.00517e-09,0,0,6.64942e-08,0,0,0,0,0,0,0,0
|
||||
12185000,0.98251,-0.00709446,-0.0120618,0.185684,0.00938135,0.00910116,0.0126797,0.00407779,0.00170691,0.0215166,-1.25199e-05,-5.87733e-05,2.12886e-06,0,0,-0.00136508,0.204706,0.00196981,0.434395,0,0,0,0,0,1.04149e-05,6.42236e-05,6.42068e-05,0.000291369,0.0388413,0.0388428,0.0191242,0.0420974,0.0420974,0.0685749,4.55832e-09,4.56108e-09,8.96805e-09,0,0,6.61343e-08,0,0,0,0,0,0,0,0
|
||||
12285000,0.982494,-0.00714667,-0.0120538,0.185766,0.00715958,0.00782763,0.0110889,0.00491534,0.00254645,0.0221265,-1.25235e-05,-5.87703e-05,1.95706e-06,0,0,-0.00136492,0.204706,0.00196981,0.434395,0,0,0,0,0,1.00427e-05,6.80661e-05,6.80511e-05,0.000280958,0.0440421,0.0440437,0.0185769,0.0475408,0.0475409,0.0691666,4.55841e-09,4.56117e-09,8.9275e-09,0,0,6.58214e-08,0,0,0,0,0,0,0,0
|
||||
12385000,0.982502,-0.00719601,-0.0119778,0.185725,0.00582827,0.00607604,0.0115786,0.00405065,0.00200229,0.0192434,-1.2436e-05,-5.89632e-05,1.83186e-06,0,0,-0.001364,0.204706,0.00196981,0.434395,0,0,0,0,0,9.70173e-06,6.44508e-05,6.44376e-05,0.000271745,0.0398968,0.0398983,0.0174685,0.0424381,0.0424383,0.068458,4.44948e-09,4.45218e-09,8.88314e-09,0,0,6.55353e-08,0,0,0,0,0,0,0,0
|
||||
12485000,0.982479,-0.00719731,-0.0119893,0.185849,0.00637707,0.0068954,0.0154451,0.00466817,0.00263351,0.0212862,-1.24389e-05,-5.89599e-05,1.68233e-06,0,0,-0.00136416,0.204706,0.00196981,0.434395,0,0,0,0,0,9.41687e-06,6.8459e-05,6.84469e-05,0.000263562,0.0452642,0.0452661,0.0169518,0.0481964,0.0481966,0.0689332,4.44956e-09,4.45226e-09,8.83523e-09,0,0,6.52883e-08,0,0,0,0,0,0,0,0
|
||||
12585000,0.982454,-0.00727421,-0.0119237,0.185983,0.00850148,0.00242004,0.0171138,0.00509904,0.000746057,0.0225937,-1.20859e-05,-5.90188e-05,1.45805e-06,0,0,-0.00136406,0.204706,0.00196981,0.434395,0,0,0,0,0,9.16015e-06,6.43749e-05,6.43643e-05,0.000256296,0.040671,0.0406727,0.0159758,0.0428914,0.0428916,0.0681633,4.31758e-09,4.32019e-09,8.78337e-09,0,0,6.5056e-08,0,0,0,0,0,0,0,0
|
||||
12685000,0.982456,-0.00724859,-0.0119414,0.185969,0.00881675,0.000640211,0.0172505,0.00590905,0.000898581,0.0255178,-1.20877e-05,-5.90161e-05,1.35903e-06,0,0,-0.00136432,0.204706,0.00196981,0.434395,0,0,0,0,0,9.02978e-06,6.84961e-05,6.84859e-05,0.000252759,0.0461995,0.0462014,0.0156654,0.0489091,0.0489094,0.0697078,4.31767e-09,4.32028e-09,8.74198e-09,0,0,6.49085e-08,0,0,0,0,0,0,0,0
|
||||
12785000,0.982517,-0.00741935,-0.0118101,0.185652,0.00929795,-0.00107564,0.0184446,0.00543184,-0.00172139,0.0271066,-1.15976e-05,-5.90568e-05,1.8933e-06,0,0,-0.00136424,0.204706,0.00196981,0.434395,0,0,0,0,0,8.81281e-06,6.40298e-05,6.40216e-05,0.000246898,0.0412295,0.0412313,0.0148038,0.0433744,0.0433746,0.0688574,4.16411e-09,4.16661e-09,8.68333e-09,0,0,6.47087e-08,0,0,0,0,0,0,0,0
|
||||
12885000,0.982557,-0.0074036,-0.0117467,0.185442,0.00917802,-0.00241745,0.019287,0.00639305,-0.001896,0.0304557,-1.15919e-05,-5.90614e-05,2.1703e-06,0,0,-0.00136452,0.204706,0.00196981,0.434395,0,0,0,0,0,8.62014e-06,6.82127e-05,6.82058e-05,0.0002417,0.0468502,0.0468523,0.0143772,0.0495991,0.0495994,0.0690951,4.16418e-09,4.16669e-09,8.62103e-09,0,0,6.45441e-08,0,0,0,0,0,0,0,0
|
||||
12985000,0.982597,-0.00741128,-0.0117199,0.185234,0.00768282,-0.000922373,0.0196691,0.00505337,-0.00149377,0.0319908,-1.17337e-05,-5.92772e-05,2.41545e-06,0,0,-0.00136445,0.204706,0.00196981,0.434395,0,0,0,0,0,8.44479e-06,6.3452e-05,6.34456e-05,0.000237083,0.0415882,0.0415901,0.0136305,0.0438373,0.0438375,0.0682049,3.99167e-09,3.99406e-09,8.55469e-09,0,0,6.437e-08,0,0,0,0,0,0,0,0
|
||||
13085000,0.982612,-0.00742081,-0.0116452,0.185158,0.00881036,-0.00075796,0.0180926,0.00587443,-0.00153227,0.0319902,-1.17266e-05,-5.92856e-05,2.79381e-06,0,0,-0.00136408,0.204706,0.00196981,0.434395,0,0,0,0,0,8.30624e-06,6.76521e-05,6.76471e-05,0.00023297,0.0472754,0.0472778,0.013255,0.0502211,0.0502215,0.0683206,3.99174e-09,3.99413e-09,8.48451e-09,0,0,6.42327e-08,0,0,0,0,0,0,0,0
|
||||
13185000,0.982621,-0.00743525,-0.0115935,0.185109,0.00507883,-0.00231696,0.0172215,0.00278727,-0.00261675,0.0329846,-1.16554e-05,-5.96787e-05,2.98779e-06,0,0,-0.00136394,0.204706,0.00196981,0.434395,0,0,0,0,0,8.178e-06,6.26644e-05,6.26594e-05,0.000229331,0.0417975,0.0417995,0.0126129,0.0442519,0.0442521,0.0674051,3.80337e-09,3.80563e-09,8.4106e-09,0,0,6.40732e-08,0,0,0,0,0,0,0,0
|
||||
13285000,0.982625,-0.00744819,-0.0115774,0.185091,0.00424022,-0.00318645,0.0154542,0.00318528,-0.00287659,0.0336252,-1.16568e-05,-5.9678e-05,2.92765e-06,0,0,-0.00136377,0.204706,0.00196981,0.434395,0,0,0,0,0,8.14583e-06,6.68418e-05,6.68376e-05,0.000228499,0.0475187,0.047521,0.0124272,0.0507552,0.0507556,0.0685872,3.80345e-09,3.80571e-09,8.35283e-09,0,0,6.39869e-08,0,0,0,0,0,0,0,0
|
||||
13385000,0.982616,-0.00740036,-0.0116695,0.185136,0.00313843,-0.00201636,0.0145265,0.00248419,-0.00219839,0.0335561,-1.1805e-05,-5.97569e-05,2.67005e-06,0,0,-0.00136349,0.204706,0.00196981,0.434395,0,0,0,0,0,8.03771e-06,6.16847e-05,6.16796e-05,0.000225598,0.0418806,0.0418825,0.0118713,0.0446064,0.0446066,0.067628,3.60273e-09,3.60484e-09,8.27239e-09,0,0,6.38304e-08,0,0,0,0,0,0,0,0
|
||||
13485000,0.982614,-0.00737256,-0.0116301,0.185151,0.00391984,-0.000182229,0.0152903,0.00283517,-0.00226082,0.0323443,-1.18063e-05,-5.97573e-05,2.62489e-06,0,0,-0.00136306,0.204706,0.00196981,0.434395,0,0,0,0,0,7.94779e-06,6.58024e-05,6.57982e-05,0.000223035,0.0475894,0.047592,0.0116004,0.0511952,0.0511957,0.0675635,3.60279e-09,3.60491e-09,8.18837e-09,0,0,6.37247e-08,0,0,0,0,0,0,0,0
|
||||
13585000,0.982587,-0.00738125,-0.011702,0.185286,0.00724922,-0.000698228,0.0166784,0.00504802,-0.00190484,0.0305593,-1.16859e-05,-5.93746e-05,2.36144e-06,0,0,-0.00136249,0.204706,0.00196981,0.434395,0,0,0,0,0,7.87073e-06,6.05277e-05,6.05235e-05,0.000220778,0.0418364,0.0418383,0.0111295,0.0448982,0.0448985,0.0666055,3.39353e-09,3.3955e-09,8.10094e-09,0,0,6.35664e-08,0,0,0,0,0,0,0,0
|
||||
13685000,0.982619,-0.00731818,-0.0116175,0.185125,0.0067869,-0.00213135,0.0162856,0.00574195,-0.00204757,0.0330017,-1.16817e-05,-5.93783e-05,2.57068e-06,0,0,-0.0013626,0.204706,0.00196981,0.434395,0,0,0,0,0,7.7934e-06,6.45555e-05,6.45521e-05,0.000218804,0.0475424,0.0475446,0.0109099,0.0515444,0.0515449,0.0664757,3.39359e-09,3.39557e-09,8.01015e-09,0,0,6.34693e-08,0,0,0,0,0,0,0,0
|
||||
13785000,0.982604,-0.00727078,-0.0117389,0.185201,0.0131669,0.000807221,0.0164204,0.00878527,-0.000180214,0.0326125,-1.18016e-05,-5.87537e-05,2.28024e-06,0,0,-0.00136217,0.204706,0.00196981,0.434395,0,0,0,0,0,7.72945e-06,5.92037e-05,5.91998e-05,0.000217071,0.0417393,0.0417412,0.0105144,0.0451309,0.0451312,0.06553,3.17937e-09,3.18119e-09,7.91621e-09,0,0,6.33022e-08,0,0,0,0,0,0,0,0
|
||||
13885000,0.982631,-0.00719361,-0.0117105,0.185063,0.014427,0.00180533,0.0176838,0.0101366,-2.25834e-05,0.0349894,-1.17921e-05,-5.87624e-05,2.74963e-06,0,0,-0.00136227,0.204706,0.00196981,0.434395,0,0,0,0,0,7.67681e-06,6.31161e-05,6.31127e-05,0.000215552,0.0474023,0.0474048,0.0103431,0.0518149,0.0518154,0.0653519,3.17943e-09,3.18126e-09,7.81921e-09,0,0,6.32095e-08,0,0,0,0,0,0,0,0
|
||||
13985000,0.982642,-0.00725844,-0.0114516,0.185019,0.0143739,0.00268462,0.0166978,0.00798621,-0.00142442,0.0353408,-1.16459e-05,-5.92989e-05,3.05895e-06,0,0,-0.00136204,0.204706,0.00196981,0.434395,0,0,0,0,0,7.70787e-06,5.77194e-05,5.77166e-05,0.000216358,0.0415774,0.0415797,0.0101159,0.0453115,0.0453119,0.0654822,2.96358e-09,2.96526e-09,7.74442e-09,0,0,6.30525e-08,0,0,0,0,0,0,0,0
|
||||
14085000,0.98258,-0.00724832,-0.0113888,0.185348,0.0118247,-0.00160351,0.0185099,0.00938508,-0.00139175,0.0338456,-1.16684e-05,-5.9279e-05,1.9492e-06,0,0,-0.00136158,0.204706,0.00196981,0.434395,0,0,0,0,0,7.66772e-06,6.14946e-05,6.14928e-05,0.000215179,0.0471815,0.0471836,0.00998723,0.0520168,0.0520174,0.0652644,2.96364e-09,2.96532e-09,7.64241e-09,0,0,6.29612e-08,0,0,0,0,0,0,0,0
|
||||
14185000,0.982538,-0.007231,-0.0113201,0.185574,0.00943344,-0.000323131,0.0174624,0.00858738,-0.00101225,0.0316076,-1.17914e-05,-5.93524e-05,1.18863e-06,0,0,-0.00136065,0.204706,0.00196981,0.434395,0,0,0,0,0,7.63119e-06,5.60889e-05,5.60868e-05,0.000214156,0.0413466,0.0413482,0.00971064,0.0454474,0.0454477,0.0643394,2.74934e-09,2.75087e-09,7.53786e-09,0,0,6.27589e-08,0,0,0,0,0,0,0,0
|
||||
14285000,0.982532,-0.00715575,-0.0113128,0.185609,0.0106055,-0.000764476,0.0163141,0.00945612,-0.00112597,0.0353144,-1.1792e-05,-5.93507e-05,1.14062e-06,0,0,-0.00136096,0.204706,0.00196981,0.434395,0,0,0,0,0,7.6029e-06,5.97107e-05,5.97088e-05,0.000213263,0.046911,0.046913,0.00962339,0.0521616,0.0521621,0.0641022,2.7494e-09,2.75093e-09,7.43091e-09,0,0,6.26656e-08,0,0,0,0,0,0,0,0
|
||||
14385000,0.982538,-0.00724566,-0.0112515,0.185579,0.0112367,-0.00363174,0.0163659,0.00887302,-0.00239494,0.0388848,-1.16094e-05,-5.95235e-05,1.37212e-06,0,0,-0.00136111,0.204706,0.00196981,0.434395,0,0,0,0,0,7.57741e-06,5.43211e-05,5.4319e-05,0.00021248,0.0410862,0.0410877,0.00939699,0.0455453,0.0455456,0.0632071,2.5392e-09,2.54059e-09,7.32156e-09,0,0,6.24386e-08,0,0,0,0,0,0,0,0
|
||||
14485000,0.982511,-0.00734868,-0.0112193,0.185723,0.00939679,-0.00340207,0.0201124,0.00982803,-0.00275629,0.0411475,-1.16233e-05,-5.951e-05,6.66127e-07,0,0,-0.00136119,0.204706,0.00196981,0.434395,0,0,0,0,0,7.55108e-06,5.7776e-05,5.77752e-05,0.00021181,0.0465414,0.0465431,0.00934714,0.052259,0.0522594,0.062963,2.53926e-09,2.54065e-09,7.21046e-09,0,0,6.23406e-08,0,0,0,0,0,0,0,0
|
||||
14585000,0.982497,-0.007423,-0.0110435,0.185803,0.00725285,-0.00337403,0.0187311,0.00642853,-0.00354594,0.0389864,-1.16921e-05,-6.00859e-05,4.37493e-07,0,0,-0.00136048,0.204706,0.00196981,0.434395,0,0,0,0,0,7.60501e-06,5.24425e-05,5.24413e-05,0.000213297,0.0407458,0.0407472,0.00925076,0.0456127,0.045613,0.0630943,2.3358e-09,2.33705e-09,7.12589e-09,0,0,6.21128e-08,0,0,0,0,0,0,0,0
|
||||
14685000,0.982515,-0.00739752,-0.0110997,0.185706,0.00667776,-0.00341475,0.0184792,0.00711692,-0.00386727,0.0394594,-1.16882e-05,-6.00905e-05,6.48317e-07,0,0,-0.00136024,0.204706,0.00196981,0.434395,0,0,0,0,0,7.58494e-06,5.57226e-05,5.57215e-05,0.000212774,0.0461265,0.0461281,0.00923336,0.0523176,0.0523181,0.0628459,2.33586e-09,2.33711e-09,7.01173e-09,0,0,6.20091e-08,0,0,0,0,0,0,0,0
|
||||
14785000,0.982552,-0.00734823,-0.0110785,0.185514,0.00791009,0.00328667,0.0182226,0.00575093,0.00114578,0.0414172,-1.25361e-05,-5.99898e-05,1.12476e-06,0,0,-0.00136052,0.204706,0.00196981,0.434395,0,0,0,0,0,7.56245e-06,5.04697e-05,5.04683e-05,0.00021231,0.0403699,0.0403713,0.00908496,0.0456545,0.0456548,0.06201,2.14086e-09,2.14198e-09,6.89596e-09,0,0,6.17212e-08,0,0,0,0,0,0,0,0
|
||||
14885000,0.982587,-0.007274,-0.0110044,0.185333,0.00662426,0.00132815,0.0217991,0.00646563,0.00138021,0.0423544,-1.2526e-05,-5.99999e-05,1.64069e-06,0,0,-0.0013603,0.204706,0.00196981,0.434395,0,0,0,0,0,7.54552e-06,5.3569e-05,5.35682e-05,0.000211901,0.0456248,0.0456262,0.00909768,0.0523441,0.0523446,0.0617745,2.14091e-09,2.14203e-09,6.7792e-09,0,0,6.16078e-08,0,0,0,0,0,0,0,0
|
||||
14985000,0.982591,-0.0074185,-0.0108766,0.185315,0.00566068,-0.000486923,0.0245673,0.0051283,-0.000276744,0.0437472,-1.23553e-05,-6.0306e-05,1.86034e-06,0,0,-0.00135954,0.204706,0.00196981,0.434395,0,0,0,0,0,7.53453e-06,4.84298e-05,4.84285e-05,0.000211519,0.039907,0.0399081,0.00898144,0.0456752,0.0456755,0.0609863,1.95598e-09,1.95696e-09,6.66126e-09,0,0,6.12844e-08,0,0,0,0,0,0,0,0
|
||||
15085000,0.982589,-0.00735974,-0.0109621,0.185325,0.00569351,0.000301726,0.0284344,0.00570597,-0.000319026,0.0461754,-1.23574e-05,-6.03042e-05,1.75931e-06,0,0,-0.0013595,0.204706,0.00196981,0.434395,0,0,0,0,0,7.52229e-06,5.1348e-05,5.13464e-05,0.000211178,0.0450425,0.0450438,0.00902066,0.0523419,0.0523423,0.0607709,1.95604e-09,1.95702e-09,6.54274e-09,0,0,6.11589e-08,0,0,0,0,0,0,0,0
|
||||
15185000,0.982582,-0.00748839,-0.0110044,0.185352,0.00400529,-0.000789858,0.0288112,0.00451783,-0.000382179,0.0467433,-1.24122e-05,-6.04665e-05,1.57594e-06,0,0,-0.00135879,0.204706,0.00196981,0.434395,0,0,0,0,0,7.50854e-06,4.63497e-05,4.63474e-05,0.000210854,0.0394082,0.0394091,0.00893121,0.0456777,0.045678,0.0600314,1.7822e-09,1.78308e-09,6.42345e-09,0,0,6.07972e-08,0,0,0,0,0,0,0,0
|
||||
15285000,0.9826,-0.00758756,-0.011034,0.185249,0.00389031,-0.00140636,0.0286121,0.00493644,-0.000448439,0.0465638,-1.2404e-05,-6.04772e-05,2.05388e-06,0,0,-0.00135817,0.204706,0.00196981,0.434395,0,0,0,0,0,7.57379e-06,4.90872e-05,4.90852e-05,0.000212607,0.0444334,0.0444344,0.00906837,0.0523176,0.052318,0.0607508,1.78227e-09,1.78314e-09,6.33373e-09,0,0,6.06954e-08,0,0,0,0,0,0,0,0
|
||||
15385000,0.982566,-0.00765763,-0.0110386,0.185427,0.00461738,0.000966945,0.0282437,0.00395788,-0.00024183,0.0457899,-1.24963e-05,-6.05855e-05,1.61142e-06,0,0,-0.00135698,0.204706,0.00196981,0.434395,0,0,0,0,0,7.56692e-06,4.42483e-05,4.42442e-05,0.000212292,0.0388769,0.038878,0.00899836,0.0456653,0.0456657,0.060039,1.62008e-09,1.62078e-09,6.21381e-09,0,0,6.02936e-08,0,0,0,0,0,0,0,0
|
||||
15485000,0.982561,-0.00769536,-0.0109989,0.185454,0.00363078,-0.00132678,0.0282495,0.00435928,-0.000223392,0.0466718,-1.24955e-05,-6.0588e-05,1.69248e-06,0,0,-0.00135657,0.204706,0.00196981,0.434395,0,0,0,0,0,7.5609e-06,4.68084e-05,4.68038e-05,0.000211987,0.0437678,0.043769,0.00908014,0.0522742,0.0522747,0.0598752,1.62015e-09,1.62082e-09,6.09403e-09,0,0,6.01399e-08,0,0,0,0,0,0,0,0
|
||||
15585000,0.98256,-0.00783254,-0.0110058,0.185453,0.00732817,-0.00477549,0.0278274,0.00633064,-0.00420308,0.0456512,-1.18183e-05,-6.05345e-05,1.97634e-06,0,0,-0.00135543,0.204706,0.00196981,0.434395,0,0,0,0,0,7.55503e-06,4.21457e-05,4.21393e-05,0.000211672,0.0382987,0.0382998,0.0090278,0.0456403,0.0456406,0.0592131,1.46981e-09,1.47035e-09,5.97422e-09,0,0,5.96958e-08,0,0,0,0,0,0,0,0
|
||||
15685000,0.98259,-0.00779931,-0.0109974,0.185297,0.00907639,-0.00796076,0.0282086,0.00713631,-0.00484125,0.0467527,-1.18122e-05,-6.05447e-05,2.39332e-06,0,0,-0.00135503,0.204706,0.00196981,0.434395,0,0,0,0,0,7.54046e-06,4.45338e-05,4.45264e-05,0.000211355,0.0430465,0.0430477,0.00912551,0.0522134,0.0522139,0.059079,1.46988e-09,1.47038e-09,5.85466e-09,0,0,5.95227e-08,0,0,0,0,0,0,0,0
|
||||
15785000,0.982628,-0.00780518,-0.0108879,0.185104,0.00585756,-0.00780901,0.0275828,0.00551852,-0.00380284,0.0479477,-1.20782e-05,-6.0707e-05,3.02472e-06,0,0,-0.00135415,0.204706,0.00196981,0.434395,0,0,0,0,0,7.52548e-06,4.00636e-05,4.00554e-05,0.000211028,0.0376797,0.0376806,0.00908661,0.045604,0.0456044,0.0584651,1.33142e-09,1.33181e-09,5.73566e-09,0,0,5.9035e-08,0,0,0,0,0,0,0,0
|
||||
15885000,0.982596,-0.00785085,-0.0109351,0.185269,0.00450019,-0.00581754,0.0287098,0.00596979,-0.00448815,0.0479994,-1.20864e-05,-6.06969e-05,2.54259e-06,0,0,-0.00135349,0.204706,0.00196981,0.434395,0,0,0,0,0,7.59014e-06,4.22866e-05,4.22775e-05,0.000212748,0.0422757,0.0422769,0.00927009,0.0521369,0.0521374,0.0592373,1.3315e-09,1.33187e-09,5.64686e-09,0,0,5.88942e-08,0,0,0,0,0,0,0,0
|
||||
15985000,0.982601,-0.00766544,-0.0108851,0.185253,0.00286255,-0.00415942,0.025183,0.00477227,-0.00345485,0.0457259,-1.22734e-05,-6.07656e-05,2.39219e-06,0,0,-0.00135129,0.204706,0.00196981,0.434395,0,0,0,0,0,7.57131e-06,3.80205e-05,3.80097e-05,0.000212383,0.037025,0.0370259,0.00923926,0.0455573,0.0455577,0.0586527,1.20466e-09,1.20495e-09,5.52899e-09,0,0,5.83632e-08,0,0,0,0,0,0,0,0
|
||||
16085000,0.982601,-0.00762876,-0.0108737,0.185255,0.00131738,-0.00531287,0.0237193,0.00491861,-0.00394774,0.0472106,-1.2281e-05,-6.07559e-05,1.93956e-06,0,0,-0.00135106,0.204706,0.00196981,0.434395,0,0,0,0,0,7.5481e-06,4.00855e-05,4.00738e-05,0.000211997,0.0414857,0.0414868,0.00936194,0.0520464,0.0520469,0.0585916,1.20473e-09,1.20499e-09,5.41194e-09,0,0,5.81514e-08,0,0,0,0,0,0,0,0
|
||||
16185000,0.982585,-0.00753944,-0.0107807,0.185346,-0.00251606,-0.00343225,0.0225582,0.00260213,-0.0029728,0.0440195,-1.25155e-05,-6.09272e-05,1.40908e-06,0,0,-0.00134923,0.204706,0.00196981,0.434395,0,0,0,0,0,7.52855e-06,3.60276e-05,3.60149e-05,0.000211585,0.0363378,0.0363386,0.00933754,0.0455009,0.0455012,0.0580519,1.08904e-09,1.08923e-09,5.29598e-09,0,0,5.75763e-08,0,0,0,0,0,0,0,0
|
||||
16285000,0.982581,-0.00759017,-0.0107109,0.185371,-0.00221686,-0.00486093,0.0220981,0.00234585,-0.00340127,0.0453723,-1.25138e-05,-6.09298e-05,1.52176e-06,0,0,-0.001349,0.204706,0.00196981,0.434395,0,0,0,0,0,7.51793e-06,3.7943e-05,3.79301e-05,0.000211135,0.0406421,0.040643,0.00946841,0.0519416,0.0519421,0.0580298,1.0891e-09,1.08928e-09,5.1811e-09,0,0,5.73412e-08,0,0,0,0,0,0,0,0
|
||||
16385000,0.982594,-0.00754211,-0.0107175,0.185305,0.000210717,-0.0039948,0.0227028,0.00341847,-0.00262925,0.0452679,-1.25386e-05,-6.07212e-05,1.92103e-06,0,0,-0.00134797,0.204706,0.00196981,0.434395,0,0,0,0,0,7.50414e-06,3.41e-05,3.40865e-05,0.000210664,0.0356165,0.0356172,0.0094474,0.045435,0.0454354,0.0575318,9.84053e-10,9.84176e-10,5.06753e-09,0,0,5.67228e-08,0,0,0,0,0,0,0,0
|
||||
16485000,0.98259,-0.00764339,-0.010701,0.185324,0.00257237,-0.00542014,0.0245585,0.0035544,-0.00316585,0.0486507,-1.25417e-05,-6.07169e-05,1.73023e-06,0,0,-0.00134826,0.204706,0.00196981,0.434395,0,0,0,0,0,7.48432e-06,3.58752e-05,3.58615e-05,0.000210166,0.0397602,0.0397612,0.0095839,0.0518229,0.0518234,0.0575479,9.8412e-10,9.84225e-10,4.95526e-09,0,0,5.64634e-08,0,0,0,0,0,0,0,0
|
||||
16585000,0.982586,-0.00762813,-0.0107056,0.185341,0.0065069,-0.00606697,0.0279726,0.00312946,-0.00246829,0.0493113,-1.26803e-05,-6.07258e-05,1.62328e-06,0,0,-0.00134745,0.204706,0.00196981,0.434395,0,0,0,0,0,7.53682e-06,3.22485e-05,3.22342e-05,0.000211684,0.0348594,0.0348603,0.00963441,0.0453597,0.0453601,0.0579145,8.8908e-10,8.8915e-10,4.87196e-09,0,0,5.58726e-08,0,0,0,0,0,0,0,0
|
||||
16685000,0.9826,-0.00768578,-0.0106398,0.18527,0.00767117,-0.00978573,0.0282461,0.00383667,-0.0032397,0.0506667,-1.26757e-05,-6.07318e-05,1.89631e-06,0,0,-0.00134703,0.204706,0.00196981,0.434395,0,0,0,0,0,7.51752e-06,3.38923e-05,3.38779e-05,0.000211115,0.0388538,0.0388548,0.00977544,0.0516905,0.051691,0.0579687,8.89146e-10,8.89201e-10,4.76222e-09,0,0,5.55929e-08,0,0,0,0,0,0,0,0
|
||||
16785000,0.982621,-0.00753587,-0.0105347,0.185172,0.00885145,-0.00946897,0.026976,0.00303176,-0.00238172,0.0497741,-1.29087e-05,-6.08045e-05,2.05111e-06,0,0,-0.0013454,0.204706,0.00196981,0.434395,0,0,0,0,0,7.49128e-06,3.0479e-05,3.04643e-05,0.000210525,0.0341094,0.0341103,0.0097521,0.0452755,0.0452759,0.0575304,8.03402e-10,8.03425e-10,4.65413e-09,0,0,5.48936e-08,0,0,0,0,0,0,0,0
|
||||
16885000,0.982665,-0.00750386,-0.0106264,0.184934,0.00756385,-0.00947439,0.0282128,0.00384405,-0.0033114,0.0489134,-1.28992e-05,-6.0817e-05,2.62408e-06,0,0,-0.00134425,0.204706,0.00196981,0.434395,0,0,0,0,0,7.46295e-06,3.20015e-05,3.19856e-05,0.000209903,0.0379477,0.0379487,0.00989422,0.0515469,0.0515473,0.05762,8.03468e-10,8.0348e-10,4.54764e-09,0,0,5.4589e-08,0,0,0,0,0,0,0,0
|
||||
16985000,0.982665,-0.00752543,-0.0106523,0.184933,0.00762503,-0.00954762,0.0283168,0.00363401,-0.00249016,0.047895,-1.30261e-05,-6.06814e-05,2.72152e-06,0,0,-0.00134289,0.204706,0.00196981,0.434395,0,0,0,0,0,7.44087e-06,2.87958e-05,2.87799e-05,0.000209239,0.03334,0.0333407,0.00986612,0.0451827,0.045183,0.0572078,7.26259e-10,7.26248e-10,4.44279e-09,0,0,5.38513e-08,0,0,0,0,0,0,0,0
|
||||
17085000,0.982655,-0.00762639,-0.0105846,0.184985,0.00847346,-0.0119635,0.0284686,0.00444374,-0.00358221,0.047669,-1.30301e-05,-6.0678e-05,2.52729e-06,0,0,-0.0013419,0.204706,0.00196981,0.434395,0,0,0,0,0,7.41641e-06,3.02043e-05,3.01886e-05,0.000208553,0.0370358,0.0370367,0.0100074,0.0513915,0.051392,0.0573297,7.26326e-10,7.26305e-10,4.33979e-09,0,0,5.3522e-08,0,0,0,0,0,0,0,0
|
||||
17185000,0.982606,-0.00772612,-0.0104877,0.185245,0.00783732,-0.0166328,0.0296029,0.00286992,-0.0071384,0.0503038,-1.29243e-05,-6.08037e-05,1.9044e-06,0,0,-0.00134135,0.204706,0.00196981,0.434395,0,0,0,0,0,7.46872e-06,2.71988e-05,2.71834e-05,0.000209841,0.0325708,0.0325715,0.0100489,0.0450814,0.0450817,0.0577715,6.56928e-10,6.56892e-10,4.26375e-09,0,0,5.28389e-08,0,0,0,0,0,0,0,0
|
||||
17285000,0.982572,-0.00767986,-0.0104829,0.185429,0.00819007,-0.0171973,0.0290735,0.0036569,-0.00879996,0.0507844,-1.29358e-05,-6.0792e-05,1.29585e-06,0,0,-0.00134057,0.204706,0.00196981,0.434395,0,0,0,0,0,7.44332e-06,2.8503e-05,2.8487e-05,0.000209083,0.0361261,0.0361269,0.0101893,0.0512258,0.0512263,0.0579268,6.56995e-10,6.56952e-10,4.16391e-09,0,0,5.24904e-08,0,0,0,0,0,0,0,0
|
||||
17385000,0.982614,-0.0075958,-0.010478,0.185207,0.00541356,-0.0173087,0.0290674,0.00516344,-0.00562716,0.051344,-1.32764e-05,-6.0528e-05,1.72786e-06,0,0,-0.00133929,0.204706,0.00196981,0.434395,0,0,0,0,0,7.40708e-06,2.56901e-05,2.56743e-05,0.000208302,0.0318066,0.0318069,0.0101475,0.0449728,0.0449731,0.0575529,5.94694e-10,5.94636e-10,4.06588e-09,0,0,5.16894e-08,0,0,0,0,0,0,0,0
|
||||
17485000,0.982601,-0.00759474,-0.0105308,0.185276,0.00305734,-0.0181563,0.0285204,0.00551966,-0.007373,0.0518013,-1.32814e-05,-6.05234e-05,1.47708e-06,0,0,-0.00133849,0.204706,0.00196981,0.434395,0,0,0,0,0,7.37854e-06,2.6898e-05,2.68815e-05,0.00020749,0.0352226,0.0352229,0.0102837,0.0510505,0.0510509,0.0577342,5.94762e-10,5.94699e-10,3.96983e-09,0,0,5.1318e-08,0,0,0,0,0,0,0,0
|
||||
17585000,0.982601,-0.00754144,-0.0104351,0.185282,-0.000319369,-0.0142899,0.0274991,0.0019783,-0.00554851,0.0498998,-1.36511e-05,-6.07198e-05,1.44742e-06,0,0,-0.00133655,0.204706,0.00196981,0.434395,0,0,0,0,0,7.34835e-06,2.42689e-05,2.42523e-05,0.00020665,0.0310471,0.0310474,0.0102339,0.0448568,0.0448571,0.0573788,5.38893e-10,5.38815e-10,3.87563e-09,0,0,5.04916e-08,0,0,0,0,0,0,0,0
|
||||
17685000,0.982628,-0.00763672,-0.0103536,0.185139,-0.00141648,-0.014892,0.0287828,0.00191204,-0.00702976,0.0522277,-1.36499e-05,-6.07211e-05,1.51421e-06,0,0,-0.00133637,0.204706,0.00196981,0.434395,0,0,0,0,0,7.3086e-06,2.53875e-05,2.53711e-05,0.000205798,0.0343241,0.0343244,0.0103646,0.0508662,0.0508665,0.0575822,5.38962e-10,5.3888e-10,3.78344e-09,0,0,5.0099e-08,0,0,0,0,0,0,0,0
|
||||
17785000,0.982672,-0.00762044,-0.010329,0.184909,0.00100198,-0.0130672,0.0285905,0.00291264,-0.00606392,0.0558749,-1.38494e-05,-6.05076e-05,1.66125e-06,0,0,-0.00133649,0.204706,0.00196981,0.434395,0,0,0,0,0,7.26228e-06,2.29325e-05,2.29165e-05,0.000204925,0.0302941,0.0302945,0.010306,0.0447339,0.0447342,0.057241,4.88893e-10,4.88802e-10,3.69314e-09,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
17885000,0.982679,-0.00756809,-0.0104355,0.184864,0.00318571,-0.0153998,0.0280818,0.0031789,-0.00750499,0.0608607,-1.38479e-05,-6.05085e-05,1.72373e-06,0,0,-0.00133722,0.204706,0.00196981,0.434395,0,0,0,0,0,7.29703e-06,2.39706e-05,2.39533e-05,0.000205953,0.0334497,0.0334501,0.0105111,0.0506737,0.050674,0.0582998,4.8897e-10,4.88878e-10,3.62669e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
17985000,0.982686,-0.00741031,-0.0104198,0.18484,0.00222615,-0.00917478,0.0278023,0.00254653,-0.00204124,0.0609591,-1.43796e-05,-6.03589e-05,1.63703e-06,0,0,-0.00133631,0.204706,0.00196981,0.434395,0,0,0,0,0,7.2592e-06,2.16796e-05,2.16623e-05,0.000205009,0.0295554,0.0295558,0.0104425,0.0446046,0.0446048,0.0579592,4.44103e-10,4.44006e-10,3.53976e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
18085000,0.982685,-0.0074949,-0.0103823,0.184843,0.00234362,-0.00976518,0.0274271,0.00284765,-0.00301724,0.0603313,-1.43803e-05,-6.03589e-05,1.62416e-06,0,0,-0.00133509,0.204706,0.00196981,0.434395,0,0,0,0,0,7.22543e-06,2.26419e-05,2.26247e-05,0.000204043,0.0325803,0.0325807,0.0105618,0.0504738,0.0504741,0.0582014,4.44174e-10,4.44075e-10,3.45484e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
18185000,0.98273,-0.00751171,-0.0104225,0.184599,0.00221635,-0.00851888,0.0281284,0.00347517,-0.00228429,0.0586432,-1.44547e-05,-6.02655e-05,2.29661e-06,0,0,-0.00133317,0.204706,0.00196981,0.434395,0,0,0,0,0,7.18712e-06,2.05058e-05,2.04886e-05,0.000203059,0.0288194,0.0288197,0.0104846,0.0444692,0.0444694,0.0578677,4.03984e-10,4.03884e-10,3.3718e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
18285000,0.982728,-0.00754738,-0.0103958,0.184611,0.00294959,-0.00930521,0.0273916,0.0036727,-0.00316124,0.057656,-1.44547e-05,-6.02664e-05,2.32823e-06,0,0,-0.00133178,0.204706,0.00196981,0.434395,0,0,0,0,0,7.15324e-06,2.13995e-05,2.13823e-05,0.000202049,0.0317248,0.0317252,0.0105959,0.050266,0.0502663,0.0581147,4.04056e-10,4.03954e-10,3.29064e-09,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
18385000,0.982704,-0.00747388,-0.0104142,0.184736,0.00356473,-0.0083451,0.0271695,0.00535626,-0.0024373,0.057255,-1.45058e-05,-6.00877e-05,2.09429e-06,0,0,-0.00133054,0.204706,0.00196981,0.434395,0,0,0,0,0,7.12096e-06,1.94084e-05,1.93912e-05,0.000201025,0.0281036,0.0281039,0.0105104,0.0443277,0.0443279,0.0577847,3.68055e-10,3.67954e-10,3.21144e-09,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
18485000,0.982714,-0.00750804,-0.0104275,0.184686,0.00637899,-0.00809514,0.0268703,0.00593685,-0.0032663,0.059864,-1.45014e-05,-6.00921e-05,2.32711e-06,0,0,-0.00133054,0.204706,0.00196981,0.434395,0,0,0,0,0,7.152e-06,2.02397e-05,2.02221e-05,0.000201848,0.0308964,0.0308969,0.0107009,0.0500526,0.0500529,0.0588981,3.68134e-10,3.68034e-10,3.1533e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
18585000,0.982687,-0.00734841,-0.0103129,0.18484,0.00515552,-0.00748762,0.0265528,0.00480495,-0.00258602,0.061526,-1.46263e-05,-6.01387e-05,2.09583e-06,0,0,-0.00132976,0.204706,0.00196981,0.434395,0,0,0,0,0,7.12008e-06,1.83835e-05,1.83662e-05,0.000200773,0.0274076,0.027408,0.0106065,0.0441813,0.0441814,0.0585592,3.35871e-10,3.35773e-10,3.07737e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
18685000,0.982702,-0.00733087,-0.0102627,0.184765,0.00469407,-0.00655633,0.025069,0.0053019,-0.00328856,0.0609321,-1.46243e-05,-6.01413e-05,2.21964e-06,0,0,-0.0013286,0.204706,0.00196981,0.434395,0,0,0,0,0,7.07922e-06,1.91569e-05,1.91395e-05,0.000199691,0.0300917,0.0300921,0.0107057,0.0498338,0.049834,0.0588233,3.35945e-10,3.35847e-10,3.00325e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
18785000,0.982704,-0.00727114,-0.0101622,0.184764,0.00369864,-0.00631462,0.0243799,0.00541381,-0.00267129,0.0575813,-1.46887e-05,-6.00988e-05,2.22059e-06,0,0,-0.0013256,0.204706,0.00196981,0.434395,0,0,0,0,0,7.0401e-06,1.74265e-05,1.74098e-05,0.000198598,0.026726,0.0267263,0.0106044,0.04403,0.0440301,0.0584829,3.07016e-10,3.06923e-10,2.931e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
18885000,0.982695,-0.00722647,-0.0101762,0.18481,0.00268919,-0.00604566,0.0228757,0.00570533,-0.00334941,0.0545251,-1.46936e-05,-6.00948e-05,1.9948e-06,0,0,-0.00132355,0.204706,0.00196981,0.434395,0,0,0,0,0,6.99917e-06,1.81476e-05,1.81304e-05,0.000197494,0.0293038,0.0293041,0.0106969,0.0496096,0.0496098,0.0587469,3.07091e-10,3.06999e-10,2.86052e-09,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
18985000,0.982673,-0.00721366,-0.0102225,0.184923,0.00125129,-0.0060592,0.0234164,0.00471865,-0.00270331,0.0573698,-1.47745e-05,-6.01137e-05,1.95011e-06,0,0,-0.00132323,0.204706,0.00196981,0.434395,0,0,0,0,0,6.96709e-06,1.65357e-05,1.65185e-05,0.000196373,0.0260644,0.0260646,0.0105896,0.0438743,0.0438744,0.0584031,2.81145e-10,2.81058e-10,2.79185e-09,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
19085000,0.982679,-0.00728882,-0.0102316,0.184887,-0.000817138,-0.00621313,0.0239055,0.0047799,-0.00327876,0.0535085,-1.47721e-05,-6.0117e-05,2.11293e-06,0,0,-0.00132091,0.204706,0.00196981,0.434395,0,0,0,0,0,6.92879e-06,1.72087e-05,1.71913e-05,0.000195247,0.0285376,0.0285377,0.0106758,0.0493816,0.0493818,0.0586644,2.81221e-10,2.81134e-10,2.72489e-09,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
19185000,0.982652,-0.00718747,-0.0103642,0.185032,-0.0020899,-0.0060532,0.0239342,0.00399504,-0.00270656,0.0535238,-1.4847e-05,-6.00976e-05,1.69032e-06,0,0,-0.00131997,0.204706,0.00196981,0.434395,0,0,0,0,0,6.95122e-06,1.57066e-05,1.56885e-05,0.000195868,0.0254179,0.025418,0.0106505,0.0437147,0.0437148,0.0591787,2.57939e-10,2.57857e-10,2.6758e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
19285000,0.982649,-0.00712793,-0.0103163,0.185053,-0.0032655,-0.00606905,0.0242826,0.00376212,-0.00331514,0.0535716,-1.48499e-05,-6.00951e-05,1.54762e-06,0,0,-0.0013191,0.204706,0.00196981,0.434395,0,0,0,0,0,6.90869e-06,1.63354e-05,1.63172e-05,0.000194712,0.0278001,0.0278001,0.0107327,0.0491496,0.0491498,0.0594427,2.58016e-10,2.57934e-10,2.6118e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
19385000,0.982643,-0.00721818,-0.0102083,0.185083,-0.00317883,-0.0025617,0.025955,0.00324328,-0.00141484,0.0523406,-1.49735e-05,-6.00375e-05,1.32799e-06,0,0,-0.00131732,0.204706,0.00196981,0.434395,0,0,0,0,0,6.86449e-06,1.49332e-05,1.49161e-05,0.000193555,0.0247906,0.0247906,0.0106144,0.0435513,0.0435514,0.0590781,2.37095e-10,2.37018e-10,2.54948e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
19485000,0.982596,-0.00726951,-0.0101113,0.185337,-0.00418261,-0.00259986,0.025231,0.00283979,-0.00167234,0.0520544,-1.49817e-05,-6.00298e-05,9.08274e-07,0,0,-0.00131624,0.204706,0.00196981,0.434395,0,0,0,0,0,6.83202e-06,1.55215e-05,1.55048e-05,0.000192379,0.0270853,0.0270853,0.0106913,0.0489141,0.0489143,0.0593352,2.37173e-10,2.37097e-10,2.48877e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
19585000,0.982573,-0.00720833,-0.0102219,0.185456,-0.00592271,-0.00523916,0.0266784,0.00347131,-0.00256926,0.0522161,-1.49115e-05,-5.99574e-05,7.83117e-07,0,0,-0.00131499,0.204706,0.00196981,0.434395,0,0,0,0,0,6.79638e-06,1.4214e-05,1.4197e-05,0.0001912,0.0241881,0.0241881,0.0105686,0.0433847,0.0433848,0.0589587,2.18359e-10,2.18289e-10,2.4296e-09,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
19685000,0.982589,-0.0072285,-0.0102362,0.185368,-0.00735467,-0.00409088,0.0259249,0.00284156,-0.00303991,0.0520519,-1.49074e-05,-5.99617e-05,1.01311e-06,0,0,-0.00131391,0.204706,0.00196981,0.434395,0,0,0,0,0,6.75471e-06,1.4766e-05,1.47487e-05,0.000190028,0.026398,0.026398,0.0106408,0.0486765,0.0486767,0.0592073,2.18439e-10,2.18369e-10,2.37204e-09,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
19785000,0.982574,-0.00730857,-0.0102417,0.185444,-0.00760111,-0.00263129,0.0247237,0.00533088,-0.00247407,0.0489953,-1.48915e-05,-5.98056e-05,8.34879e-07,0,0,-0.00131149,0.204706,0.00196981,0.434395,0,0,0,0,0,6.77317e-06,1.35449e-05,1.35282e-05,0.00019051,0.0236102,0.0236101,0.0106056,0.0432156,0.0432157,0.0597081,2.01509e-10,2.01444e-10,2.32988e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
19885000,0.982548,-0.00731687,-0.0103321,0.185578,-0.00740174,-0.00209382,0.0244662,0.00452816,-0.00266829,0.0477778,-1.48979e-05,-5.97997e-05,5.11681e-07,0,0,-0.00131013,0.204706,0.00196981,0.434395,0,0,0,0,0,6.73307e-06,1.40635e-05,1.40462e-05,0.000189312,0.0257385,0.0257384,0.0106752,0.0484378,0.0484379,0.0599547,2.01589e-10,2.01525e-10,2.27493e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
19985000,0.982569,-0.00734034,-0.0104643,0.18546,-0.00743841,-0.00193606,0.0219228,0.0049674,-0.00113565,0.0441131,-1.49444e-05,-5.96832e-05,6.10111e-07,0,0,-0.00130712,0.204706,0.00196981,0.434395,0,0,0,0,0,6.6849e-06,1.2923e-05,1.29057e-05,0.000188119,0.0230538,0.0230537,0.0105465,0.0430449,0.043045,0.0595538,1.86329e-10,1.8627e-10,2.22142e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
20085000,0.982579,-0.00734637,-0.0104751,0.185406,-0.00698817,-0.00441695,0.022026,0.00422292,-0.00147997,0.0473177,-1.49448e-05,-5.96827e-05,5.84179e-07,0,0,-0.00130748,0.204706,0.00196981,0.434395,0,0,0,0,0,6.63865e-06,1.34104e-05,1.3393e-05,0.000186928,0.0251085,0.0251084,0.0106126,0.0481984,0.0481985,0.0597901,1.86411e-10,1.86352e-10,2.16936e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
20185000,0.982557,-0.00734912,-0.0105774,0.185513,-0.00588569,-0.00255418,0.0228492,0.00537633,-0.00115518,0.0469179,-1.49579e-05,-5.96011e-05,2.50369e-07,-7.81064e-11,7.95604e-11,-0.00130621,0.204706,0.00196981,0.434395,0,0,0,0,0,6.59591e-06,1.23437e-05,1.23261e-05,0.000185732,0.0227716,0.0227717,0.0104831,0.0428728,0.0428729,0.0593832,1.7264e-10,1.72585e-10,2.11867e-09,4.00001e-06,4.00001e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20285000,0.982568,-0.00734147,-0.0106065,0.185454,-0.00901672,-0.00286919,0.0231699,0.00466315,-0.00135112,0.0476206,-1.49599e-05,-5.95992e-05,1.48541e-07,3.30905e-09,-3.3663e-09,-0.00130561,0.204706,0.00196981,0.434395,0,0,0,0,0,6.54771e-06,1.28029e-05,1.27851e-05,0.000184547,0.0257918,0.0257923,0.0105469,0.0479677,0.0479678,0.0596089,1.72723e-10,1.72668e-10,2.06937e-09,4.00002e-06,4.00002e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20385000,0.982566,-0.00729237,-0.0105989,0.18547,-0.00962049,-0.0018275,0.0222149,0.00570575,-0.00105037,0.0470927,-1.49495e-05,-5.95254e-05,4.10074e-07,-2.5527e-06,-5.36011e-08,-0.00130385,0.204706,0.00196981,0.434395,0,0,0,0,0,6.51384e-06,1.18091e-05,1.17915e-05,0.000183347,0.0247389,0.02474,0.0104182,0.0427113,0.0427114,0.0591966,1.60328e-10,1.60277e-10,2.02136e-09,3.97911e-06,3.97911e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20485000,0.982581,-0.0073051,-0.0105706,0.185388,-0.0139888,-0.00278387,0.022825,0.00450044,-0.0012573,0.0466811,-1.49518e-05,-5.95233e-05,2.93052e-07,-2.536e-06,-7.0442e-08,-0.00130284,0.204706,0.00196981,0.434395,0,0,0,0,0,6.51824e-06,1.22424e-05,1.22248e-05,0.00018371,0.0291164,0.0291185,0.0105716,0.047811,0.0478111,0.0603074,1.60415e-10,1.60365e-10,1.98622e-09,3.97912e-06,3.97912e-06,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
20585000,0.982622,-0.00727677,-0.0105781,0.185174,-0.0131457,-0.00353431,0.0224949,0.00566523,-0.0010488,0.0450846,-1.49247e-05,-5.9432e-05,7.76259e-07,-1.04065e-05,1.19492e-06,-0.00130096,0.204706,0.00196981,0.434395,0,0,0,0,0,6.47339e-06,1.13438e-05,1.13263e-05,0.000182508,0.0285741,0.0285771,0.010442,0.0426101,0.0426102,0.059878,1.49485e-10,1.49437e-10,1.94043e-09,3.90078e-06,3.90078e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
20685000,0.982609,-0.00720229,-0.0105726,0.185244,-0.0151916,-0.00252299,0.0234623,0.0042931,-0.00131077,0.0454735,-1.49317e-05,-5.94256e-05,4.22025e-07,-1.03866e-05,1.17267e-06,-0.00130027,0.204706,0.00196981,0.434395,0,0,0,0,0,6.42739e-06,1.17543e-05,1.17368e-05,0.000181315,0.0340496,0.0340542,0.0105046,0.0478218,0.047822,0.060089,1.49568e-10,1.49523e-10,1.89591e-09,3.90079e-06,3.90079e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
20785000,0.982634,-0.00674024,-0.0105101,0.185134,-0.0162511,-0.000100085,0.0111655,0.00364688,-0.0010552,0.0441177,-1.49247e-05,-5.93728e-05,5.53585e-07,-2.07282e-05,3.06293e-06,-0.00129867,0.204706,0.00196981,0.434395,0,0,0,0,0,6.38125e-06,1.09889e-05,1.09709e-05,0.000180125,0.0332243,0.0332295,0.0103764,0.0426322,0.0426324,0.0596558,1.403e-10,1.40261e-10,1.85256e-09,3.74749e-06,3.7475e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
20885000,0.982693,0.00211917,-0.00683226,0.185102,-0.0225131,0.0116014,-0.102277,0.00164123,-0.000451671,0.0385589,-1.49244e-05,-5.93729e-05,5.69359e-07,-2.06777e-05,3.01665e-06,-0.00129798,0.204706,0.00196981,0.434395,0,0,0,0,0,6.33763e-06,1.13685e-05,1.1357e-05,0.000178955,0.0396364,0.039643,0.0104365,0.048071,0.0480713,0.0598511,1.40383e-10,1.40347e-10,1.81036e-09,3.7475e-06,3.7475e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20985000,0.982693,0.00585138,-0.00310555,0.185124,-0.0313384,0.0284186,-0.243435,0.00136432,0.000116371,0.0252298,-1.48491e-05,-5.93103e-05,5.25255e-07,-3.63527e-05,2.14502e-05,-0.00130112,0.204706,0.00196981,0.434395,0,0,0,0,0,6.29709e-06,1.07573e-05,1.07592e-05,0.000177772,0.0379332,0.0379382,0.0103067,0.0428238,0.042824,0.0594152,1.32859e-10,1.32828e-10,1.76931e-09,3.52352e-06,3.52353e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21085000,0.982631,0.00442636,-0.00334905,0.18549,-0.0446362,0.0445566,-0.361104,-0.00243081,0.00381904,-0.00412968,-1.48507e-05,-5.93088e-05,4.42448e-07,-3.63768e-05,2.14717e-05,-0.00130142,0.204706,0.00196981,0.434395,0,0,0,0,0,6.32975e-06,1.11365e-05,1.11347e-05,0.000178019,0.0447212,0.0447259,0.0104553,0.0485873,0.0485877,0.0605083,1.32947e-10,1.32917e-10,1.73929e-09,3.52353e-06,3.52353e-06,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
21185000,0.982579,0.00163668,-0.00494552,0.18577,-0.0449922,0.0460167,-0.486035,-0.00117926,0.00236202,-0.037772,-1.46401e-05,-5.9227e-05,5.79627e-07,-6.41008e-05,8.08748e-05,-0.00130929,0.204706,0.00196981,0.434395,0,0,0,0,0,6.31038e-06,1.07158e-05,1.07076e-05,0.000176802,0.0415069,0.0415105,0.0103253,0.0431767,0.043177,0.0600571,1.27127e-10,1.27104e-10,1.70014e-09,3.25046e-06,3.25047e-06,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
21285000,0.982525,-0.00057601,-0.00632143,0.186021,-0.0447508,0.0491526,-0.616072,-0.00569607,0.00713553,-0.093891,-1.46464e-05,-5.92212e-05,2.6756e-07,-6.40747e-05,8.08441e-05,-0.00130894,0.204706,0.00196981,0.434395,0,0,0,0,0,6.27737e-06,1.10893e-05,1.10775e-05,0.000175603,0.0483122,0.0483163,0.0103838,0.0492678,0.0492684,0.0602393,1.27211e-10,1.27191e-10,1.66204e-09,3.25046e-06,3.25048e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
21385000,0.982479,-0.00205063,-0.00698862,0.186233,-0.0379334,0.044426,-0.740285,-0.00401091,0.00953641,-0.155475,-1.45688e-05,-5.91346e-05,1.79159e-07,-8.8395e-05,0.000101808,-0.00131505,0.204706,0.00196981,0.434395,0,0,0,0,0,6.24799e-06,1.08452e-05,1.08326e-05,0.00017441,0.0436384,0.0436424,0.0102565,0.0436264,0.0436268,0.0597872,1.22941e-10,1.22927e-10,1.62497e-09,2.95613e-06,2.95616e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
21485000,0.982454,-0.00289469,-0.00743253,0.186335,-0.0329238,0.0412092,-0.875675,-0.00762425,0.0138522,-0.240069,-1.45653e-05,-5.91374e-05,3.4755e-07,-8.82023e-05,0.000101677,-0.00131364,0.204706,0.00196981,0.434395,0,0,0,0,0,6.21793e-06,1.12125e-05,1.11995e-05,0.000173226,0.0501727,0.0501778,0.0103151,0.0499999,0.0500007,0.059961,1.23027e-10,1.23015e-10,1.5889e-09,2.95614e-06,2.95617e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21585000,0.982458,-0.00333176,-0.00742123,0.186307,-0.0244497,0.0366954,-0.998852,-0.00653387,0.0148758,-0.325274,-1.45047e-05,-5.91083e-05,4.94278e-07,-9.16215e-05,0.000100338,-0.00132158,0.204706,0.00196981,0.434395,0,0,0,0,0,6.17894e-06,1.11247e-05,1.11126e-05,0.000172062,0.0443618,0.0443665,0.0101899,0.0441018,0.0441024,0.0595089,1.20027e-10,1.2002e-10,1.55381e-09,2.66523e-06,2.66527e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21685000,0.982451,-0.00368118,-0.00727497,0.186344,-0.02143,0.0325768,-1.13224,-0.00882054,0.0183837,-0.439412,-1.44992e-05,-5.91119e-05,7.41638e-07,-9.12004e-05,0.000100067,-0.00131882,0.204706,0.00196981,0.434395,0,0,0,0,0,6.1469e-06,1.14903e-05,1.14794e-05,0.000170899,0.0504423,0.0504481,0.0102485,0.0506828,0.0506837,0.0596752,1.20113e-10,1.20108e-10,1.51964e-09,2.66523e-06,2.66528e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21785000,0.982473,-0.00405202,-0.00738817,0.186216,-0.0118592,0.02754,-1.25991,-0.00155519,0.016593,-0.552264,-1.43855e-05,-5.9041e-05,1.12046e-06,-0.000111719,9.50885e-05,-0.0013257,0.204706,0.00196981,0.434395,0,0,0,0,0,6.15586e-06,1.15325e-05,1.15218e-05,0.000171089,0.0439274,0.0439325,0.0102132,0.0445443,0.044545,0.060114,1.1808e-10,1.18077e-10,1.49464e-09,2.39447e-06,2.39452e-06,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
21885000,0.982461,-0.00433918,-0.00750732,0.186268,-0.00821644,0.023248,-1.38107,-0.00258033,0.0191757,-0.69182,-1.43903e-05,-5.9035e-05,8.48614e-07,-0.0001114,9.4848e-05,-0.00132318,0.204706,0.00196981,0.434395,0,0,0,0,0,6.11097e-06,1.19025e-05,1.18921e-05,0.000169937,0.0494637,0.0494698,0.0102729,0.051248,0.0512491,0.0602783,1.18167e-10,1.18166e-10,1.46205e-09,2.39447e-06,2.39452e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
21985000,0.982479,-0.00503103,-0.0078083,0.186141,-0.00727784,0.0190731,-1.36903,0.00122239,0.0158116,-0.826869,-1.42849e-05,-5.90003e-05,9.68594e-07,-9.34784e-05,7.16483e-05,-0.00132787,0.204706,0.00196981,0.434395,0,0,0,0,0,6.06526e-06,1.20451e-05,1.20352e-05,0.000168795,0.0426154,0.0426206,0.0101499,0.0449108,0.0449116,0.0598151,1.16818e-10,1.16819e-10,1.43034e-09,2.15238e-06,2.15245e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
22085000,0.982475,-0.005771,-0.00860215,0.186104,-0.00417131,0.0154182,-1.34971,0.000587399,0.0174911,-0.968683,-1.42789e-05,-5.90039e-05,1.23515e-06,-9.30753e-05,7.14054e-05,-0.00132556,0.204706,0.00196981,0.434395,0,0,0,0,0,6.02965e-06,1.24234e-05,1.24123e-05,0.000167649,0.0475596,0.0475659,0.0102099,0.0516379,0.0516392,0.0599732,1.16905e-10,1.16909e-10,1.39946e-09,2.15238e-06,2.15245e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
22185000,0.982494,-0.00622455,-0.00890997,0.185977,0.00162422,0.0113556,-1.36458,0.00704471,0.0127939,-1.1099,-1.41492e-05,-5.89463e-05,1.44211e-06,-8.35331e-05,4.96126e-05,-0.00132337,0.204706,0.00196981,0.434395,0,0,0,0,0,5.98669e-06,1.26432e-05,1.2632e-05,0.00016652,0.0407967,0.0408022,0.0100888,0.0451774,0.0451783,0.0595069,1.16047e-10,1.16052e-10,1.36939e-09,1.93909e-06,1.93917e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22285000,0.982479,-0.00694731,-0.00915314,0.186019,0.00758155,0.00623647,-1.36258,0.00748929,0.013712,-1.25243,-1.41511e-05,-5.89422e-05,1.29987e-06,-8.32008e-05,4.93796e-05,-0.00132122,0.204706,0.00196981,0.434395,0,0,0,0,0,5.94567e-06,1.30272e-05,1.3017e-05,0.0001654,0.0452248,0.0452315,0.0101494,0.0518671,0.0518686,0.0596595,1.16137e-10,1.16141e-10,1.34013e-09,1.93909e-06,1.93917e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22385000,0.982649,-0.0073356,-0.00935318,0.185093,0.00926933,-0.00321676,-1.36447,0.0127794,0.00393917,-1.3968,-1.40149e-05,-5.88849e-05,1.19579e-06,-5.43823e-05,4.14972e-05,-0.00131736,0.204181,0.00196475,0.434409,0,0,0,0,0,8.11398e-05,1.34282e-05,1.33439e-05,0.00230692,0.0387265,0.0387322,0.0101183,0.0453404,0.0453415,0.0600915,1.15598e-10,1.15601e-10,1.32584e-09,1.75455e-06,1.75463e-06,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
22485000,0.982339,-0.00749073,-0.00979986,0.186706,0.0137691,-0.00972613,-1.3692,0.0139153,0.00327682,-1.53811,-1.40142e-05,-5.88837e-05,1.19476e-06,-5.41193e-05,4.13234e-05,-0.00131571,0.204181,0.00196475,0.434409,0,0,0,0,0,5.69679e-05,1.34392e-05,1.33685e-05,0.0016194,0.0428696,0.0428765,0.0101796,0.0519066,0.0519083,0.0602438,1.15698e-10,1.15701e-10,1.32593e-09,1.75454e-06,1.75464e-06,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
22585000,0.982442,-0.00734698,-0.0103862,0.186132,0.0222098,-0.0162675,-1.36892,0.0256096,-0.00488522,-1.68092,-1.38666e-05,-5.88152e-05,1.19812e-06,-5.76663e-05,2.75595e-05,-0.00131301,0.204181,0.00196475,0.434409,0,0,0,0,0,4.39517e-05,1.34798e-05,1.34052e-05,0.00124759,0.0371813,0.0371875,0.0100609,0.0453749,0.0453763,0.0597706,1.15329e-10,1.15332e-10,1.32601e-09,1.58565e-06,1.58575e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
22685000,0.982385,-0.00727618,-0.0105874,0.186426,0.0244748,-0.0211135,-1.37236,0.027938,-0.00680314,-1.82478,-1.38654e-05,-5.88133e-05,1.19533e-06,-5.72749e-05,2.72982e-05,-0.00131061,0.204181,0.00196475,0.434409,0,0,0,0,0,3.57897e-05,1.35298e-05,1.34624e-05,0.00101471,0.0413683,0.0413758,0.0101235,0.0517513,0.0517534,0.0599184,1.15429e-10,1.15431e-10,1.32608e-09,1.58565e-06,1.58575e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
22785000,0.982334,-0.0072165,-0.0109752,0.186675,0.0274496,-0.0270889,-1.37645,0.0366672,-0.0161392,-1.9727,-1.36867e-05,-5.8706e-05,1.18931e-06,-3.67789e-05,4.19254e-06,-0.00130605,0.204181,0.00196475,0.434409,0,0,0,0,0,3.00933e-05,1.35762e-05,1.35109e-05,0.00085525,0.0362514,0.0362582,0.0100079,0.0452942,0.0452958,0.0594495,1.1501e-10,1.15013e-10,1.32612e-09,1.42674e-06,1.42685e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22885000,0.982492,-0.00740506,-0.011306,0.185813,0.0305036,-0.0318074,-1.3783,0.0395265,-0.019006,-2.11697,-1.3685e-05,-5.87043e-05,1.20581e-06,-3.64196e-05,3.91845e-06,-0.00130374,0.204181,0.00196475,0.434409,0,0,0,0,0,2.59199e-05,1.36507e-05,1.35907e-05,0.000739228,0.0404136,0.0404219,0.010072,0.0515222,0.0515246,0.0595937,1.1511e-10,1.15113e-10,1.32614e-09,1.42674e-06,1.42685e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22985000,0.982622,-0.00733242,-0.0116712,0.185105,0.0316155,-0.0352118,-1.38263,0.0481003,-0.0290402,-2.26916,-1.34907e-05,-5.85789e-05,1.22274e-06,-1.40167e-05,-1.98001e-05,-0.00129786,0.204181,0.00196475,0.434409,0,0,0,0,0,2.27494e-05,1.36932e-05,1.36337e-05,0.000651014,0.0356149,0.0356227,0.00995932,0.0451537,0.0451555,0.0591298,1.1452e-10,1.14523e-10,1.32613e-09,1.27964e-06,1.27974e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23085000,0.982677,-0.00734316,-0.0119929,0.184794,0.0352542,-0.0400303,-1.37994,0.0514288,-0.032832,-2.40846,-1.34905e-05,-5.85785e-05,1.2211e-06,-1.39502e-05,-1.98433e-05,-0.00129745,0.204181,0.00196475,0.434409,0,0,0,0,0,2.08059e-05,1.37868e-05,1.37275e-05,0.000597713,0.039686,0.0396954,0.0101114,0.0512693,0.0512721,0.0601626,1.14619e-10,1.14622e-10,1.32612e-09,1.27964e-06,1.27974e-06,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
23185000,0.982665,-0.00729742,-0.0121811,0.184844,0.0395683,-0.0396938,-1.38324,0.0624221,-0.0428419,-2.55574,-1.33311e-05,-5.84591e-05,1.20447e-06,-4.51184e-07,-3.31467e-05,-0.00129313,0.204181,0.00196475,0.434409,0,0,0,0,0,1.87e-05,1.38206e-05,1.37643e-05,0.000538867,0.0350556,0.0350648,0.00999936,0.0449906,0.0449927,0.0596904,1.1382e-10,1.13824e-10,1.32605e-09,1.14593e-06,1.14602e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
23285000,0.982712,-0.00777067,-0.0123127,0.184567,0.0432512,-0.0442663,-1.37917,0.0664942,-0.0470845,-2.69998,-1.33294e-05,-5.84572e-05,1.21203e-06,-1.1822e-07,-3.34038e-05,-0.00129096,0.204181,0.00196475,0.434409,0,0,0,0,0,1.69953e-05,1.39246e-05,1.38756e-05,0.000490647,0.0389791,0.0389901,0.0100669,0.0510206,0.0510238,0.0598338,1.1392e-10,1.13923e-10,1.32593e-09,1.14592e-06,1.14602e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
23385000,0.982675,-0.00773462,-0.0124218,0.184761,0.0470008,-0.0427723,-1.38057,0.0773421,-0.0509405,-2.8407,-1.31308e-05,-5.83913e-05,1.17672e-06,-5.91708e-07,-6.54615e-05,-0.00128955,0.204181,0.00196475,0.434409,0,0,0,0,0,1.55685e-05,1.39551e-05,1.39088e-05,0.000450443,0.0344417,0.0344514,0.00995759,0.0448264,0.0448288,0.0593676,1.12929e-10,1.12933e-10,1.32576e-09,1.02659e-06,1.02667e-06,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
23485000,0.982722,-0.00782656,-0.0126921,0.184487,0.0502716,-0.0440384,-1.38222,0.0821665,-0.0553131,-2.98441,-1.31288e-05,-5.83899e-05,1.20034e-06,-3.2027e-07,-6.57109e-05,-0.00128756,0.204181,0.00196475,0.434409,0,0,0,0,0,1.43882e-05,1.40766e-05,1.40316e-05,0.000416395,0.0381799,0.0381915,0.0100254,0.0507875,0.0507911,0.059504,1.13029e-10,1.13033e-10,1.32555e-09,1.02658e-06,1.02667e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23585000,0.982747,-0.00807587,-0.0126313,0.184346,0.0500133,-0.0463651,-1.38168,0.0889742,-0.065885,-3.13026,-1.30146e-05,-5.82642e-05,1.21221e-06,2.06867e-05,-7.29933e-05,-0.00128473,0.204181,0.00196475,0.434409,0,0,0,0,0,1.3373e-05,1.41069e-05,1.40672e-05,0.000387222,0.0337061,0.0337164,0.00991853,0.0446703,0.044673,0.0590442,1.11893e-10,1.11897e-10,1.32528e-09,9.21904e-07,9.21979e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
23685000,0.982754,-0.00870684,-0.0131282,0.184246,0.0475989,-0.0483409,-1.28572,0.0938695,-0.0706857,-3.26825,-1.30134e-05,-5.82635e-05,1.22837e-06,2.08251e-05,-7.31279e-05,-0.00128366,0.204181,0.00196475,0.434409,0,0,0,0,0,1.27163e-05,1.42471e-05,1.42087e-05,0.000368069,0.0371609,0.0371724,0.0100741,0.0505693,0.0505733,0.0600741,1.11992e-10,1.11997e-10,1.32506e-09,9.21906e-07,9.21984e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
23785000,0.982743,-0.0104846,-0.0158123,0.184003,0.0431805,-0.0430459,-0.968442,0.104033,-0.074715,-3.39112,-1.28614e-05,-5.82296e-05,1.26618e-06,1.72372e-05,-9.26831e-05,-0.00127917,0.204181,0.00196475,0.434409,0,0,0,0,0,1.1934e-05,1.43142e-05,1.42629e-05,0.000345209,0.0325778,0.0325875,0.00996749,0.0445213,0.0445243,0.0596071,1.10761e-10,1.10766e-10,1.32468e-09,8.31265e-07,8.31329e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
23885000,0.98265,-0.0138296,-0.0199451,0.183873,0.0376948,-0.0422756,-0.537896,0.108044,-0.0789339,-3.46951,-1.28606e-05,-5.82285e-05,1.26524e-06,1.73993e-05,-9.2806e-05,-0.0012781,0.204181,0.00196475,0.434409,0,0,0,0,0,1.12285e-05,1.45101e-05,1.44397e-05,0.00032509,0.0355629,0.0355748,0.0100386,0.050344,0.0503484,0.0597464,1.10861e-10,1.10865e-10,1.32424e-09,8.31263e-07,8.31333e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
23985000,0.982584,-0.0160929,-0.0224334,0.183759,0.0394343,-0.0391198,-0.153725,0.116872,-0.0809979,-3.53795,-1.27317e-05,-5.81949e-05,1.26322e-06,1.37957e-05,-0.00010937,-0.00125463,0.204181,0.00196475,0.434409,0,0,0,0,0,1.05984e-05,1.46119e-05,1.45323e-05,0.000307291,0.0311387,0.0311498,0.00993511,0.0443681,0.0443714,0.0592866,1.09534e-10,1.09539e-10,1.32373e-09,7.52443e-07,7.52502e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
24085000,0.982611,-0.0157343,-0.0215104,0.183756,0.0448348,-0.0464812,0.0905898,0.121028,-0.0852365,-3.54135,-1.27315e-05,-5.81933e-05,1.23369e-06,1.39576e-05,-0.00010946,-0.00125387,0.204181,0.00196475,0.434409,0,0,0,0,0,1.00374e-05,1.47603e-05,1.46923e-05,0.000291489,0.0339731,0.033987,0.010008,0.0501023,0.0501072,0.0594259,1.09633e-10,1.09638e-10,1.32314e-09,7.52441e-07,7.52506e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
24185000,0.982728,-0.0129508,-0.0178554,0.183735,0.0560275,-0.0511634,0.0829637,0.129247,-0.0900846,-3.55764,-1.26608e-05,-5.81487e-05,1.262e-06,1.56334e-05,-0.000116348,-0.00123497,0.204181,0.00196475,0.434409,0,0,0,0,0,9.55318e-06,1.48176e-05,1.47703e-05,0.000277351,0.0299511,0.0299633,0.00990615,0.0442056,0.0442093,0.0589732,1.08273e-10,1.08279e-10,1.32247e-09,6.84578e-07,6.84634e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
24285000,0.982824,-0.010512,-0.0143776,0.183684,0.0588974,-0.0542092,0.05777,0.135038,-0.0954076,-3.55385,-1.26598e-05,-5.81479e-05,1.2718e-06,1.5755e-05,-0.000116458,-0.00123405,0.204181,0.00196475,0.434409,0,0,0,0,0,9.11041e-06,1.49661e-05,1.49357e-05,0.000264607,0.0327061,0.0327198,0.00997893,0.049859,0.0498644,0.0591131,1.08373e-10,1.08378e-10,1.32172e-09,6.84577e-07,6.84638e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
24385000,0.982888,-0.0095944,-0.0132956,0.183475,0.0535062,-0.0476355,0.0742226,0.142972,-0.0960516,-3.55009,-1.25669e-05,-5.81727e-05,1.31462e-06,8.64886e-06,-0.000130857,-0.00123294,0.204181,0.00196475,0.434409,0,0,0,0,0,8.8095e-06,1.50669e-05,1.50401e-05,0.000256024,0.0288252,0.0288361,0.00996175,0.0440376,0.0440417,0.0595406,1.07089e-10,1.07094e-10,1.32113e-09,6.2776e-07,6.27812e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
24485000,0.982928,-0.00981431,-0.0133634,0.183245,0.0476512,-0.042947,0.0723698,0.148012,-0.100569,-3.54222,-1.25656e-05,-5.81748e-05,1.39301e-06,8.52254e-06,-0.000130858,-0.00123309,0.204181,0.00196475,0.434409,0,0,0,0,0,8.44373e-06,1.52613e-05,1.52357e-05,0.000245254,0.0313582,0.0313703,0.0100359,0.0496044,0.0496101,0.0596852,1.07188e-10,1.07193e-10,1.32023e-09,6.27758e-07,6.27816e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
24585000,0.982886,-0.0105138,-0.0134737,0.18342,0.0457265,-0.0374183,0.0677499,0.153335,-0.0976709,-3.53652,-1.24836e-05,-5.82298e-05,1.39079e-06,-7.59536e-07,-0.000146102,-0.00123197,0.204181,0.00196475,0.434409,0,0,0,0,0,8.1224e-06,1.53795e-05,1.53571e-05,0.000235426,0.0276563,0.0276659,0.00993488,0.0438605,0.0438648,0.0592333,1.06006e-10,1.06011e-10,1.31923e-09,5.80547e-07,5.806e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
24685000,0.98287,-0.0110286,-0.013308,0.183488,0.0422608,-0.0358315,0.0668989,0.157785,-0.101268,-3.52972,-1.24837e-05,-5.82297e-05,1.3855e-06,-7.51579e-07,-0.000146104,-0.00123196,0.204181,0.00196475,0.434409,0,0,0,0,0,7.81926e-06,1.55864e-05,1.5568e-05,0.000226454,0.0299904,0.0300009,0.0100095,0.0493333,0.0493393,0.0593787,1.06105e-10,1.0611e-10,1.31814e-09,5.80546e-07,5.80604e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
24785000,0.982895,-0.0111766,-0.0126751,0.183388,0.039968,-0.0327493,0.0592132,0.161296,-0.0978645,-3.52724,-1.2421e-05,-5.82472e-05,1.39844e-06,-4.26296e-06,-0.000158684,-0.00123107,0.204181,0.00196475,0.434409,0,0,0,0,0,7.53076e-06,1.57096e-05,1.56958e-05,0.000218241,0.0264692,0.0264775,0.00990911,0.0436702,0.0436747,0.0589285,1.05047e-10,1.05052e-10,1.31695e-09,5.41671e-07,5.41726e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
24885000,0.982898,-0.0110196,-0.0121689,0.183419,0.0369756,-0.0352945,0.0489027,0.165165,-0.101273,-3.52408,-1.24197e-05,-5.82469e-05,1.42683e-06,-4.17677e-06,-0.000158787,-0.00123027,0.204181,0.00196475,0.434409,0,0,0,0,0,7.27887e-06,1.59291e-05,1.59173e-05,0.000210677,0.028624,0.028633,0.00998383,0.0490419,0.0490479,0.0590747,1.05146e-10,1.05151e-10,1.31565e-09,5.4167e-07,5.41729e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
24985000,0.982879,-0.010823,-0.0119398,0.183545,0.0299354,-0.0298431,0.0414481,0.166536,-0.0932132,-3.52158,-1.23352e-05,-5.82894e-05,1.42936e-06,-1.0219e-05,-0.000176696,-0.0012298,0.204181,0.00196475,0.434409,0,0,0,0,0,7.11544e-06,1.60639e-05,1.60521e-05,0.000205627,0.0252896,0.0252966,0.00996935,0.0434638,0.0434683,0.0595091,1.04225e-10,1.0423e-10,1.31463e-09,5.09935e-07,5.09992e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
25085000,0.982877,-0.0111612,-0.0120003,0.183534,0.0257517,-0.0284278,0.0383428,0.169247,-0.0961721,-3.52339,-1.23332e-05,-5.82866e-05,1.41667e-06,-9.91309e-06,-0.000176945,-0.00122777,0.204181,0.00196475,0.434409,0,0,0,0,0,6.88691e-06,1.63e-05,1.62892e-05,0.000199071,0.0272698,0.0272775,0.0100454,0.0487282,0.048734,0.0596607,1.04324e-10,1.04328e-10,1.31315e-09,5.09934e-07,5.09995e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
25185000,0.982827,-0.01141,-0.0118546,0.183794,0.0228197,-0.0223834,0.0383973,0.17135,-0.0894296,-3.52109,-1.23e-05,-5.83393e-05,1.37634e-06,-1.71765e-05,-0.000187055,-0.00122655,0.204181,0.00196475,0.434409,0,0,0,0,0,6.69082e-06,1.6443e-05,1.64336e-05,0.00019299,0.024122,0.0241281,0.0099459,0.0432395,0.0432439,0.0592111,1.03542e-10,1.03546e-10,1.31155e-09,4.84207e-07,4.84267e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
25285000,0.982779,-0.011559,-0.0112148,0.184082,0.0167839,-0.0229561,0.033182,0.173295,-0.0916753,-3.51852,-1.23013e-05,-5.83369e-05,1.28788e-06,-1.70577e-05,-0.000187082,-0.00122624,0.204181,0.00196475,0.434409,0,0,0,0,0,6.50536e-06,1.66894e-05,1.66834e-05,0.00018736,0.0259499,0.0259566,0.0100221,0.0483912,0.0483968,0.0593636,1.03641e-10,1.03645e-10,1.30983e-09,4.84207e-07,4.8427e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
25385000,0.98278,-0.0117161,-0.0110327,0.18408,0.0101245,-0.0158581,0.0314973,0.170665,-0.0818081,-3.51937,-1.22298e-05,-5.83665e-05,1.29474e-06,-1.99299e-05,-0.000202417,-0.00122413,0.204181,0.00196475,0.434409,0,0,0,0,0,6.32544e-06,1.68398e-05,1.68347e-05,0.000182136,0.0229941,0.0229994,0.00992378,0.0429964,0.0430006,0.0589208,1.02995e-10,1.02999e-10,1.30799e-09,4.63511e-07,4.63574e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
25485000,0.98277,-0.0117607,-0.0107357,0.184145,0.00388295,-0.0143513,0.0305967,0.171303,-0.0833152,-3.51802,-1.22297e-05,-5.8365e-05,1.26037e-06,-1.98166e-05,-0.000202492,-0.00122353,0.204181,0.00196475,0.434409,0,0,0,0,0,6.15844e-06,1.71011e-05,1.70971e-05,0.000177279,0.0246805,0.0246863,0.01,0.0480319,0.0480371,0.0590742,1.03094e-10,1.03097e-10,1.30604e-09,4.63511e-07,4.63577e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
25585000,0.982756,-0.0119992,-0.0105617,0.184217,0.00050284,-0.012242,0.0323852,0.169166,-0.0774822,-3.51638,-1.2226e-05,-5.83856e-05,1.21559e-06,-2.18128e-05,-0.000208018,-0.00122287,0.204181,0.00196475,0.434409,0,0,0,0,0,6.00235e-06,1.72581e-05,1.72548e-05,0.000172754,0.0219115,0.0219161,0.00990252,0.0427349,0.0427389,0.0586379,1.02578e-10,1.02582e-10,1.30395e-09,4.46992e-07,4.47058e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
25685000,0.982768,-0.0114794,-0.0102626,0.184204,-0.000887212,-0.0112687,0.0215104,0.169144,-0.078691,-3.51647,-1.22245e-05,-5.83847e-05,1.23345e-06,-2.16781e-05,-0.000208152,-0.00122188,0.204181,0.00196475,0.434409,0,0,0,0,0,5.90326e-06,1.75328e-05,1.75282e-05,0.000169854,0.0234809,0.0234855,0.0100631,0.0476521,0.0476569,0.0596692,1.02677e-10,1.0268e-10,1.30233e-09,4.46994e-07,4.47063e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
25785000,0.982785,-0.0112891,-0.00957331,0.184158,-0.0103867,-0.00467776,0.0202839,0.163599,-0.0713742,-3.51934,-1.2195e-05,-5.83976e-05,1.23666e-06,-2.14553e-05,-0.000216397,-0.00121982,0.204181,0.00196475,0.434409,0,0,0,0,0,5.76222e-06,1.76927e-05,1.76891e-05,0.000165858,0.0208947,0.0208986,0.00996475,0.0424564,0.04246,0.0592263,1.02283e-10,1.02286e-10,1.30001e-09,4.33938e-07,4.34007e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
25885000,0.982753,-0.0113524,-0.00962085,0.184326,-0.0173386,-0.00219472,0.0226854,0.162147,-0.0716939,-3.51813,-1.21971e-05,-5.83942e-05,1.10004e-06,-2.13266e-05,-0.000216431,-0.00121949,0.204181,0.00196475,0.434409,0,0,0,0,0,5.63229e-06,1.7981e-05,1.79769e-05,0.000162121,0.0223473,0.0223515,0.0100418,0.0472546,0.0472589,0.0593859,1.02382e-10,1.02384e-10,1.29758e-09,4.33938e-07,4.34009e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
25985000,0.982745,-0.0114884,-0.0097957,0.184351,-0.0251304,0.0023088,0.0159091,0.152059,-0.0649436,-3.51839,-1.21706e-05,-5.83716e-05,1.07188e-06,-1.66661e-05,-0.000223895,-0.00121822,0.204181,0.00196475,0.434409,0,0,0,0,0,5.51132e-06,1.81472e-05,1.8142e-05,0.000158623,0.0199398,0.0199432,0.00994402,0.0421625,0.0421658,0.0589491,1.02096e-10,1.02098e-10,1.29499e-09,4.23713e-07,4.23783e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
26085000,0.982777,-0.0111922,-0.00975227,0.184199,-0.0304327,0.0032127,0.0142734,0.149258,-0.0646571,-3.5188,-1.21683e-05,-5.83724e-05,1.15004e-06,-1.66047e-05,-0.000223997,-0.00121753,0.204181,0.00196475,0.434409,0,0,0,0,0,5.39579e-06,1.84476e-05,1.84409e-05,0.000155355,0.0213004,0.0213041,0.0100198,0.0468426,0.0468465,0.0591039,1.02194e-10,1.02196e-10,1.29228e-09,4.23713e-07,4.23785e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
26185000,0.982772,-0.0111746,-0.0102826,0.184196,-0.0358793,0.00656753,0.00982489,0.140696,-0.0608748,-3.52216,-1.21676e-05,-5.83681e-05,1.20479e-06,-1.41026e-05,-0.000226896,-0.00121571,0.204181,0.00196475,0.434409,0,0,0,0,0,5.29431e-06,1.86159e-05,1.86062e-05,0.000152282,0.0190556,0.0190585,0.00992271,0.0418558,0.0418587,0.058673,1.02004e-10,1.02005e-10,1.28942e-09,4.15806e-07,4.15877e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
26285000,0.98277,-0.0112426,-0.010598,0.184189,-0.0375432,0.00798828,0.00386299,0.137009,-0.0601819,-3.52329,-1.21679e-05,-5.83658e-05,1.13658e-06,-1.3976e-05,-0.000226988,-0.00121507,0.204181,0.00196475,0.434409,0,0,0,0,0,5.2267e-06,1.89295e-05,1.89184e-05,0.000150446,0.0203382,0.020341,0.0100839,0.0464199,0.0464233,0.059712,1.02102e-10,1.02104e-10,1.28721e-09,4.15808e-07,4.1588e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
26385000,0.9828,-0.0107382,-0.010576,0.184056,-0.0429043,0.0124573,0.00695542,0.124753,-0.0552527,-3.52332,-1.21532e-05,-5.83397e-05,1.09358e-06,-9.13117e-06,-0.000231505,-0.00121492,0.204181,0.00196475,0.434409,0,0,0,0,0,5.12293e-06,1.90946e-05,1.9081e-05,0.000147723,0.0182432,0.0182452,0.00998535,0.041539,0.0415415,0.0592738,1.01993e-10,1.01994e-10,1.2841e-09,4.09776e-07,4.09847e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
26485000,0.982808,-0.0104936,-0.0104682,0.184035,-0.0462604,0.0155475,0.0160522,0.120298,-0.0538742,-3.52222,-1.2154e-05,-5.83387e-05,1.04648e-06,-9.1096e-06,-0.000231508,-0.00121491,0.204181,0.00196475,0.434409,0,0,0,0,0,5.03124e-06,1.94185e-05,1.9404e-05,0.000145164,0.0194453,0.0194472,0.0100615,0.0459898,0.0459927,0.0594341,1.02091e-10,1.02092e-10,1.28086e-09,4.09776e-07,4.09847e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
26585000,0.982794,-0.0100082,-0.0107474,0.184121,-0.0466612,0.0205936,0.0164134,0.111753,-0.0498518,-3.52252,-1.2142e-05,-5.8326e-05,9.81954e-07,-6.86985e-06,-0.000234387,-0.00121332,0.204181,0.00196475,0.434409,0,0,0,0,0,4.95004e-06,1.95818e-05,1.9564e-05,0.000142755,0.017497,0.0174981,0.00996334,0.0412147,0.0412168,0.0590015,1.02046e-10,1.02046e-10,1.27746e-09,4.05232e-07,4.053e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
26685000,0.982786,-0.00988843,-0.0104591,0.184188,-0.0485981,0.0254452,0.0155548,0.106976,-0.0475499,-3.52103,-1.2144e-05,-5.83234e-05,8.59488e-07,-6.81675e-06,-0.0002344,-0.00121327,0.204181,0.00196475,0.434409,0,0,0,0,0,4.86989e-06,1.99164e-05,1.98989e-05,0.000140499,0.0186483,0.018649,0.0100391,0.0455565,0.0455589,0.0591619,1.02144e-10,1.02144e-10,1.27392e-09,4.05231e-07,4.05299e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
26785000,0.982806,-0.00973492,-0.00995513,0.184115,-0.0538268,0.026561,0.0141969,0.0958795,-0.0453435,-3.52375,-1.21248e-05,-5.82977e-05,8.15112e-07,-2.64818e-06,-0.000236943,-0.00121137,0.204181,0.00196475,0.434409,0,0,0,0,0,4.79141e-06,2.00706e-05,2.00538e-05,0.000138383,0.0168344,0.0168348,0.00994139,0.0408863,0.040888,0.0587344,1.02145e-10,1.02146e-10,1.27022e-09,4.01868e-07,4.01932e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
26885000,0.982836,-0.00913357,-0.0100463,0.18398,-0.0595805,0.0292207,0.00983072,0.0901737,-0.0425584,-3.52305,-1.21228e-05,-5.82995e-05,9.148e-07,-2.65134e-06,-0.00023697,-0.00121117,0.204181,0.00196475,0.434409,0,0,0,0,0,4.72149e-06,2.04178e-05,2.03986e-05,0.000136391,0.0179408,0.0179412,0.0100168,0.0451246,0.0451265,0.0588948,1.02243e-10,1.02244e-10,1.26639e-09,4.01868e-07,4.01931e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
26985000,0.982829,-0.00865812,-0.0105396,0.184014,-0.0652972,0.0328735,0.0078529,0.0788846,-0.0391151,-3.52755,-1.20919e-05,-5.82738e-05,8.61081e-07,8.65242e-07,-0.000240303,-0.00120879,0.204181,0.00196475,0.434409,0,0,0,0,0,4.68609e-06,2.05657e-05,2.0543e-05,0.000135352,0.0162498,0.01625,0.0100029,0.0405575,0.0405588,0.0593397,1.02276e-10,1.02277e-10,1.26342e-09,3.99422e-07,3.99479e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
27085000,0.982829,-0.00848822,-0.0108751,0.184004,-0.06749,0.0400223,0.0116874,0.0721728,-0.0354534,-3.53094,-1.20898e-05,-5.82712e-05,8.38843e-07,1.10978e-06,-0.00024056,-0.0012072,0.204181,0.00196475,0.434409,0,0,0,0,0,4.62429e-06,2.09241e-05,2.08994e-05,0.00013357,0.0173101,0.0173097,0.0100788,0.0446982,0.0446996,0.0595047,1.02373e-10,1.02374e-10,1.25932e-09,3.99421e-07,3.99478e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
27185000,0.982835,-0.00856313,-0.0107887,0.183971,-0.0723113,0.0430938,0.0129309,0.0627114,-0.0319473,-3.53343,-1.20543e-05,-5.82513e-05,8.19989e-07,3.37968e-06,-0.000243317,-0.00120575,0.204181,0.00196475,0.434409,0,0,0,0,0,4.56514e-06,2.10574e-05,2.10326e-05,0.000131894,0.0157297,0.0157291,0.0099801,0.0402315,0.0402325,0.0590743,1.02417e-10,1.02419e-10,1.25506e-09,3.97657e-07,3.97707e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
27285000,0.982842,-0.00873013,-0.0117131,0.183868,-0.0789069,0.0489462,0.115778,0.055192,-0.0273587,-3.53157,-1.20527e-05,-5.82502e-05,8.27427e-07,3.52598e-06,-0.000243479,-0.00120475,0.204181,0.00196475,0.434409,0,0,0,0,0,4.50772e-06,2.14279e-05,2.13995e-05,0.000130321,0.0166677,0.0166669,0.0100555,0.0442797,0.0442807,0.059239,1.02515e-10,1.02516e-10,1.25066e-09,3.97657e-07,3.97705e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
27385000,0.982802,-0.0100955,-0.0141984,0.183839,-0.082357,0.0536285,0.431627,0.0472975,-0.0223341,-3.51336,-1.20041e-05,-5.82084e-05,8.41011e-07,6.60516e-06,-0.000247059,-0.00119984,0.204181,0.00196475,0.434409,0,0,0,0,0,4.45817e-06,2.15627e-05,2.15271e-05,0.000128828,0.0149216,0.0149207,0.00995545,0.0399042,0.0399049,0.0588078,1.02558e-10,1.02559e-10,1.24609e-09,3.96386e-07,3.96425e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
27485000,0.982746,-0.0115367,-0.0161732,0.183893,-0.0853735,0.0591354,0.750703,0.038865,-0.0166794,-3.45573,-1.20045e-05,-5.82047e-05,7.18761e-07,6.77534e-06,-0.000247242,-0.00119891,0.204181,0.00196475,0.434409,0,0,0,0,0,4.41113e-06,2.19472e-05,2.19058e-05,0.000127429,0.0156224,0.015621,0.0100299,0.0438374,0.0438381,0.0589718,1.02655e-10,1.02657e-10,1.24138e-09,3.96386e-07,3.96422e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
27585000,0.982767,-0.0115535,-0.0151948,0.183858,-0.0784466,0.0599324,0.855298,0.0318218,-0.0146415,-3.39498,-1.19327e-05,-5.81609e-05,7.28602e-07,1.04671e-05,-0.000251565,-0.00118377,0.204181,0.00196475,0.434409,0,0,0,0,0,4.39004e-06,2.2098e-05,2.2061e-05,0.000126861,0.0142014,0.0141993,0.0100152,0.0395588,0.0395592,0.0594201,1.02707e-10,1.0271e-10,1.23776e-09,3.9546e-07,3.95488e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
27685000,0.982837,-0.010408,-0.0123048,0.183771,-0.0746752,0.0558446,0.762333,0.0242047,-0.00878954,-3.31686,-1.19299e-05,-5.81602e-05,7.7444e-07,1.06448e-05,-0.000251777,-0.0011825,0.204181,0.00196475,0.434409,0,0,0,0,0,4.34411e-06,2.24749e-05,2.24467e-05,0.000125636,0.0152295,0.0152275,0.0100904,0.0433963,0.0433965,0.0595883,1.02805e-10,1.02807e-10,1.2328e-09,3.9546e-07,3.95485e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
27785000,0.982873,-0.00908459,-0.0107252,0.183748,-0.0726391,0.0510949,0.749732,0.0192971,-0.00825255,-3.24306,-1.18785e-05,-5.81383e-05,8.42908e-07,1.17392e-05,-0.000253221,-0.00118364,0.204181,0.00196475,0.434409,0,0,0,0,0,4.30547e-06,2.26031e-05,2.25772e-05,0.000124473,0.0140051,0.0140034,0.00998939,0.0392221,0.0392223,0.0591531,1.02822e-10,1.02825e-10,1.22766e-09,3.94759e-07,3.94773e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
27885000,0.98287,-0.00869836,-0.0108057,0.183776,-0.0790058,0.0568517,0.791393,0.011728,-0.00290538,-3.16841,-1.18764e-05,-5.81372e-05,8.57632e-07,1.18912e-05,-0.000253404,-0.00118259,0.204181,0.00196475,0.434409,0,0,0,0,0,4.27071e-06,2.29998e-05,2.29723e-05,0.000123377,0.0149129,0.014911,0.0100644,0.0429885,0.0429884,0.0593204,1.02919e-10,1.02922e-10,1.22239e-09,3.94759e-07,3.9477e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
27985000,0.98287,-0.00916671,-0.0111981,0.183733,-0.0786756,0.0570641,0.778703,0.00751927,-0.00282252,-3.09805,-1.17935e-05,-5.8092e-05,8.8162e-07,1.44437e-05,-0.000256925,-0.00117793,0.204181,0.00196475,0.434409,0,0,0,0,0,4.23538e-06,2.31089e-05,2.30808e-05,0.000122346,0.0137648,0.013763,0.00996416,0.0389068,0.0389067,0.0588895,1.02886e-10,1.02891e-10,1.21696e-09,3.94183e-07,3.94182e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
28085000,0.982894,-0.00950038,-0.0112068,0.183588,-0.0820022,0.0570841,0.784935,-0.000473691,0.00292204,-3.0203,-1.17903e-05,-5.80953e-05,1.05066e-06,1.44262e-05,-0.000256936,-0.00117781,0.204181,0.00196475,0.434409,0,0,0,0,0,4.20226e-06,2.35138e-05,2.34859e-05,0.000121384,0.0147078,0.0147061,0.0100384,0.0426092,0.0426088,0.0590558,1.02983e-10,1.02988e-10,1.2114e-09,3.94183e-07,3.94178e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
28185000,0.982897,-0.00901274,-0.0115134,0.183574,-0.0812717,0.0520267,0.790756,-0.00619739,0.00197372,-2.94609,-1.16997e-05,-5.80589e-05,1.06585e-06,1.66391e-05,-0.000260736,-0.00117532,0.204181,0.00196475,0.434409,0,0,0,0,0,4.17197e-06,2.35899e-05,2.35597e-05,0.000120476,0.0136085,0.0136072,0.00993809,0.0386143,0.038614,0.058629,1.02876e-10,1.02884e-10,1.20567e-09,3.93617e-07,3.93601e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
28285000,0.982919,-0.00850158,-0.0118076,0.183465,-0.0861278,0.0545659,0.79132,-0.0145215,0.00735061,-2.86945,-1.16959e-05,-5.80604e-05,1.19394e-06,1.67453e-05,-0.000260889,-0.00117441,0.204181,0.00196475,0.434409,0,0,0,0,0,4.16573e-06,2.40041e-05,2.39713e-05,0.000120292,0.0145638,0.0145626,0.0100971,0.0422626,0.042262,0.0596713,1.02974e-10,1.02981e-10,1.20132e-09,3.9362e-07,3.936e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
28385000,0.982909,-0.00855145,-0.0124521,0.183469,-0.0858548,0.0562132,0.792309,-0.0183865,0.00924605,-2.79668,-1.15991e-05,-5.79887e-05,1.34868e-06,2.04168e-05,-0.000265301,-0.00117177,0.204181,0.00196475,0.434409,0,0,0,0,0,4.14408e-06,2.40432e-05,2.40081e-05,0.00011948,0.0135257,0.0135247,0.00999577,0.0383477,0.0383472,0.0592358,1.02774e-10,1.02784e-10,1.19534e-09,3.92973e-07,3.92942e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
28485000,0.982907,-0.00887583,-0.0129568,0.183431,-0.0869327,0.0585593,0.793429,-0.0269919,0.0149599,-2.72203,-1.15961e-05,-5.79868e-05,1.35927e-06,2.06476e-05,-0.000265591,-0.00117015,0.204181,0.00196475,0.434409,0,0,0,0,0,4.11821e-06,2.44646e-05,2.44278e-05,0.000118728,0.0144918,0.0144907,0.01007,0.0419529,0.0419522,0.0594048,1.02871e-10,1.0288e-10,1.18924e-09,3.92974e-07,3.92937e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
28585000,0.982943,-0.00899088,-0.0129467,0.183232,-0.0799717,0.0529598,0.790749,-0.0296322,0.0117208,-2.64651,-1.14474e-05,-5.79305e-05,1.48159e-06,2.3528e-05,-0.000271836,-0.00116849,0.204181,0.00196475,0.434409,0,0,0,0,0,4.08954e-06,2.4458e-05,2.44215e-05,0.000118026,0.0135045,0.0135036,0.0099685,0.0381105,0.0381099,0.0589734,1.02558e-10,1.0257e-10,1.18298e-09,3.92163e-07,3.92114e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
28685000,0.98294,-0.00879032,-0.0123405,0.1833,-0.0794224,0.0528746,0.791587,-0.0375881,0.0170386,-2.57146,-1.1445e-05,-5.79284e-05,1.47372e-06,2.37393e-05,-0.000272104,-0.00116702,0.204181,0.00196475,0.434409,0,0,0,0,0,4.0703e-06,2.48823e-05,2.48472e-05,0.000117367,0.014487,0.0144862,0.0100411,0.0416832,0.0416823,0.0591356,1.02654e-10,1.02667e-10,1.1766e-09,3.92164e-07,3.9211e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
28785000,0.982964,-0.00818291,-0.0121726,0.183213,-0.0747307,0.0518557,0.790158,-0.0395318,0.0181463,-2.49927,-1.13332e-05,-5.78361e-05,1.64842e-06,2.84446e-05,-0.000277281,-0.00116354,0.204181,0.00196475,0.434409,0,0,0,0,0,4.05055e-06,2.48258e-05,2.47906e-05,0.000116749,0.0135326,0.0135321,0.00994015,0.0379049,0.0379042,0.058708,1.02208e-10,1.02225e-10,1.17007e-09,3.91116e-07,3.9105e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
28885000,0.982993,-0.00800703,-0.0119152,0.183079,-0.0783357,0.0526977,0.78946,-0.0471526,0.0233644,-2.42315,-1.13289e-05,-5.78368e-05,1.76326e-06,2.85991e-05,-0.000277491,-0.00116251,0.204181,0.00196475,0.434409,0,0,0,0,0,4.05032e-06,2.52565e-05,2.52218e-05,0.000116802,0.0145366,0.0145363,0.0100987,0.0414551,0.0414542,0.0597538,1.02305e-10,1.02323e-10,1.16513e-09,3.91119e-07,3.91049e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
28985000,0.982982,-0.00781711,-0.0121643,0.18313,-0.0736046,0.0484074,0.78856,-0.0461489,0.0219616,-2.35198,-1.11726e-05,-5.77367e-05,1.83908e-06,3.33453e-05,-0.000284682,-0.00115884,0.204181,0.00196475,0.434409,0,0,0,0,0,4.03672e-06,2.51465e-05,2.51113e-05,0.000116251,0.0136072,0.0136074,0.00999637,0.0377324,0.0377318,0.0593174,1.01709e-10,1.01732e-10,1.15837e-09,3.89774e-07,3.89692e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
29085000,0.982985,-0.00770624,-0.0122115,0.183119,-0.0761264,0.0496792,0.788269,-0.0536953,0.026838,-2.27509,-1.11706e-05,-5.77366e-05,1.88039e-06,3.34433e-05,-0.000284814,-0.00115815,0.204181,0.00196475,0.434409,0,0,0,0,0,4.02081e-06,2.55821e-05,2.55464e-05,0.000115743,0.0146323,0.0146329,0.0100692,0.0412698,0.041269,0.0594817,1.01804e-10,1.0183e-10,1.1515e-09,3.89776e-07,3.89687e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
29185000,0.983015,-0.00768809,-0.0124671,0.18294,-0.0714118,0.0468655,0.78247,-0.051042,0.0257739,-2.20666,-1.10078e-05,-5.7605e-05,2.0718e-06,3.98359e-05,-0.000292354,-0.00115341,0.204181,0.00196475,0.434409,0,0,0,0,0,4.00235e-06,2.54136e-05,2.53778e-05,0.000115269,0.0137255,0.0137264,0.00996747,0.0375943,0.0375938,0.0590492,1.01046e-10,1.01076e-10,1.14449e-09,3.88089e-07,3.8799e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
29285000,0.983001,-0.00793628,-0.0125067,0.183,-0.0725952,0.0518192,0.784874,-0.0582013,0.0307521,-2.12974,-1.10047e-05,-5.76062e-05,2.17388e-06,3.99116e-05,-0.000292466,-0.0011529,0.204181,0.00196475,0.434409,0,0,0,0,0,3.99331e-06,2.5852e-05,2.58166e-05,0.000114822,0.0147704,0.0147714,0.0100399,0.0411282,0.0411276,0.059212,1.01141e-10,1.01173e-10,1.13738e-09,3.88091e-07,3.87985e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
29385000,0.983014,-0.00841137,-0.0120327,0.182942,-0.0677884,0.0499194,0.787071,-0.0562357,0.0314698,-2.05463,-1.08654e-05,-5.74967e-05,2.31501e-06,4.49712e-05,-0.000298809,-0.00115116,0.204181,0.00196475,0.434409,0,0,0,0,0,3.98064e-06,2.56192e-05,2.55873e-05,0.000114408,0.0138643,0.0138656,0.00993868,0.0374906,0.0374902,0.0587835,1.00209e-10,1.00246e-10,1.13013e-09,3.86031e-07,3.85915e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
29485000,0.983031,-0.00846391,-0.0119025,0.182857,-0.069569,0.0497423,0.788336,-0.0630554,0.0364782,-1.97789,-1.08597e-05,-5.75015e-05,2.56815e-06,4.50111e-05,-0.000298916,-0.00115044,0.204181,0.00196475,0.434409,0,0,0,0,0,3.97064e-06,2.60593e-05,2.60275e-05,0.000114023,0.0149333,0.0149351,0.0100105,0.0410286,0.0410282,0.0589449,1.00305e-10,1.00342e-10,1.12279e-09,3.86032e-07,3.85911e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
29585000,0.983051,-0.00840418,-0.0119253,0.182751,-0.0646251,0.0468572,0.790148,-0.060314,0.0355813,-1.89986,-1.06961e-05,-5.73939e-05,2.73772e-06,4.99027e-05,-0.000306184,-0.0011503,0.204181,0.00196475,0.434409,0,0,0,0,0,3.97914e-06,2.57648e-05,2.57334e-05,0.000114262,0.0140302,0.0140321,0.0099935,0.0374203,0.03742,0.0593891,9.91948e-11,9.92349e-11,1.11721e-09,3.83583e-07,3.83455e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
29685000,0.983081,-0.00847452,-0.0117225,0.182602,-0.0684354,0.0449585,0.785935,-0.0669351,0.0402091,-1.82506,-1.06899e-05,-5.73972e-05,2.95969e-06,5.00383e-05,-0.000306415,-0.00114887,0.204181,0.00196475,0.434409,0,0,0,0,0,3.96698e-06,2.62053e-05,2.61743e-05,0.000113928,0.0151301,0.0151327,0.0100661,0.0409702,0.0409701,0.0595537,9.92912e-11,9.93307e-11,1.10968e-09,3.83586e-07,3.83452e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
29785000,0.983094,-0.00835984,-0.0122686,0.182501,-0.0637469,0.0369284,0.782253,-0.0621022,0.0376426,-1.75292,-1.0524e-05,-5.72639e-05,3.21225e-06,5.63556e-05,-0.000313812,-0.00114596,0.204181,0.00196475,0.434409,0,0,0,0,0,3.95846e-06,2.58463e-05,2.58139e-05,0.000113612,0.0142243,0.0142272,0.00996398,0.0373826,0.0373826,0.0591204,9.79957e-11,9.80382e-11,1.10202e-09,3.80733e-07,3.80592e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
29885000,0.983103,-0.00786404,-0.012664,0.182446,-0.0633726,0.0364903,0.778582,-0.0683483,0.0412738,-1.6809,-1.05162e-05,-5.72655e-05,3.42133e-06,5.66332e-05,-0.000314212,-0.00114384,0.204181,0.00196475,0.434409,0,0,0,0,0,3.95166e-06,2.62879e-05,2.62531e-05,0.000113319,0.0153463,0.0153497,0.010036,0.0409514,0.0409517,0.0592834,9.8091e-11,9.8135e-11,1.09429e-09,3.80736e-07,3.80589e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
29985000,0.983103,-0.00800637,-0.0127479,0.182434,-0.0578638,0.0313482,0.775545,-0.0638932,0.0369411,-1.61129,-1.03238e-05,-5.71588e-05,3.52001e-06,6.16716e-05,-0.00032311,-0.00113996,0.204181,0.00196475,0.434409,0,0,0,0,0,3.94447e-06,2.58613e-05,2.58276e-05,0.000113045,0.0144241,0.0144276,0.00993369,0.0373758,0.0373761,0.0588487,9.66112e-11,9.666e-11,1.08642e-09,3.77489e-07,3.77336e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
30085000,0.983102,-0.00816624,-0.0128959,0.182422,-0.0573265,0.0309891,0.773576,-0.0696489,0.0400816,-1.53742,-1.03253e-05,-5.71545e-05,3.36058e-06,6.18251e-05,-0.000323289,-0.00113866,0.204181,0.00196475,0.434409,0,0,0,0,0,3.93222e-06,2.63001e-05,2.62661e-05,0.000112798,0.015567,0.015571,0.0100053,0.0409684,0.0409692,0.0590102,9.67064e-11,9.67567e-11,1.0785e-09,3.77492e-07,3.77334e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
30185000,0.983078,-0.00816071,-0.0129252,0.182549,-0.0507563,0.0274251,0.773492,-0.0632003,0.0388062,-1.46555,-1.02305e-05,-5.70003e-05,3.23731e-06,6.87391e-05,-0.0003277,-0.00113619,0.204181,0.00196475,0.434409,0,0,0,0,0,3.94735e-06,2.58093e-05,2.57764e-05,0.000113148,0.0146222,0.0146262,0.00998836,0.0373965,0.0373973,0.0594556,9.50511e-11,9.51054e-11,1.0725e-09,3.73875e-07,3.73713e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
30285000,0.983069,-0.00819967,-0.0129319,0.182594,-0.0493444,0.0263255,0.773745,-0.0681458,0.0415076,-1.39322,-1.02262e-05,-5.7e-05,3.31606e-06,6.89544e-05,-0.000327998,-0.0011344,0.204181,0.00196475,0.434409,0,0,0,0,0,3.944e-06,2.62445e-05,2.62118e-05,0.000112925,0.0157811,0.0157857,0.0100606,0.0410169,0.0410181,0.0596204,9.51464e-11,9.5202e-11,1.06442e-09,3.73878e-07,3.73712e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
30385000,0.983067,-0.00819692,-0.0128774,0.182611,-0.0413104,0.0205064,0.771336,-0.0601282,0.0390754,-1.32528,-1.00905e-05,-5.68271e-05,3.63992e-06,7.72881e-05,-0.000334126,-0.00113022,0.204181,0.00196475,0.434409,0,0,0,0,0,3.94508e-06,2.56925e-05,2.56614e-05,0.000112713,0.0148141,0.0148186,0.00995772,0.0374412,0.0374424,0.0591809,9.33252e-11,9.33846e-11,1.05624e-09,3.69924e-07,3.69754e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
30485000,0.983101,-0.00822215,-0.0130233,0.182415,-0.0433331,0.0194711,0.772307,-0.0643089,0.0411206,-1.25349,-1.00831e-05,-5.68296e-05,3.86362e-06,7.75137e-05,-0.000334464,-0.00112828,0.204181,0.00196475,0.434409,0,0,0,0,0,3.93567e-06,2.61239e-05,2.60923e-05,0.000112526,0.0159898,0.0159949,0.0100298,0.0410919,0.0410937,0.0593441,9.34206e-11,9.34812e-11,1.048e-09,3.69928e-07,3.69754e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
30585000,0.983123,-0.00854131,-0.0133242,0.182259,-0.038144,0.0166846,0.771944,-0.0575167,0.0379818,-1.18178,-9.95386e-06,-5.66934e-05,4.12184e-06,8.39937e-05,-0.000340224,-0.00112572,0.204181,0.00196475,0.434409,0,0,0,0,0,3.92901e-06,2.55163e-05,2.54857e-05,0.000112349,0.0149947,0.0149995,0.00992783,0.0375059,0.0375075,0.0589088,9.14486e-11,9.15123e-11,1.03967e-09,3.65679e-07,3.65503e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
30685000,0.983144,-0.0089235,-0.0135669,0.18211,-0.0358393,0.014119,0.770848,-0.0612709,0.0395627,-1.1107,-9.94935e-06,-5.6693e-05,4.20346e-06,8.42375e-05,-0.000340556,-0.00112355,0.204181,0.00196475,0.434409,0,0,0,0,0,3.9193e-06,2.59425e-05,2.5912e-05,0.000112188,0.0161895,0.0161949,0.00999939,0.0411887,0.0411909,0.0590706,9.1544e-11,9.16088e-11,1.03129e-09,3.65683e-07,3.65503e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
30785000,0.983175,-0.00862664,-0.0132927,0.181979,-0.0283831,0.00911903,0.76942,-0.0545716,0.0394244,-1.04075,-9.94901e-06,-5.65589e-05,4.2466e-06,9.04638e-05,-0.000340635,-0.00112032,0.204181,0.00196475,0.434409,0,0,0,0,0,3.909e-06,2.52818e-05,2.5253e-05,0.00011204,0.0151657,0.0151708,0.0098979,0.0375868,0.0375887,0.0586395,8.94381e-11,8.95053e-11,1.02283e-09,3.61186e-07,3.61006e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
30885000,0.983167,-0.00800001,-0.013161,0.182056,-0.0274625,0.00470965,0.767084,-0.0572887,0.0401663,-0.96843,-9.94778e-06,-5.65569e-05,4.21654e-06,9.0634e-05,-0.000340849,-0.00111875,0.204181,0.00196475,0.434409,0,0,0,0,0,3.92673e-06,2.57011e-05,2.56712e-05,0.000112475,0.0163771,0.0163828,0.0100541,0.0413027,0.0413054,0.0596769,8.95347e-11,8.96025e-11,1.01648e-09,3.61192e-07,3.61009e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
30985000,0.98317,-0.00817522,-0.0131233,0.182036,-0.0201208,-0.000124043,0.768554,-0.0478441,0.0343355,-0.899334,-9.81793e-06,-5.6423e-05,4.26282e-06,9.68241e-05,-0.000346821,-0.0011156,0.204181,0.00196475,0.434409,0,0,0,0,0,3.92209e-06,2.49949e-05,2.49667e-05,0.000112339,0.015317,0.0153222,0.00995157,0.03768,0.0376823,0.0592372,8.73135e-11,8.73826e-11,1.00791e-09,3.56496e-07,3.56314e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
31085000,0.983133,-0.0083264,-0.013237,0.182223,-0.0178201,-0.00326827,0.767557,-0.0496935,0.0340985,-0.825253,-9.81791e-06,-5.64213e-05,4.21411e-06,9.69248e-05,-0.000346939,-0.00111464,0.204181,0.00196475,0.434409,0,0,0,0,0,3.92488e-06,2.54071e-05,2.53791e-05,0.000112204,0.0165377,0.0165435,0.0100236,0.0414282,0.0414314,0.0594008,8.7409e-11,8.74789e-11,9.99311e-10,3.56501e-07,3.56316e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
31185000,0.983154,-0.00846116,-0.0133857,0.18209,-0.0135565,-0.00651234,0.769056,-0.0419875,0.0306301,-0.755399,-9.77352e-06,-5.63184e-05,4.53722e-06,0.000101938,-0.000348821,-0.00111207,0.204181,0.00196475,0.434409,0,0,0,0,0,3.92207e-06,2.46627e-05,2.46356e-05,0.000112082,0.0154475,0.0154527,0.00992191,0.0377812,0.0377839,0.0589654,8.50948e-11,8.51653e-11,9.90646e-10,3.51664e-07,3.51481e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
31285000,0.983178,-0.00873165,-0.0134705,0.181944,-0.00991317,-0.0101086,0.772962,-0.0431103,0.0298409,-0.683767,-9.76743e-06,-5.63208e-05,4.73165e-06,0.000102129,-0.000349099,-0.00111014,0.204181,0.00196475,0.434409,0,0,0,0,0,3.91639e-06,2.50668e-05,2.50401e-05,0.000111969,0.0166658,0.0166716,0.00999265,0.0415601,0.0415636,0.0591221,8.51903e-11,8.52616e-11,9.81946e-10,3.51669e-07,3.51484e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
31385000,0.98319,-0.00850609,-0.0132732,0.181902,-0.00438402,-0.0156642,0.772309,-0.0352996,0.0259324,-0.610893,-9.74631e-06,-5.62425e-05,4.64104e-06,0.00010565,-0.000350237,-0.00110766,0.204181,0.00196475,0.434409,0,0,0,0,0,3.90844e-06,2.42907e-05,2.42652e-05,0.000111867,0.0155511,0.0155561,0.00989168,0.0378863,0.0378891,0.0586911,8.28073e-11,8.28784e-11,9.732e-10,3.46754e-07,3.46573e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
31485000,0.983175,-0.00825805,-0.0135884,0.181973,-0.0036613,-0.0202718,0.769157,-0.0357493,0.024095,-0.535741,-9.74583e-06,-5.62419e-05,4.63524e-06,0.000105713,-0.000350314,-0.001107,0.204181,0.00196475,0.434409,0,0,0,0,0,3.9281e-06,2.46872e-05,2.46599e-05,0.000112339,0.0167889,0.0167944,0.0100482,0.0416944,0.0416982,0.0597305,8.29041e-11,8.29756e-11,9.66651e-10,3.46761e-07,3.46578e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
31585000,0.983205,-0.00806029,-0.0140632,0.181785,0.000406426,-0.0207666,0.772777,-0.0257779,0.0217998,-0.464304,-9.75733e-06,-5.61092e-05,4.85201e-06,0.000111934,-0.000349828,-0.0011043,0.204181,0.00196475,0.434409,0,0,0,0,0,3.92123e-06,2.38874e-05,2.38591e-05,0.000112243,0.0156368,0.0156416,0.00994624,0.0379922,0.0379953,0.059291,8.04702e-11,8.05407e-11,9.57844e-10,3.41807e-07,3.41628e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
31685000,0.983235,-0.00806224,-0.0145422,0.181581,-0.000813562,-0.0231968,0.769099,-0.0258081,0.0195256,-0.394806,-9.74971e-06,-5.61126e-05,5.10411e-06,0.000112178,-0.000350176,-0.00110156,0.204181,0.00196475,0.434409,0,0,0,0,0,3.91496e-06,2.4275e-05,2.4245e-05,0.000112149,0.0168747,0.01688,0.0100177,0.0418265,0.0418305,0.0594497,8.05659e-11,8.06368e-11,9.49015e-10,3.41813e-07,3.41633e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
31785000,0.983254,-0.00821291,-0.0152085,0.181421,0.00772067,-0.0242709,0.76896,-0.0153644,0.0202676,-0.323349,-9.84818e-06,-5.59487e-05,5.31754e-06,0.000119743,-0.00034591,-0.00109902,0.204181,0.00196475,0.434409,0,0,0,0,0,3.90951e-06,2.34583e-05,2.34276e-05,0.000112058,0.0157031,0.0157076,0.00991644,0.0380958,0.0380991,0.0590147,7.81049e-11,7.81741e-11,9.40158e-10,3.36876e-07,3.36702e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
31885000,0.983268,-0.00798975,-0.0150143,0.181371,0.0122242,-0.027878,0.76769,-0.0143349,0.0175952,-0.254092,-9.84303e-06,-5.59502e-05,5.46637e-06,0.000119978,-0.000346216,-0.00109634,0.204181,0.00196475,0.434409,0,0,0,0,0,3.90714e-06,2.38342e-05,2.38039e-05,0.000111969,0.0169371,0.016942,0.0099875,0.041954,0.0419581,0.0591721,7.82006e-11,7.82702e-11,9.31285e-10,3.36883e-07,3.36707e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
31985000,0.98326,-0.00815853,-0.0145871,0.181439,0.0196168,-0.0268163,0.764365,-0.00369276,0.0169724,-0.187679,-9.92232e-06,-5.58237e-05,5.41536e-06,0.00012577,-0.00034316,-0.00109198,0.204181,0.00196475,0.434409,0,0,0,0,0,3.90499e-06,2.30031e-05,2.2976e-05,0.000111881,0.0157443,0.0157486,0.00988705,0.0381949,0.0381983,0.0587416,7.57314e-11,7.57987e-11,9.22394e-10,3.32006e-07,3.31836e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
32085000,0.983279,-0.00854223,-0.0142212,0.181348,0.0205173,-0.0314746,0.766757,-0.00166203,0.0141188,-0.116765,-9.92027e-06,-5.58232e-05,5.44953e-06,0.000125943,-0.000343361,-0.00108996,0.204181,0.00196475,0.434409,0,0,0,0,0,3.89857e-06,2.33686e-05,2.33439e-05,0.000111799,0.0169706,0.0169752,0.00995794,0.0420732,0.0420775,0.0588977,7.58271e-11,7.58949e-11,9.13495e-10,3.32013e-07,3.31842e-07,5e-08,0,0,0,0,0,0,0,0
|
||||
32185000,0.983272,-0.00868877,-0.0144894,0.181358,0.0243554,-0.0323633,0.766812,0.00794621,0.0155311,-0.0475981,-1.00765e-05,-5.57174e-05,5.43512e-06,0.00013081,-0.000336964,-0.00108635,0.204181,0.00196475,0.434409,0,0,0,0,0,3.91528e-06,2.25356e-05,2.25113e-05,0.000112291,0.0157535,0.0157572,0.00994148,0.0382866,0.03829,0.059339,7.33699e-11,7.34349e-11,9.0683e-10,3.27238e-07,3.27074e-07,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
32285000,0.983292,-0.00861372,-0.0147496,0.181232,0.026901,-0.0369109,0.765333,0.0105284,0.012032,0.0214446,-1.00717e-05,-5.57191e-05,5.58463e-06,0.00013103,-0.000337234,-0.00108364,0.204181,0.00196475,0.434409,0,0,0,0,0,3.91019e-06,2.2893e-05,2.28678e-05,0.000112208,0.0169805,0.0169846,0.0100131,0.042181,0.0421852,0.0594985,7.34657e-11,7.3531e-11,8.97917e-10,3.27245e-07,3.2708e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
32385000,0.983274,-0.00860839,-0.0148514,0.181321,0.0326671,-0.0357428,0.764013,0.0200932,0.0121826,0.0942163,-1.02016e-05,-5.56443e-05,5.53355e-06,0.000134458,-0.000331967,-0.001081,0.204181,0.00196475,0.434409,0,0,0,0,0,3.9093e-06,2.20611e-05,2.20363e-05,0.000112121,0.0157502,0.0157536,0.00991239,0.0383692,0.0383726,0.0590642,7.10347e-11,7.10968e-11,8.89e-10,3.22604e-07,3.22447e-07,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
32485000,0.98329,-0.0115133,-0.0127894,0.181228,0.0610097,-0.103372,-0.108551,0.0252658,0.00343156,0.102768,-1.02025e-05,-5.56416e-05,5.4471e-06,0.000134494,-0.000331993,-0.00108057,0.204181,0.00196475,0.434409,0,0,0,0,0,3.90009e-06,2.24013e-05,2.23916e-05,0.000112043,0.018984,0.018986,0.00978734,0.0423792,0.0423834,0.0592139,7.11312e-11,7.11921e-11,8.80088e-10,0,0,0,0,0,0,0,0,0,0,0
|
||||
32585000,0.983307,-0.011399,-0.012725,0.181149,0.0592457,-0.101433,-0.109941,0.0352402,0.00327999,0.0848924,-1.05259e-05,-5.55767e-05,5.64232e-06,0.000134494,-0.000331993,-0.00108057,0.204181,0.00196475,0.434409,0,0,0,0,0,3.89679e-06,2.13888e-05,2.13789e-05,0.000111955,0.0180972,0.0180992,0.00942068,0.0385724,0.0385757,0.0587436,6.84086e-11,6.84601e-11,8.71169e-10,0,0,0,0,0,0,0,0,0,0,0
|
||||
32685000,0.983312,-0.0113883,-0.0125952,0.181131,0.0564344,-0.108107,-0.111734,0.0410737,-0.0072045,0.0701459,-1.05258e-05,-5.55757e-05,5.62087e-06,0.000134494,-0.000331993,-0.00108057,0.204181,0.00196475,0.434409,0,0,0,0,0,3.89217e-06,2.17228e-05,2.17127e-05,0.00011187,0.0201474,0.0201506,0.00922532,0.0427366,0.0427409,0.0588169,6.85054e-11,6.85554e-11,8.62272e-10,0,0,0,0,0,0,0,0,0,0,0
|
||||
32785000,0.983321,-0.0111366,-0.0126446,0.181097,0.0528833,-0.102803,-0.112353,0.0485437,-0.005462,0.0552886,-1.0894e-05,-5.5513e-05,5.80138e-06,0.000134494,-0.000331993,-0.00108057,0.204181,0.00196475,0.434409,0,0,0,0,0,3.91035e-06,2.05757e-05,2.05647e-05,0.000112357,0.019122,0.0191253,0.00897046,0.0388573,0.0388607,0.059175,6.56553e-11,6.56956e-11,8.55625e-10,0,0,0,0,0,0,0,0,0,0,0
|
||||
32885000,0.983343,-0.0111123,-0.0127126,0.180976,0.0539607,-0.110507,-0.113667,0.0539388,-0.0161481,0.0416368,-1.08923e-05,-5.55145e-05,5.87971e-06,0.000134494,-0.000331993,-0.00108057,0.204181,0.00196475,0.434409,0,0,0,0,0,3.90341e-06,2.0896e-05,2.08842e-05,0.000112271,0.0212664,0.0212709,0.00879151,0.0431385,0.0431429,0.0591806,6.5752e-11,6.57911e-11,8.46752e-10,3.22609e-07,3.22451e-07,5.0003e-08,0,0,0,0,0,0,0,0
|
||||
32985000,0.98336,-0.0109197,-0.0126439,0.180899,0.0495513,-0.105393,-0.112656,0.0593799,-0.0162601,0.0290317,-1.12189e-05,-5.54872e-05,6.0976e-06,0.00013455,-0.000332572,-0.00108061,0.204181,0.00196475,0.434409,0,0,0,0,0,3.90033e-06,1.96371e-05,1.96248e-05,0.000112176,0.0201159,0.0201204,0.008497,0.0391717,0.0391752,0.058626,6.28372e-11,6.28661e-11,8.37885e-10,3.22612e-07,3.22455e-07,5.00129e-08,0,0,0,0,0,0,0,0
|
||||
33085000,0.983363,-0.0108881,-0.0126664,0.180883,0.0470061,-0.11037,-0.110423,0.0642382,-0.0270082,0.0205214,-1.12196e-05,-5.5487e-05,6.07415e-06,0.00013455,-0.000332571,-0.00108062,0.204181,0.00196475,0.434409,0,0,0,0,0,3.89547e-06,1.99419e-05,1.9929e-05,0.000112083,0.0224249,0.022431,0.00835266,0.0435684,0.043573,0.0585729,6.29339e-11,6.29618e-11,8.29054e-10,3.22622e-07,3.22465e-07,5.00229e-08,0,0,0,0,0,0,0,0
|
||||
33185000,0.983371,-0.0106625,-0.0125557,0.180861,0.0413634,-0.105745,-0.108826,0.0680086,-0.0261344,0.0144202,-1.15421e-05,-5.54542e-05,5.99687e-06,0.000134709,-0.000335641,-0.00108087,0.204181,0.00196475,0.434409,0,0,0,0,0,3.88815e-06,1.86038e-05,1.85905e-05,0.000111988,0.0211721,0.0211778,0.00810725,0.0395035,0.039507,0.0579989,6.00245e-11,6.00428e-11,8.20236e-10,3.22419e-07,3.22261e-07,5.00304e-08,0,0,0,0,0,0,0,0
|
||||
33285000,0.983398,-0.0107355,-0.0125706,0.180705,0.0394273,-0.108957,-0.108656,0.0719837,-0.036874,0.00591751,-1.15377e-05,-5.54595e-05,6.23111e-06,0.000134706,-0.000335639,-0.00108088,0.204181,0.00196475,0.434409,0,0,0,0,0,3.88279e-06,1.88926e-05,1.8879e-05,0.000111891,0.0236251,0.0236326,0.00799882,0.0440162,0.0440209,0.0578991,6.01212e-11,6.01388e-11,8.11459e-10,3.22429e-07,3.22271e-07,5.00403e-08,0,0,0,0,0,0,0,0
|
||||
33385000,0.983415,-0.0104668,-0.012596,0.180629,0.0331154,-0.0970429,-0.106307,0.0727555,-0.0295937,-0.00248725,-1.19609e-05,-5.54002e-05,6.3123e-06,0.000134706,-0.000335639,-0.00108117,0.204181,0.00196475,0.434409,0,0,0,0,0,3.87642e-06,1.75133e-05,1.74991e-05,0.000111789,0.0219592,0.0219662,0.00779775,0.039844,0.0398476,0.0573155,5.72858e-11,5.72945e-11,8.02702e-10,0,0,5.00418e-08,0,0,0,0,0,0,0,0
|
||||
33485000,0.983419,-0.0104532,-0.0125559,0.180609,0.0294368,-0.100535,-0.106231,0.0758406,-0.0394421,-0.0132188,-1.19607e-05,-5.54003e-05,6.3208e-06,0.000134706,-0.000335639,-0.00108117,0.204181,0.00196475,0.434409,0,0,0,0,0,3.89148e-06,1.77857e-05,1.77714e-05,0.000112262,0.0241764,0.0241849,0.00778651,0.0444618,0.0444667,0.0580104,5.73832e-11,5.73915e-11,7.96185e-10,0,0,5.00515e-08,0,0,0,0,0,0,0,0
|
||||
33585000,0.983451,-0.0101607,-0.0124957,0.180455,0.0239734,-0.0929438,-0.102487,0.0759842,-0.0335687,-0.0190251,-1.22966e-05,-5.53536e-05,6.51804e-06,0.000134706,-0.000335639,-0.00108181,0.204181,0.00196475,0.434409,0,0,0,0,0,3.88406e-06,1.63989e-05,1.63841e-05,0.000112154,0.0223061,0.0223136,0.00762289,0.0401774,0.0401812,0.0574092,5.46742e-11,5.46746e-11,7.87488e-10,0,0,5.00437e-08,0,0,0,0,0,0,0,0
|
||||
33685000,0.983462,-0.0101551,-0.01249,0.1804,0.0203592,-0.0964702,-0.104093,0.0782391,-0.0430795,-0.0275037,-1.22956e-05,-5.53548e-05,6.56989e-06,0.000134706,-0.000335639,-0.00108184,0.204181,0.00196475,0.434409,0,0,0,0,0,3.87843e-06,1.66554e-05,1.66403e-05,0.000112043,0.0244989,0.0245079,0.0075793,0.0448802,0.0448852,0.0572473,5.47708e-11,5.47709e-11,7.78841e-10,0,0,5.00524e-08,0,0,0,0,0,0,0,0
|
||||
33785000,0.983473,-0.00993954,-0.0124639,0.180355,0.0145857,-0.0884614,-0.098318,0.0796302,-0.0363932,-0.0334735,-1.26087e-05,-5.52688e-05,6.49939e-06,0.000134706,-0.000335639,-0.00108257,0.204181,0.00196475,0.434409,0,0,0,0,0,3.86955e-06,1.52906e-05,1.52752e-05,0.00011193,0.0224735,0.0224813,0.00745186,0.0404865,0.0404903,0.056654,5.2226e-11,5.22192e-11,7.70225e-10,0,0,5.00318e-08,0,0,0,0,0,0,0,0
|
||||
33885000,0.983491,-0.0099786,-0.0124262,0.180253,0.0113716,-0.0890618,-0.097921,0.0808729,-0.0453144,-0.0407438,-1.26055e-05,-5.52722e-05,6.65967e-06,0.000134706,-0.000335639,-0.00108265,0.204181,0.00196475,0.434409,0,0,0,0,0,3.86407e-06,1.55316e-05,1.55162e-05,0.000111811,0.024614,0.0246234,0.00743744,0.0452533,0.0452584,0.0564754,5.23225e-11,5.23156e-11,7.61656e-10,0,0,5.00388e-08,0,0,0,0,0,0,0,0
|
||||
33985000,0.983482,-0.00971083,-0.0125434,0.180311,0.00779941,-0.0781908,-0.0942757,0.0812244,-0.0360785,-0.0439306,-1.2931e-05,-5.51544e-05,6.54729e-06,0.000134706,-0.000335639,-0.00108359,0.204181,0.00196475,0.434409,0,0,0,0,0,3.85841e-06,1.42135e-05,1.41975e-05,0.000111687,0.0224772,0.0224853,0.00734195,0.0407594,0.0407632,0.0558971,4.99669e-11,4.99541e-11,7.53131e-10,0,0,5.0005e-08,0,0,0,0,0,0,0,0
|
||||
34085000,0.983487,-0.00964654,-0.012552,0.180286,0.0044861,-0.0822617,-0.0933622,0.0818833,-0.044133,-0.0506216,-1.29313e-05,-5.51543e-05,6.53457e-06,0.000134706,-0.000335639,-0.00108369,0.204181,0.00196475,0.434409,0,0,0,0,0,3.87193e-06,1.44403e-05,1.44239e-05,0.000112137,0.0245544,0.0245637,0.00741083,0.0455697,0.0455748,0.0565077,5.00642e-11,5.00515e-11,7.46799e-10,0,0,5.00108e-08,0,0,0,0,0,0,0,0
|
||||
34185000,0.983488,-0.00946866,-0.0125741,0.180285,-0.000175009,-0.0722992,-0.0910214,0.0827377,-0.0359938,-0.0523916,-1.31966e-05,-5.50508e-05,6.58234e-06,0.000134706,-0.000335639,-0.00108446,0.204181,0.00196475,0.434409,0,0,0,0,0,3.86711e-06,1.31857e-05,1.31692e-05,0.000112003,0.0223367,0.0223446,0.00734135,0.0409881,0.0409919,0.0559343,4.79092e-11,4.78915e-11,7.38358e-10,0,0,5.00037e-08,0,0,0,0,0,0,0,0
|
||||
34285000,0.983493,-0.00935994,-0.0126394,0.18026,-6.56656e-05,-0.0753501,-0.0899868,0.082756,-0.0434173,-0.0596514,-1.31951e-05,-5.50523e-05,6.6529e-06,0.000134706,-0.000335639,-0.00108456,0.204181,0.00196475,0.434409,0,0,0,0,0,3.8623e-06,1.33993e-05,1.33821e-05,0.000111865,0.0243402,0.0243493,0.00737868,0.0458217,0.0458268,0.0557554,4.80057e-11,4.79882e-11,7.29972e-10,0,0,5.0004e-08,0,0,0,0,0,0,0,0
|
||||
34385000,0.983516,-0.00914415,-0.012633,0.180147,-0.00389612,-0.064632,-0.0849739,0.0818784,-0.0352132,-0.062808,-1.34381e-05,-5.49671e-05,6.64543e-06,0.000134706,-0.000335639,-0.00108603,0.204181,0.00196475,0.434409,0,0,0,0,0,3.85129e-06,1.22205e-05,1.22031e-05,0.000111729,0.0220675,0.0220751,0.00733349,0.041168,0.0411719,0.0552086,4.60529e-11,4.60313e-11,7.21639e-10,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
34485000,0.983521,-0.00922737,-0.0125676,0.180121,-0.00671741,-0.0678918,-0.0834901,0.0813481,-0.0419077,-0.0663075,-1.34364e-05,-5.49687e-05,6.71912e-06,0.000134706,-0.000335639,-0.00108639,0.204181,0.00196475,0.434409,0,0,0,0,0,3.84625e-06,1.24214e-05,1.24043e-05,0.000111584,0.0239921,0.0240007,0.0073933,0.046006,0.046011,0.0550444,4.61493e-11,4.61281e-11,7.13363e-10,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
34585000,0.983525,-0.00903438,-0.0123775,0.180119,-0.00860069,-0.0573819,0.662421,0.0807244,-0.0350088,-0.0411829,-1.36259e-05,-5.48861e-05,6.67215e-06,0.000134706,-0.000335639,-0.00108775,0.204181,0.00196475,0.434409,0,0,0,0,0,3.83885e-06,1.13249e-05,1.13082e-05,0.000111436,0.0204658,0.0204724,0.00736626,0.041264,0.0412678,0.0545278,4.43934e-11,4.43689e-11,7.05144e-10,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
34685000,0.983531,-0.00901958,-0.0120954,0.18011,-0.0113346,-0.0545748,1.65309,0.079737,-0.0406042,0.0716704,-1.3627e-05,-5.4885e-05,6.62559e-06,0.000134706,-0.000335639,-0.00108748,0.204181,0.00196475,0.434409,0,0,0,0,0,3.83153e-06,1.15142e-05,1.14983e-05,0.000111285,0.0205706,0.0205773,0.00744265,0.0458986,0.0459034,0.0543843,4.44898e-11,4.44658e-11,6.96987e-10,0,0,5e-08,0,0,0,0,0,0,0,0
|
||||
34785000,0.983543,-0.00886932,-0.0118592,0.180065,-0.0130252,-0.0442325,2.61955,0.0795802,-0.0339024,0.233693,-1.37741e-05,-5.48068e-05,6.66661e-06,0.000134706,-0.000335639,-0.00106151,0.204181,0.00196475,0.434409,0,0,0,0,0,3.84327e-06,1.06234e-05,1.0608e-05,0.0001117,0.0173848,0.0173899,0.00748222,0.0411363,0.0411399,0.0546363,4.30832e-11,4.30569e-11,6.90927e-10,0,0,5.0002e-08,0,0,0,0,0,0,0,0
|
||||
34885000,0.983548,-0.00885328,-0.0115784,0.180057,-0.0156976,-0.0414105,3.60512,0.0781945,-0.0381592,0.523545,-1.37758e-05,-5.48053e-05,6.62188e-06,0.000134706,-0.000335639,-0.00105927,0.204181,0.00196475,0.434409,0,0,0,0,0,3.83563e-06,1.08044e-05,1.07897e-05,0.000111539,0.0174924,0.0174975,0.00757633,0.045452,0.0454566,0.0545154,4.31795e-11,4.31539e-11,6.82876e-10,0,0,5.0001e-08,0,0,0,0,0,0,0,0
|
||||
|
||||
|
@@ -0,0 +1,57 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2019 ECL Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file test_EKF_utils.cpp
|
||||
*
|
||||
* @brief Unit tests for the miscellaneous EKF utilities
|
||||
*/
|
||||
|
||||
#include <gtest/gtest.h>
|
||||
#include <cmath>
|
||||
#include <vector>
|
||||
|
||||
#include "EKF/utils.hpp"
|
||||
|
||||
TEST(eclPowfTest, compareToStandardImplementation)
|
||||
{
|
||||
std::vector<int> exponents = {-3,-2,-1,-0,0,1,2,3};
|
||||
std::vector<float> bases = {-INFINITY, -11.1f,-0.5f, -0.f, 0.f, 0.5f, 11.1f, INFINITY};
|
||||
|
||||
for (auto const exponent : exponents) {
|
||||
for (auto const basis : bases) {
|
||||
EXPECT_EQ(ecl::powf(basis, exponent),
|
||||
std::pow(basis, static_cast<float>(exponent)));
|
||||
}
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user