diff --git a/.ci/Jenkinsfile-hardware b/.ci/Jenkinsfile-hardware index ae55849141..503fba6934 100644 --- a/.ci/Jenkinsfile-hardware +++ b/.ci/Jenkinsfile-hardware @@ -864,12 +864,13 @@ void printTopics() { sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener cpuload" || true' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener distance_sensor" || true' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener ekf2_timestamps" || true' - sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_gps_status" || true' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener esc_status" || true' + sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_aid_src_fake_pos" || true' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_attitude" || true' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_baro_bias" || true' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_event_flags" || true' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_global_position" || true' + sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_gps_status" || true' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_innovation_test_ratios" || true' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_innovation_variances" || true' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_innovations" || true' diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index 0709971fd2..2064d91ba2 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -77,6 +77,9 @@ set(msg_files estimator_states.msg estimator_status.msg estimator_status_flags.msg + estimator_aid_source_1d.msg + estimator_aid_source_2d.msg + estimator_aid_source_3d.msg event.msg follow_target.msg failure_detector_status.msg diff --git a/msg/estimator_aid_source_1d.msg b/msg/estimator_aid_source_1d.msg new file mode 100644 index 0000000000..5670ab9e07 --- /dev/null +++ b/msg/estimator_aid_source_1d.msg @@ -0,0 +1,21 @@ +uint64 timestamp # time since system start (microseconds) +uint64 timestamp_sample # the timestamp of the raw data (microseconds) + +uint8 estimator_instance + +uint32 device_id + +uint64 time_last_fuse + +float32 observation +float32 observation_variance + +float32 innovation +float32 innovation_variance +float32 test_ratio + +bool fusion_enabled # true when measurements are being fused +bool innovation_rejected # true if the observation has been rejected +bool fused # true if the sample was successfully fused + +# TOPICS estimator_aid_source_1d diff --git a/msg/estimator_aid_source_2d.msg b/msg/estimator_aid_source_2d.msg new file mode 100644 index 0000000000..c70403ff99 --- /dev/null +++ b/msg/estimator_aid_source_2d.msg @@ -0,0 +1,22 @@ +uint64 timestamp # time since system start (microseconds) +uint64 timestamp_sample # the timestamp of the raw data (microseconds) + +uint8 estimator_instance + +uint32 device_id + +uint64[2] time_last_fuse + +float32[2] observation +float32[2] observation_variance + +float32[2] innovation +float32[2] innovation_variance +float32[2] test_ratio + +bool[2] fusion_enabled # true when measurements are being fused +bool[2] innovation_rejected # true if the observation has been rejected +bool[2] fused # true if the sample was successfully fused + +# TOPICS estimator_aid_source_2d +# TOPICS estimator_aid_src_fake_pos diff --git a/msg/estimator_aid_source_3d.msg b/msg/estimator_aid_source_3d.msg new file mode 100644 index 0000000000..52ad3fccb9 --- /dev/null +++ b/msg/estimator_aid_source_3d.msg @@ -0,0 +1,21 @@ +uint64 timestamp # time since system start (microseconds) +uint64 timestamp_sample # the timestamp of the raw data (microseconds) + +uint8 estimator_instance + +uint32 device_id + +uint64[3] time_last_fuse + +float32[3] observation +float32[3] observation_variance + +float32[3] innovation +float32[3] innovation_variance +float32[3] test_ratio + +bool[3] fusion_enabled # true when measurements are being fused +bool[3] innovation_rejected # true if the observation has been rejected +bool[3] fused # true if the sample was successfully fused + +# TOPICS estimator_aid_source_3d diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index f96b7a0714..092e0f2c80 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -48,6 +48,10 @@ #include "EKFGSF_yaw.h" #include "baro_bias_estimator.hpp" +#include +#include +#include + class Ekf final : public EstimatorInterface { public: @@ -336,6 +340,8 @@ public: const BaroBiasEstimator::status &getBaroBiasEstimatorStatus() const { return _baro_b_est.getStatus(); } + const auto &aid_src_fake_pos() const { return _aid_src_fake_pos; } + private: // set the internal states and status to their default value @@ -394,7 +400,6 @@ private: uint64_t _time_last_flow_terrain_fuse{0}; ///< time the last fusion of optical flow measurements for terrain estimation were performed (uSec) uint64_t _time_last_arsp_fuse{0}; ///< time the last fusion of airspeed measurements were performed (uSec) uint64_t _time_last_beta_fuse{0}; ///< time the last fusion of synthetic sideslip measurements were performed (uSec) - uint64_t _time_last_fake_pos_fuse{0}; ///< last time we faked position measurements to constrain tilt errors during operation without external aiding (uSec) uint64_t _time_last_zero_velocity_fuse{0}; ///< last time of zero velocity update (uSec) uint64_t _time_last_gps_yaw_fuse{0}; ///< time the last fusion of GPS yaw measurements were performed (uSec) uint64_t _time_last_gps_yaw_data{0}; ///< time the last GPS yaw measurement was available (uSec) @@ -491,6 +496,8 @@ private: bool _inhibit_flow_use{false}; ///< true when use of optical flow and range finder is being inhibited Vector2f _flow_compensated_XY_rad{}; ///< measured delta angle of the image about the X and Y body axes after removal of body rotation (rad), RH rotation is positive + estimator_aid_source_2d_s _aid_src_fake_pos{}; + // output predictor states Vector3f _delta_angle_corr{}; ///< delta angle correction vector (rad) Vector3f _vel_err_integ{}; ///< integral of velocity tracking error (m) @@ -676,7 +683,7 @@ private: Vector3f &innov_var, Vector2f &test_ratio); bool fuseHorizontalPosition(const Vector3f &innov, float innov_gate, const Vector3f &obs_var, - Vector3f &innov_var, Vector2f &test_ratiov, bool inhibit_gate = false); + Vector3f &innov_var, Vector2f &test_ratiov); bool fuseVerticalPosition(float innov, float innov_gate, float obs_var, float &innov_var, float &test_ratio); @@ -1048,6 +1055,65 @@ private: bool isYawEmergencyEstimateAvailable() const; void resetGpsDriftCheckFilters(); + + bool resetEstimatorAidStatusFlags(estimator_aid_source_1d_s &status) + { + if (status.timestamp_sample != 0) { + status.timestamp_sample = 0; + status.fusion_enabled = false; + status.innovation_rejected = false; + status.fused = false; + + return true; + } + + return false; + } + + void resetEstimatorAidStatus(estimator_aid_source_1d_s &status) + { + if (resetEstimatorAidStatusFlags(status)) { + status.observation = 0; + status.observation_variance = 0; + + status.innovation = 0; + status.innovation_variance = 0; + status.test_ratio = 0; + } + } + + template + bool resetEstimatorAidStatusFlags(T &status) + { + if (status.timestamp_sample != 0) { + status.timestamp_sample = 0; + + for (size_t i = 0; i < (sizeof(status.fusion_enabled) / sizeof(status.fusion_enabled[0])); i++) { + status.fusion_enabled[i] = false; + status.innovation_rejected[i] = false; + status.fused[i] = false; + } + + return true; + } + + return false; + } + + template + void resetEstimatorAidStatus(T &status) + { + if (resetEstimatorAidStatusFlags(status)) { + for (size_t i = 0; i < (sizeof(status.fusion_enabled) / sizeof(status.fusion_enabled[0])); i++) { + status.observation[i] = 0; + status.observation_variance[i] = 0; + + status.innovation[i] = 0; + status.innovation_variance[i] = 0; + status.test_ratio[i] = 0; + } + } + } }; #endif // !EKF_EKF_H diff --git a/src/modules/ekf2/EKF/fake_pos_control.cpp b/src/modules/ekf2/EKF/fake_pos_control.cpp index 2962771c9b..2975109f3d 100644 --- a/src/modules/ekf2/EKF/fake_pos_control.cpp +++ b/src/modules/ekf2/EKF/fake_pos_control.cpp @@ -40,9 +40,14 @@ void Ekf::controlFakePosFusion() { + auto &fake_pos = _aid_src_fake_pos; + + // clear + resetEstimatorAidStatusFlags(fake_pos); + // If we aren't doing any aiding, fake position measurements at the last known position to constrain drift // During intial tilt aligment, fake position is used to perform a "quasi-stationary" leveling of the EKF - const bool fake_pos_data_ready = isTimedOut(_time_last_fake_pos_fuse, (uint64_t)2e5); // Fuse fake position at a limited rate + const bool fake_pos_data_ready = isTimedOut(fake_pos.time_last_fuse[0], (uint64_t)2e5); // Fuse fake position at a limited rate if (fake_pos_data_ready) { const bool continuing_conditions_passing = !isHorizontalAidingActive(); @@ -52,7 +57,7 @@ void Ekf::controlFakePosFusion() if (continuing_conditions_passing) { fuseFakePosition(); - const bool is_fusion_failing = isTimedOut(_time_last_fake_pos_fuse, (uint64_t)4e5); + const bool is_fusion_failing = isTimedOut(fake_pos.time_last_fuse[0], (uint64_t)4e5); if (is_fusion_failing) { resetFakePosFusion(); @@ -79,6 +84,7 @@ void Ekf::controlFakePosFusion() void Ekf::startFakePosFusion() { if (!_using_synthetic_position) { + ECL_INFO("start fake position fusion"); _using_synthetic_position = true; _fuse_hpos_as_odom = false; // TODO: needed? resetFakePosFusion(); @@ -87,39 +93,66 @@ void Ekf::startFakePosFusion() void Ekf::resetFakePosFusion() { + ECL_INFO("reset fake position fusion"); _last_known_posNE = _state.pos.xy(); + resetHorizontalPositionToLastKnown(); resetHorizontalVelocityToZero(); - _time_last_fake_pos_fuse = _time_last_imu; + + _aid_src_fake_pos.time_last_fuse[0] = _time_last_imu; + _aid_src_fake_pos.time_last_fuse[1] = _time_last_imu; } void Ekf::stopFakePosFusion() { - _using_synthetic_position = false; + if (_using_synthetic_position) { + ECL_INFO("stop fake position fusion"); + _using_synthetic_position = false; + + resetEstimatorAidStatus(_aid_src_fake_pos); + } } void Ekf::fuseFakePosition() { - Vector3f fake_pos_obs_var; + Vector2f obs_var; if (_control_status.flags.in_air && _control_status.flags.tilt_align) { - fake_pos_obs_var(0) = fake_pos_obs_var(1) = sq(fmaxf(_params.pos_noaid_noise, _params.gps_pos_noise)); + obs_var(0) = obs_var(1) = sq(fmaxf(_params.pos_noaid_noise, _params.gps_pos_noise)); } else if (!_control_status.flags.in_air && _control_status.flags.vehicle_at_rest) { // Accelerate tilt fine alignment by fusing more // aggressively when the vehicle is at rest - fake_pos_obs_var(0) = fake_pos_obs_var(1) = sq(0.01f); + obs_var(0) = obs_var(1) = sq(0.01f); } else { - fake_pos_obs_var(0) = fake_pos_obs_var(1) = sq(0.5f); + obs_var(0) = obs_var(1) = sq(0.5f); } - _gps_pos_innov.xy() = Vector2f(_state.pos) - _last_known_posNE; + const float innov_gate = 3.f; - const float fake_pos_innov_gate = 3.f; + auto &fake_pos = _aid_src_fake_pos; - if (fuseHorizontalPosition(_gps_pos_innov, fake_pos_innov_gate, fake_pos_obs_var, - _gps_pos_innov_var, _gps_pos_test_ratio, true)) { - _time_last_fake_pos_fuse = _time_last_imu; + for (int i = 0; i < 2; i++) { + fake_pos.observation[i] = _last_known_posNE(i); + fake_pos.observation_variance[i] = obs_var(i); + + fake_pos.innovation[i] = _state.pos(i) - _last_known_posNE(i); + fake_pos.innovation_variance[i] = P(7 + i, 7 + i) + obs_var(i); + fake_pos.test_ratio[i] = sq(fake_pos.innovation[i]) / (sq(innov_gate) * fake_pos.innovation_variance[i]); + + fake_pos.innovation_rejected[i] = (fake_pos.test_ratio[i] > 1.f); + + // always protect against extreme values that could result in a NaN + fake_pos.fusion_enabled[i] = fake_pos.test_ratio[i] < sq(100.0f / innov_gate); + + if (fake_pos.fusion_enabled[i] && !fake_pos.innovation_rejected[i]) { + if (fuseVelPosHeight(fake_pos.innovation[i], fake_pos.innovation_variance[i], 3 + i)) { + fake_pos.fused[i] = true; + fake_pos.time_last_fuse[i] = _time_last_imu; + } + } } + + fake_pos.timestamp_sample = _time_last_imu; } diff --git a/src/modules/ekf2/EKF/vel_pos_fusion.cpp b/src/modules/ekf2/EKF/vel_pos_fusion.cpp index 8826ce4ab8..431fd6d82b 100644 --- a/src/modules/ekf2/EKF/vel_pos_fusion.cpp +++ b/src/modules/ekf2/EKF/vel_pos_fusion.cpp @@ -102,7 +102,7 @@ bool Ekf::fuseVerticalVelocity(const Vector3f &innov, const float innov_gate, co } bool Ekf::fuseHorizontalPosition(const Vector3f &innov, const float innov_gate, const Vector3f &obs_var, - Vector3f &innov_var, Vector2f &test_ratio, bool inhibit_gate) + Vector3f &innov_var, Vector2f &test_ratio) { innov_var(0) = P(7, 7) + obs_var(0); @@ -112,12 +112,7 @@ bool Ekf::fuseHorizontalPosition(const Vector3f &innov, const float innov_gate, const bool innov_check_pass = test_ratio(0) <= 1.0f; - if (innov_check_pass || inhibit_gate) { - if (inhibit_gate && test_ratio(0) > sq(100.0f / innov_gate)) { - // always protect against extreme values that could result in a NaN - return false; - } - + if (innov_check_pass) { _innov_check_fail_status.flags.reject_hor_pos = false; bool fuse_x = fuseVelPosHeight(innov(0), innov_var(0), 3); diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 8ab17c8807..c8a49c6f85 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -614,6 +614,8 @@ void EKF2::Run() UpdateMagCalibration(now); PublishSensorBias(now); + PublishAidSourceStatus(now); + } else { // ekf no update perf_set_elapsed(_ecl_ekf_update_perf, hrt_elapsed_time(&ekf_update_start)); @@ -632,6 +634,12 @@ void EKF2::Run() ScheduleDelayed(100_ms); } +void EKF2::PublishAidSourceStatus(const hrt_abstime ×tamp) +{ + // fake position + PublishAidSourceStatus(_ekf.aid_src_fake_pos(), _status_fake_pos_pub_last, _estimator_aid_src_fake_pos_pub); +} + void EKF2::PublishAttitude(const hrt_abstime ×tamp) { if (_ekf.attitude_valid()) { diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index fe7fbdca63..3c5127cab6 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -135,6 +135,7 @@ private: void Run() override; + void PublishAidSourceStatus(const hrt_abstime ×tamp); void PublishAttitude(const hrt_abstime ×tamp); void PublishBaroBias(const hrt_abstime ×tamp); void PublishEventFlags(const hrt_abstime ×tamp); @@ -167,6 +168,21 @@ private: void UpdateGyroCalibration(const hrt_abstime ×tamp); void UpdateMagCalibration(const hrt_abstime ×tamp); + // publish helper for estimator_aid_source topics + template + void PublishAidSourceStatus(const T &status, hrt_abstime &status_publish_last, uORB::PublicationMulti &pub) + { + if (status.timestamp_sample > status_publish_last) { + // publish if updated + T status_out{status}; + status_out.estimator_instance = _instance; + status_out.timestamp = hrt_absolute_time(); + pub.publish(status_out); + + // record timestamp sample + status_publish_last = status.timestamp_sample; + } + } /* * Calculate filtered WGS84 height from estimated AMSL height @@ -239,6 +255,8 @@ private: hrt_abstime _last_sensor_bias_published{0}; hrt_abstime _last_gps_status_published{0}; + hrt_abstime _status_fake_pos_pub_last{0}; + float _last_baro_bias_published{}; float _airspeed_scale_factor{1.0f}; ///< scale factor correction applied to airspeed measurements @@ -298,6 +316,8 @@ private: uORB::PublicationMulti _estimator_visual_odometry_aligned_pub{ORB_ID(estimator_visual_odometry_aligned)}; uORB::PublicationMulti _yaw_est_pub{ORB_ID(yaw_estimator_status)}; + uORB::PublicationMulti _estimator_aid_src_fake_pos_pub{ORB_ID(estimator_aid_src_fake_pos)}; + // publications with topic dependent on multi-mode uORB::PublicationMulti _attitude_pub; uORB::PublicationMulti _local_position_pub; diff --git a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv index 8276ba5450..d6f7806c33 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -14,8 +14,8 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 1190000,1,-0.0112,-0.0137,-0.0166,0.0163,-0.0049,-0.155,0.00161,-0.000401,-0.0818,-1.25e-07,-6.6e-07,-2.4e-09,4.68e-07,-8.34e-08,-1.35e-08,0.192,0.00189,0.404,0,0,0,0,0,1.85e-06,0.00506,0.00506,0.00108,0.85,0.85,0.491,0.151,0.151,0.328,9.88e-07,9.88e-07,6.56e-07,3.99e-06,3.99e-06,3.99e-06,0,0,0,0,0,0,0,0 1290000,1,-0.0113,-0.0139,-0.0166,0.0212,-0.00611,-0.169,0.00349,-0.000977,-0.098,-1.25e-07,-6.6e-07,-2.4e-09,4.68e-07,-8.34e-08,-1.35e-08,0.192,0.00189,0.404,0,0,0,0,0,2.06e-06,0.0056,0.0056,0.00108,1.03,1.03,0.5,0.214,0.214,0.402,9.88e-07,9.88e-07,5.97e-07,3.99e-06,3.99e-06,3.99e-06,0,0,0,0,0,0,0,0 1390000,1,-0.0114,-0.0142,-0.0166,0.0275,-0.00825,-0.181,0.00597,-0.00168,-0.115,-1.25e-07,-6.6e-07,-2.4e-09,4.68e-07,-8.34e-08,-1.35e-08,0.192,0.00189,0.404,0,0,0,0,0,2.31e-06,0.00618,0.00619,0.00108,1.26,1.26,0.509,0.301,0.301,0.487,9.88e-07,9.88e-07,5.41e-07,3.99e-06,3.99e-06,3.99e-06,0,0,0,0,0,0,0,0 -1490000,1,-0.0114,-0.0143,-0.0166,0.0277,-0.00795,-0.196,0.00506,-0.00142,-0.134,-4.58e-07,-2.01e-06,-2.38e-09,1.16e-06,-2.53e-07,-3.54e-08,0.192,0.00189,0.404,0,0,0,0,0,2.42e-06,0.00637,0.00637,0.00108,1.01,1.01,0.519,0.189,0.189,0.582,9.62e-07,9.62e-07,4.87e-07,3.99e-06,3.99e-06,3.99e-06,0,0,0,0,0,0,0,0 -1590000,1,-0.0114,-0.0146,-0.0166,0.0346,-0.00911,-0.209,0.00815,-0.00227,-0.155,-4.58e-07,-2.01e-06,-2.38e-09,1.16e-06,-2.53e-07,-3.54e-08,0.192,0.00189,0.404,0,0,0,0,0,2.7e-06,0.00702,0.00702,0.00107,1.3,1.3,0.53,0.268,0.268,0.689,9.62e-07,9.62e-07,4.38e-07,3.99e-06,3.99e-06,3.99e-06,0,0,0,0,0,0,0,0 +1490000,1,-0.0114,-0.0143,-0.0166,0.0277,-0.00795,-0.196,0.00506,-0.00142,-0.134,-4.58e-07,-2.01e-06,-2.37e-09,1.16e-06,-2.53e-07,-3.54e-08,0.192,0.00189,0.404,0,0,0,0,0,2.42e-06,0.00637,0.00637,0.00108,1.01,1.01,0.519,0.189,0.189,0.582,9.62e-07,9.62e-07,4.87e-07,3.99e-06,3.99e-06,3.99e-06,0,0,0,0,0,0,0,0 +1590000,1,-0.0114,-0.0146,-0.0166,0.0346,-0.00911,-0.209,0.00815,-0.00227,-0.155,-4.58e-07,-2.01e-06,-2.37e-09,1.16e-06,-2.53e-07,-3.54e-08,0.192,0.00189,0.404,0,0,0,0,0,2.7e-06,0.00702,0.00702,0.00107,1.3,1.3,0.53,0.268,0.268,0.689,9.62e-07,9.62e-07,4.38e-07,3.99e-06,3.99e-06,3.99e-06,0,0,0,0,0,0,0,0 1690000,1,-0.0115,-0.0145,-0.0166,0.0339,-0.0104,-0.221,0.00659,-0.00188,-0.176,-1.15e-06,-4.89e-06,2.07e-09,2.38e-06,-5.49e-07,-7.51e-08,0.192,0.00189,0.404,0,0,0,0,0,2.66e-06,0.00677,0.00677,0.00105,1.11,1.11,0.542,0.179,0.179,0.807,9.06e-07,9.06e-07,3.92e-07,3.98e-06,3.98e-06,3.99e-06,0,0,0,0,0,0,0,0 1790000,1,-0.0115,-0.0148,-0.0167,0.0422,-0.0137,-0.236,0.0104,-0.00306,-0.199,-1.15e-06,-4.89e-06,2.07e-09,2.38e-06,-5.49e-07,-7.51e-08,0.192,0.00189,0.404,0,0,0,0,0,2.96e-06,0.00744,0.00744,0.00104,1.45,1.45,0.554,0.262,0.262,0.936,9.06e-07,9.06e-07,3.51e-07,3.98e-06,3.98e-06,3.99e-06,0,0,0,0,0,0,0,0 1890000,1,-0.0113,-0.0144,-0.0167,0.0382,-0.0124,-0.25,0.00784,-0.00241,-0.223,-2.41e-06,-9.67e-06,1.8e-08,4.1e-06,-9.99e-07,-1.33e-07,0.192,0.00189,0.404,0,0,0,0,0,2.68e-06,0.00658,0.00658,0.00102,1.19,1.19,0.567,0.178,0.178,1.08,8.16e-07,8.16e-07,3.14e-07,3.97e-06,3.97e-06,3.99e-06,0,0,0,0,0,0,0,0 @@ -47,35 +47,35 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 4490000,1,-0.0101,-0.0116,-0.0168,0.0131,-0.0043,-0.602,0.0051,-0.00216,-1.33,-1.46e-05,-5.14e-05,2.32e-07,4.34e-06,-8.5e-07,-1.19e-07,0.192,0.00189,0.404,0,0,0,0,0,5.92e-07,0.00152,0.00152,0.000544,0.549,0.549,1.19,0.187,0.187,10.8,1.02e-07,1.02e-07,3.24e-08,3.92e-06,3.92e-06,3.99e-06,0,0,0,0,0,0,0,0 4590000,1,-0.0101,-0.0114,-0.0168,0.0114,-0.00343,-0.617,0.00359,-0.00141,-1.39,-1.5e-05,-5.26e-05,2.4e-07,3.59e-06,-5.72e-07,-8.71e-08,0.192,0.00189,0.404,0,0,0,0,0,5.02e-07,0.00124,0.00124,0.000533,0.418,0.418,1.23,0.132,0.132,11.5,8.3e-08,8.31e-08,3.04e-08,3.91e-06,3.91e-06,3.99e-06,0,0,0,0,0,0,0,0 4690000,1,-0.0101,-0.0114,-0.0168,0.0125,-0.00448,-0.631,0.00481,-0.00179,-1.45,-1.5e-05,-5.26e-05,2.4e-07,3.59e-06,-5.72e-07,-8.71e-08,0.192,0.00189,0.404,0,0,0,0,0,5.23e-07,0.00134,0.00134,0.000522,0.504,0.504,1.26,0.177,0.177,12.2,8.3e-08,8.31e-08,2.85e-08,3.91e-06,3.91e-06,3.99e-06,0,0,0,0,0,0,0,0 -4790000,1,-0.0101,-0.0112,-0.0168,0.0102,-0.00391,-0.645,0.00335,-0.00124,-1.52,-1.54e-05,-5.37e-05,2.47e-07,2.87e-06,-3.33e-07,-5.74e-08,0.192,0.00189,0.404,0,0,0,0,0,4.47e-07,0.0011,0.0011,0.000512,0.385,0.385,1.3,0.127,0.127,13,6.74e-08,6.74e-08,2.68e-08,3.9e-06,3.9e-06,3.99e-06,0,0,0,0,0,0,0,0 -4890000,1,-0.0101,-0.0113,-0.0168,0.0113,-0.00504,-0.66,0.00445,-0.00168,-1.58,-1.54e-05,-5.37e-05,2.47e-07,2.87e-06,-3.33e-07,-5.74e-08,0.192,0.00189,0.404,0,0,0,0,0,4.65e-07,0.00118,0.00118,0.000502,0.461,0.461,1.34,0.168,0.168,13.7,6.74e-08,6.74e-08,2.52e-08,3.9e-06,3.9e-06,3.99e-06,0,0,0,0,0,0,0,0 +4790000,1,-0.0101,-0.0112,-0.0168,0.0102,-0.00391,-0.645,0.00335,-0.00124,-1.52,-1.54e-05,-5.37e-05,2.47e-07,2.87e-06,-3.32e-07,-5.74e-08,0.192,0.00189,0.404,0,0,0,0,0,4.47e-07,0.0011,0.0011,0.000512,0.385,0.385,1.3,0.127,0.127,13,6.74e-08,6.74e-08,2.68e-08,3.9e-06,3.9e-06,3.99e-06,0,0,0,0,0,0,0,0 +4890000,1,-0.0101,-0.0113,-0.0168,0.0113,-0.00504,-0.66,0.00445,-0.00168,-1.58,-1.54e-05,-5.37e-05,2.47e-07,2.87e-06,-3.32e-07,-5.74e-08,0.192,0.00189,0.404,0,0,0,0,0,4.65e-07,0.00118,0.00118,0.000502,0.461,0.461,1.34,0.168,0.168,13.7,6.74e-08,6.74e-08,2.52e-08,3.9e-06,3.9e-06,3.99e-06,0,0,0,0,0,0,0,0 4990000,1,-0.00999,-0.0112,-0.0168,0.01,-0.00373,-0.675,0.00313,-0.00121,-1.65,-1.57e-05,-5.46e-05,2.53e-07,2.19e-06,-9.75e-08,-2.96e-08,0.192,0.00189,0.404,0,0,0,0,0,4e-07,0.000965,0.000966,0.000492,0.353,0.353,1.37,0.121,0.121,14.6,5.44e-08,5.44e-08,2.38e-08,3.9e-06,3.9e-06,3.99e-06,0,0,0,0,0,0,0,0 5090000,1,-0.01,-0.0112,-0.0168,0.0105,-0.00389,-0.69,0.00416,-0.00158,-1.72,-1.57e-05,-5.46e-05,2.53e-07,2.19e-06,-9.75e-08,-2.96e-08,0.192,0.00189,0.404,0,0,0,0,0,4.14e-07,0.00103,0.00103,0.000483,0.421,0.421,1.41,0.16,0.16,15.4,5.44e-08,5.44e-08,2.24e-08,3.9e-06,3.9e-06,3.99e-06,0,0,0,0,0,0,0,0 -5190000,1,-0.00997,-0.0111,-0.0168,0.00852,-0.00353,-0.703,0.00291,-0.00113,-1.79,-1.59e-05,-5.54e-05,2.58e-07,1.57e-06,1.19e-07,-4.12e-09,0.192,0.00189,0.404,0,0,0,0,0,3.58e-07,0.000848,0.000848,0.000474,0.323,0.323,1.45,0.116,0.116,16.3,4.38e-08,4.38e-08,2.12e-08,3.89e-06,3.89e-06,3.99e-06,0,0,0,0,0,0,0,0 -5290000,1,-0.00992,-0.0111,-0.0168,0.00778,-0.00312,-0.718,0.00373,-0.00148,-1.86,-1.59e-05,-5.54e-05,2.58e-07,1.57e-06,1.19e-07,-4.12e-09,0.192,0.00189,0.404,0,0,0,0,0,3.68e-07,0.000905,0.000905,0.000466,0.384,0.384,1.49,0.152,0.152,17.3,4.38e-08,4.38e-08,2e-08,3.89e-06,3.89e-06,3.99e-06,0,0,0,0,0,0,0,0 +5190000,1,-0.00997,-0.0111,-0.0168,0.00852,-0.00353,-0.703,0.00291,-0.00113,-1.79,-1.59e-05,-5.54e-05,2.58e-07,1.57e-06,1.19e-07,-4.11e-09,0.192,0.00189,0.404,0,0,0,0,0,3.58e-07,0.000848,0.000848,0.000474,0.323,0.323,1.45,0.116,0.116,16.3,4.38e-08,4.38e-08,2.12e-08,3.89e-06,3.89e-06,3.99e-06,0,0,0,0,0,0,0,0 +5290000,1,-0.00992,-0.0111,-0.0168,0.00778,-0.00312,-0.718,0.00373,-0.00148,-1.86,-1.59e-05,-5.54e-05,2.58e-07,1.57e-06,1.19e-07,-4.11e-09,0.192,0.00189,0.404,0,0,0,0,0,3.68e-07,0.000905,0.000905,0.000466,0.384,0.384,1.49,0.152,0.152,17.3,4.38e-08,4.38e-08,2e-08,3.89e-06,3.89e-06,3.99e-06,0,0,0,0,0,0,0,0 5390000,1,-0.00981,-0.0111,-0.0167,0.00451,-0.00239,-0.732,0.00247,-0.001,-1.93,-1.62e-05,-5.6e-05,2.63e-07,1.05e-06,3.08e-07,1.7e-08,0.192,0.00189,0.404,0,0,0,0,0,3.23e-07,0.000744,0.000744,0.000457,0.295,0.295,1.53,0.111,0.111,18.3,3.52e-08,3.52e-08,1.9e-08,3.88e-06,3.88e-06,3.99e-06,0,0,0,0,0,0,0,0 5490000,1,-0.00976,-0.0111,-0.0167,0.00459,-0.00238,-0.745,0.00293,-0.00126,-2,-1.62e-05,-5.6e-05,2.63e-07,1.05e-06,3.08e-07,1.7e-08,0.192,0.00189,0.404,0,0,0,0,0,3.3e-07,0.000792,0.000792,0.000449,0.349,0.349,1.58,0.145,0.145,19.3,3.52e-08,3.52e-08,1.8e-08,3.88e-06,3.88e-06,3.99e-06,0,0,0,0,0,0,0,0 5590000,1,-0.00972,-0.0111,-0.0168,0.00519,-0.00237,-0.76,0.00341,-0.00148,-2.08,-1.62e-05,-5.6e-05,2.63e-07,1.05e-06,3.08e-07,1.7e-08,0.192,0.00189,0.404,0,0,0,0,0,3.38e-07,0.000841,0.000842,0.000442,0.41,0.41,1.62,0.188,0.188,20.4,3.52e-08,3.52e-08,1.7e-08,3.88e-06,3.88e-06,3.99e-06,0,0,0,0,0,0,0,0 5690000,1,-0.00961,-0.011,-0.0167,0.00334,-0.000356,-0.775,0.00226,-0.000943,-2.16,-1.63e-05,-5.64e-05,2.66e-07,6.66e-07,4.59e-07,3.27e-08,0.192,0.00189,0.404,0,0,0,0,0,2.96e-07,0.000694,0.000694,0.000434,0.317,0.317,1.66,0.138,0.138,21.5,2.83e-08,2.83e-08,1.62e-08,3.88e-06,3.88e-06,3.99e-06,0,0,0,0,0,0,0,0 5790000,1,-0.00954,-0.011,-0.0167,0.00364,0.00106,0,0.00258,-0.00091,-365,-1.63e-05,-5.64e-05,2.66e-07,6.66e-07,4.59e-07,3.27e-08,0.192,0.00189,0.404,0,0,0,0,0,3.02e-07,0.000735,0.000735,0.000427,0.371,0.371,10,0.178,0.178,4,2.83e-08,2.83e-08,1.53e-08,3.88e-06,3.88e-06,3.99e-06,0,0,0,0,0,0,0,0 -5890000,1,-0.00949,-0.011,-0.0167,0.00314,0.0023,0.00414,0.00175,-0.000382,-365,-1.64e-05,-5.67e-05,2.68e-07,3.88e-07,5.42e-07,8.17e-09,0.192,0.00189,0.404,0,0,0,0,0,2.7e-07,0.000609,0.000609,0.00042,0.288,0.288,9.76,0.131,0.131,0.471,2.27e-08,2.27e-08,1.46e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0 -5990000,1,-0.00946,-0.011,-0.0167,0.0034,0.00409,0.0213,0.00206,-1.87e-05,-365,-1.64e-05,-5.67e-05,2.68e-07,3.86e-07,5.45e-07,-1.1e-07,0.192,0.00189,0.404,0,0,0,0,0,2.75e-07,0.000643,0.000643,0.000413,0.335,0.335,8.56,0.168,0.168,0.323,2.27e-08,2.27e-08,1.39e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0 +5890000,1,-0.00949,-0.011,-0.0167,0.00314,0.0023,0.00414,0.00175,-0.000382,-365,-1.64e-05,-5.67e-05,2.68e-07,3.88e-07,5.42e-07,8.18e-09,0.192,0.00189,0.404,0,0,0,0,0,2.7e-07,0.000609,0.000609,0.00042,0.288,0.288,9.76,0.131,0.131,0.471,2.27e-08,2.27e-08,1.46e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0 +5990000,1,-0.00946,-0.011,-0.0167,0.0034,0.00409,0.0213,0.00206,-1.86e-05,-365,-1.64e-05,-5.67e-05,2.68e-07,3.86e-07,5.45e-07,-1.1e-07,0.192,0.00189,0.404,0,0,0,0,0,2.75e-07,0.000643,0.000643,0.000413,0.335,0.335,8.56,0.168,0.168,0.323,2.27e-08,2.27e-08,1.39e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0 6090000,1,-0.00942,-0.011,-0.0167,0.00324,0.0055,-0.00339,0.00146,0.00043,-365,-1.64e-05,-5.7e-05,2.67e-07,1.79e-07,5.24e-07,-2.28e-08,0.192,0.00189,0.404,0,0,0,0,0,2.47e-07,0.000536,0.000537,0.000407,0.261,0.261,6.77,0.125,0.125,0.331,1.83e-08,1.83e-08,1.32e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0 6190000,1,-0.00943,-0.0109,-0.0168,0.00331,0.00755,0.00222,0.0018,0.0011,-365,-1.64e-05,-5.7e-05,2.67e-07,1.73e-07,5.29e-07,-2.76e-07,0.192,0.00189,0.404,0,0,0,0,0,2.52e-07,0.000565,0.000565,0.0004,0.303,0.303,4.66,0.159,0.159,0.319,1.83e-08,1.83e-08,1.26e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0 -6290000,1,-0.00945,-0.0109,-0.0168,0.00352,0.00715,-0.0059,0.00135,0.00124,-365,-1.63e-05,-5.71e-05,2.63e-07,-1.78e-10,3.98e-07,-3.37e-07,0.192,0.00189,0.404,0,0,0,0,0,2.3e-07,0.000475,0.000475,0.000394,0.237,0.237,3.09,0.119,0.119,0.295,1.48e-08,1.48e-08,1.2e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0 +6290000,1,-0.00945,-0.0109,-0.0168,0.00352,0.00715,-0.0059,0.00135,0.00124,-365,-1.63e-05,-5.71e-05,2.63e-07,-1.83e-10,3.98e-07,-3.37e-07,0.192,0.00189,0.404,0,0,0,0,0,2.3e-07,0.000475,0.000475,0.000394,0.237,0.237,3.09,0.119,0.119,0.295,1.48e-08,1.48e-08,1.2e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0 6390000,1,-0.00934,-0.0109,-0.0168,0.00395,0.00844,-0.0441,0.00173,0.00203,-365,-1.63e-05,-5.71e-05,2.63e-07,1.35e-08,3.85e-07,2.9e-07,0.192,0.00189,0.404,0,0,0,0,0,2.32e-07,0.000498,0.000499,0.000388,0.274,0.274,2.16,0.151,0.151,0.288,1.48e-08,1.48e-08,1.15e-08,3.87e-06,3.87e-06,3.99e-06,0,0,0,0,0,0,0,0 6490000,1,-0.00939,-0.0109,-0.0168,0.00359,0.0077,-0.048,0.00134,0.00185,-365,-1.61e-05,-5.73e-05,2.58e-07,-1.54e-07,1.8e-07,-1.71e-07,0.192,0.00189,0.404,0,0,0,0,0,2.15e-07,0.000422,0.000422,0.000382,0.215,0.215,1.47,0.113,0.113,0.256,1.2e-08,1.2e-08,1.09e-08,3.86e-06,3.86e-06,3.99e-06,0,0,0,0,0,0,0,0 -6590000,1,-0.00939,-0.0109,-0.0169,0.00353,0.00841,-0.0946,0.0017,0.00262,-365,-1.61e-05,-5.73e-05,2.58e-07,-1.13e-07,1.43e-07,1.72e-06,0.192,0.00189,0.404,0,0,0,0,0,2.18e-07,0.000442,0.000442,0.000377,0.248,0.248,1.03,0.143,0.143,0.229,1.2e-08,1.2e-08,1.05e-08,3.86e-06,3.86e-06,3.99e-06,0,0,0,0,0,0,0,0 -6690000,1,-0.0094,-0.0109,-0.017,0.00346,0.00674,-0.0733,0.0013,0.00216,-365,-1.58e-05,-5.74e-05,2.52e-07,-3.26e-07,-4.56e-08,-1.49e-06,0.192,0.00189,0.404,0,0,0,0,0,2.03e-07,0.000378,0.000378,0.000371,0.196,0.196,0.746,0.108,0.108,0.206,9.76e-09,9.77e-09,1e-08,3.86e-06,3.86e-06,3.99e-06,0,0,0,0,0,0,0,0 -6790000,1,-0.00938,-0.0109,-0.017,0.00318,0.00814,-0.11,0.00165,0.0029,-365,-1.58e-05,-5.74e-05,2.52e-07,-2.73e-07,-9.31e-08,9.41e-07,0.192,0.00189,0.404,0,0,0,0,0,2.04e-07,0.000394,0.000394,0.000366,0.225,0.225,0.577,0.136,0.136,0.196,9.76e-09,9.77e-09,9.57e-09,3.86e-06,3.86e-06,3.99e-06,0,0,0,0,0,0,0,0 +6590000,1,-0.00939,-0.0109,-0.0169,0.00352,0.00841,-0.0946,0.0017,0.00262,-365,-1.61e-05,-5.73e-05,2.58e-07,-1.13e-07,1.43e-07,1.72e-06,0.192,0.00189,0.404,0,0,0,0,0,2.18e-07,0.000442,0.000442,0.000377,0.248,0.248,1.03,0.143,0.143,0.229,1.2e-08,1.2e-08,1.05e-08,3.86e-06,3.86e-06,3.99e-06,0,0,0,0,0,0,0,0 +6690000,1,-0.0094,-0.0109,-0.017,0.00346,0.00674,-0.0733,0.0013,0.00216,-365,-1.58e-05,-5.74e-05,2.52e-07,-3.26e-07,-4.55e-08,-1.49e-06,0.192,0.00189,0.404,0,0,0,0,0,2.03e-07,0.000378,0.000378,0.000371,0.196,0.196,0.746,0.108,0.108,0.206,9.76e-09,9.77e-09,1e-08,3.86e-06,3.86e-06,3.99e-06,0,0,0,0,0,0,0,0 +6790000,1,-0.00938,-0.0109,-0.017,0.00318,0.00814,-0.11,0.00165,0.0029,-365,-1.58e-05,-5.74e-05,2.52e-07,-2.73e-07,-9.31e-08,9.41e-07,0.192,0.00189,0.404,0,0,0,0,0,2.05e-07,0.000394,0.000394,0.000366,0.225,0.225,0.577,0.136,0.136,0.196,9.76e-09,9.77e-09,9.57e-09,3.86e-06,3.86e-06,3.99e-06,0,0,0,0,0,0,0,0 6890000,0.706,0.0013,-0.0143,0.708,0.00244,0.00869,-0.121,0.00124,0.00242,-365,-1.56e-05,-5.75e-05,2.48e-07,-4.13e-07,-3.48e-07,4.85e-07,0.209,0.00206,0.432,0,0,0,0,0,0.00103,0.000339,0.000338,0.00132,0.176,0.176,0.442,0.104,0.104,0.178,7.97e-09,7.98e-09,9.28e-09,3.86e-06,3.86e-06,3.98e-06,0,0,0,0,0,0,0,0 6990000,0.704,0.00139,-0.0142,0.71,0.0024,0.00926,-0.123,0.00147,0.00334,-365,-1.56e-05,-5.75e-05,1.96e-07,-4.79e-07,-2.87e-07,-2.51e-06,0.209,0.00206,0.432,0,0,0,0,0,0.000622,0.000339,0.000339,0.000783,0.178,0.178,0.347,0.128,0.128,0.163,7.97e-09,7.98e-09,9.28e-09,3.86e-06,3.86e-06,3.98e-06,0,0,0,0,0,0,0,0 7090000,0.703,0.0014,-0.0142,0.711,0.00185,0.00855,-0.124,0.00169,0.00421,-365,-1.56e-05,-5.75e-05,1.16e-07,-5.58e-07,-2.14e-07,-6.11e-06,0.209,0.00206,0.432,0,0,0,0,0,0.000475,0.00034,0.000339,0.000593,0.184,0.184,0.287,0.156,0.156,0.156,7.97e-09,7.97e-09,9.28e-09,3.86e-06,3.86e-06,3.97e-06,0,0,0,0,0,0,0,0 7190000,0.703,0.0014,-0.0141,0.711,0.000163,0.00836,-0.145,0.00179,0.00506,-365,-1.56e-05,-5.75e-05,1.08e-07,-5.09e-07,-2.57e-07,-3.87e-06,0.209,0.00206,0.432,0,0,0,0,0,0.000383,0.000341,0.000341,0.000473,0.193,0.193,0.236,0.188,0.188,0.144,7.97e-09,7.97e-09,9.28e-09,3.86e-06,3.86e-06,3.96e-06,0,0,0,0,0,0,0,0 7290000,0.703,0.00142,-0.0141,0.711,-0.00132,0.00825,-0.145,0.00174,0.00587,-365,-1.56e-05,-5.75e-05,1.86e-07,-6.59e-07,-1.32e-07,-1.07e-05,0.209,0.00206,0.432,0,0,0,0,0,0.000326,0.000342,0.000342,0.000399,0.205,0.205,0.198,0.223,0.223,0.134,7.96e-09,7.96e-09,9.27e-09,3.86e-06,3.86e-06,3.95e-06,0,0,0,0,0,0,0,0 7390000,0.703,0.00143,-0.014,0.711,-0.00145,0.00941,-0.157,0.00158,0.00678,-365,-1.56e-05,-5.75e-05,2.7e-07,-6.93e-07,-1.07e-07,-1.22e-05,0.209,0.00206,0.432,0,0,0,0,0,0.000292,0.000344,0.000344,0.000355,0.221,0.221,0.174,0.263,0.263,0.13,7.96e-09,7.96e-09,9.27e-09,3.86e-06,3.86e-06,3.94e-06,0,0,0,0,0,0,0,0 -7490000,0.703,0.00149,-0.014,0.711,-0.00306,0.0095,-0.16,0.00133,0.00771,-365,-1.56e-05,-5.75e-05,3.27e-07,-8.61e-07,3.49e-08,-2e-05,0.209,0.00206,0.432,0,0,0,0,0,0.000264,0.000346,0.000346,0.000318,0.24,0.24,0.152,0.307,0.307,0.122,7.94e-09,7.95e-09,9.26e-09,3.86e-06,3.86e-06,3.92e-06,0,0,0,0,0,0,0,0 -7590000,0.704,0.00149,-0.0139,0.71,-0.00496,0.0104,-0.165,0.000962,0.00872,-365,-1.56e-05,-5.76e-05,5.48e-07,-1.06e-06,1.91e-07,-2.88e-05,0.209,0.00206,0.432,0,0,0,0,0,0.000243,0.000349,0.000349,0.00029,0.263,0.262,0.136,0.358,0.358,0.115,7.94e-09,7.95e-09,9.25e-09,3.86e-06,3.86e-06,3.9e-06,0,0,0,0,0,0,0,0 +7490000,0.703,0.00149,-0.014,0.711,-0.00306,0.0095,-0.16,0.00133,0.00771,-365,-1.56e-05,-5.75e-05,3.27e-07,-8.61e-07,3.5e-08,-2e-05,0.209,0.00206,0.432,0,0,0,0,0,0.000264,0.000346,0.000346,0.000318,0.24,0.24,0.152,0.307,0.307,0.122,7.94e-09,7.95e-09,9.26e-09,3.86e-06,3.86e-06,3.92e-06,0,0,0,0,0,0,0,0 +7590000,0.704,0.00149,-0.0139,0.71,-0.00496,0.0104,-0.165,0.000962,0.00872,-365,-1.56e-05,-5.76e-05,5.48e-07,-1.06e-06,1.92e-07,-2.88e-05,0.209,0.00206,0.432,0,0,0,0,0,0.000243,0.000349,0.000349,0.00029,0.263,0.262,0.136,0.358,0.358,0.115,7.94e-09,7.95e-09,9.25e-09,3.86e-06,3.86e-06,3.9e-06,0,0,0,0,0,0,0,0 7690000,0.704,0.00157,-0.0138,0.71,-0.00677,0.0109,-0.161,0.000372,0.00977,-365,-1.56e-05,-5.76e-05,5.72e-07,-1.51e-06,5.79e-07,-4.94e-05,0.209,0.00206,0.432,0,0,0,0,0,0.000228,0.000352,0.000352,0.000271,0.289,0.289,0.126,0.414,0.414,0.112,7.94e-09,7.95e-09,9.24e-09,3.86e-06,3.86e-06,3.88e-06,0,0,0,0,0,0,0,0 7790000,0.704,0.00159,-0.0138,0.711,-0.00815,0.0114,-0.16,-0.000355,0.0108,-365,-1.56e-05,-5.76e-05,2.37e-07,-1.95e-06,9.71e-07,-6.96e-05,0.209,0.00206,0.432,0,0,0,0,0,0.000215,0.000355,0.000355,0.000253,0.318,0.318,0.116,0.475,0.475,0.107,7.92e-09,7.93e-09,9.22e-09,3.86e-06,3.86e-06,3.84e-06,0,0,0,0,0,0,0,0 7890000,0.704,0.0016,-0.0138,0.71,-0.0109,0.013,-0.157,-0.0013,0.0121,-365,-1.56e-05,-5.76e-05,4.56e-07,-2.52e-06,1.44e-06,-9.52e-05,0.209,0.00206,0.432,0,0,0,0,0,0.000204,0.000359,0.000359,0.000239,0.351,0.351,0.109,0.546,0.546,0.102,7.92e-09,7.93e-09,9.2e-09,3.86e-06,3.86e-06,3.8e-06,0,0,0,0,0,0,0,0 @@ -90,7 +90,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 8790000,0.704,0.00172,-0.0136,0.71,-0.0301,0.0228,-0.152,-0.0189,0.0269,-366,-1.56e-05,-5.76e-05,8.65e-07,-9e-06,7.29e-06,-0.00041,0.209,0.00206,0.432,0,0,0,0,0,0.000164,0.000407,0.000407,0.000181,0.792,0.791,0.0954,1.64,1.64,0.0867,7.72e-09,7.72e-09,8.8e-09,3.85e-06,3.85e-06,3.14e-06,0,0,0,0,0,0,0,0 8890000,0.704,0.00176,-0.0136,0.71,-0.0323,0.0234,-0.151,-0.0221,0.0292,-366,-1.56e-05,-5.76e-05,7.16e-07,-9.86e-06,8e-06,-0.000449,0.209,0.00206,0.432,0,0,0,0,0,0.000162,0.000414,0.000414,0.000178,0.862,0.861,0.0949,1.86,1.86,0.0857,7.72e-09,7.72e-09,8.73e-09,3.85e-06,3.85e-06,3.02e-06,0,0,0,0,0,0,0,0 8990000,0.704,0.00181,-0.0135,0.71,-0.0339,0.0235,-0.142,-0.025,0.031,-365,-1.56e-05,-5.76e-05,2.64e-07,-1.09e-05,9.26e-06,-0.000509,0.209,0.00206,0.432,0,0,0,0,0,0.000161,0.00042,0.00042,0.000176,0.922,0.921,0.0956,2.05,2.05,0.0868,7.65e-09,7.66e-09,8.66e-09,3.84e-06,3.84e-06,2.91e-06,0,0,0,0,0,0,0,0 -9090000,0.704,0.00185,-0.0136,0.71,-0.0366,0.0242,-0.141,-0.0285,0.0334,-366,-1.56e-05,-5.76e-05,-6.81e-09,-1.15e-05,9.77e-06,-0.000537,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000428,0.000428,0.000173,0.999,0.998,0.0949,2.3,2.3,0.086,7.65e-09,7.66e-09,8.58e-09,3.84e-06,3.84e-06,2.78e-06,0,0,0,0,0,0,0,0 +9090000,0.704,0.00185,-0.0136,0.71,-0.0366,0.0242,-0.141,-0.0285,0.0334,-366,-1.56e-05,-5.76e-05,-6.78e-09,-1.15e-05,9.77e-06,-0.000537,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000428,0.000428,0.000173,0.999,0.998,0.0949,2.3,2.3,0.086,7.65e-09,7.66e-09,8.58e-09,3.84e-06,3.84e-06,2.78e-06,0,0,0,0,0,0,0,0 9190000,0.704,0.00186,-0.0136,0.71,-0.0378,0.0245,-0.141,-0.0315,0.035,-366,-1.55e-05,-5.76e-05,1.15e-06,-1.19e-05,1.05e-05,-0.000569,0.209,0.00206,0.432,0,0,0,0,0,0.000158,0.000433,0.000433,0.000171,1.06,1.06,0.094,2.52,2.52,0.0853,7.58e-09,7.59e-09,8.48e-09,3.83e-06,3.83e-06,2.65e-06,0,0,0,0,0,0,0,0 9290000,0.704,0.00185,-0.0136,0.71,-0.0393,0.0255,-0.137,-0.0355,0.0376,-366,-1.55e-05,-5.76e-05,1.32e-06,-1.29e-05,1.13e-05,-0.000615,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.000442,0.000442,0.000169,1.14,1.14,0.0929,2.83,2.83,0.0847,7.58e-09,7.59e-09,8.39e-09,3.83e-06,3.83e-06,2.52e-06,0,0,0,0,0,0,0,0 9390000,0.704,0.00181,-0.0135,0.71,-0.0401,0.0268,-0.135,-0.0383,0.0391,-366,-1.55e-05,-5.75e-05,1.33e-06,-1.32e-05,1.23e-05,-0.000649,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.000445,0.000445,0.000168,1.2,1.2,0.0928,3.07,3.07,0.086,7.5e-09,7.51e-09,8.3e-09,3.82e-06,3.82e-06,2.4e-06,0,0,0,0,0,0,0,0 @@ -102,7 +102,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 9990000,0.704,0.00196,-0.0134,0.71,-0.0498,0.0319,-0.1,-0.062,0.0533,-365,-1.54e-05,-5.75e-05,1.83e-06,-1.71e-05,1.77e-05,-0.000888,0.209,0.00206,0.432,0,0,0,0,0,0.000156,0.000491,0.000491,0.000163,1.7,1.7,0.0827,5.4,5.4,0.0857,7.33e-09,7.33e-09,7.61e-09,3.79e-06,3.79e-06,1.66e-06,0,0,0,0,0,0,0,0 10090000,0.705,0.00197,-0.0134,0.71,-0.0494,0.0306,-0.096,-0.0637,0.0536,-365,-1.53e-05,-5.75e-05,2.07e-06,-1.68e-05,1.9e-05,-0.000914,0.209,0.00206,0.432,0,0,0,0,0,0.000156,0.000491,0.000491,0.000162,1.74,1.74,0.0801,5.67,5.67,0.0848,7.24e-09,7.24e-09,7.47e-09,3.77e-06,3.77e-06,1.54e-06,0,0,0,0,0,0,0,0 10190000,0.704,0.00198,-0.0134,0.71,-0.0512,0.0329,-0.0957,-0.0687,0.0568,-366,-1.54e-05,-5.74e-05,8.27e-07,-1.71e-05,1.93e-05,-0.000928,0.209,0.00206,0.432,0,0,0,0,0,0.000156,0.000502,0.000502,0.000161,1.85,1.85,0.0774,6.28,6.27,0.0839,7.24e-09,7.24e-09,7.33e-09,3.77e-06,3.77e-06,1.44e-06,0,0,0,0,0,0,0,0 -10290000,0.704,0.00193,-0.0134,0.71,-0.0504,0.0315,-0.0832,-0.0697,0.0565,-365,-1.53e-05,-5.74e-05,6.93e-08,-1.73e-05,2.13e-05,-0.000983,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.0005,0.0005,0.000161,1.87,1.87,0.0758,6.51,6.51,0.0847,7.14e-09,7.15e-09,7.21e-09,3.74e-06,3.74e-06,1.35e-06,0,0,0,0,0,0,0,0 +10290000,0.704,0.00193,-0.0134,0.71,-0.0504,0.0315,-0.0832,-0.0697,0.0565,-365,-1.53e-05,-5.74e-05,6.94e-08,-1.73e-05,2.13e-05,-0.000983,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.0005,0.0005,0.000161,1.87,1.87,0.0758,6.51,6.51,0.0847,7.14e-09,7.15e-09,7.21e-09,3.74e-06,3.74e-06,1.35e-06,0,0,0,0,0,0,0,0 10390000,0.704,0.00191,-0.0133,0.71,0.00936,-0.0198,0.00845,0.000863,-0.00177,-365,-1.53e-05,-5.74e-05,1.5e-07,-1.8e-05,2.18e-05,-0.00101,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.000512,0.000512,0.00016,0.252,0.252,0.25,0.252,0.252,0.0753,7.14e-09,7.15e-09,7.07e-09,3.74e-06,3.74e-06,1.26e-06,0,0,0,0,0,0,0,0 10490000,0.704,0.00195,-0.0133,0.71,0.00799,-0.0184,0.0138,0.00171,-0.00366,-365,-1.53e-05,-5.74e-05,-5.75e-07,-1.87e-05,2.24e-05,-0.00105,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.000525,0.000525,0.00016,0.258,0.258,0.248,0.259,0.259,0.0714,7.14e-09,7.15e-09,6.92e-09,3.74e-06,3.74e-06,1.19e-06,0,0,0,0,0,0,0,0 10590000,0.704,0.00204,-0.0134,0.71,0.00751,-0.00779,0.0178,0.0018,-0.000819,-365,-1.53e-05,-5.72e-05,-4.85e-07,-2.11e-05,2.26e-05,-0.00106,0.209,0.00206,0.432,0,0,0,0,0,0.000157,0.00053,0.00053,0.00016,0.132,0.132,0.169,0.13,0.13,0.0672,7.1e-09,7.11e-09,6.77e-09,3.73e-06,3.73e-06,1.14e-06,0,0,0,0,0,0,0,0 @@ -118,12 +118,12 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 11590000,0.704,0.00203,-0.0136,0.71,-0.00298,0.00788,-0.00771,0.0043,-0.00159,-365,-1.46e-05,-5.71e-05,-3.09e-06,-2.57e-05,3.07e-05,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.00038,0.00038,0.000158,0.0887,0.0887,0.045,0.0531,0.0531,0.0628,5.58e-09,5.59e-09,5.34e-09,3.56e-06,3.56e-06,9.9e-07,0,0,0,0,0,0,0,0 11690000,0.704,0.00201,-0.0136,0.71,-0.00606,0.0105,-0.0121,0.00383,-0.000702,-365,-1.46e-05,-5.71e-05,-3.55e-06,-2.56e-05,3.06e-05,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.00039,0.00039,0.000157,0.108,0.108,0.0421,0.0611,0.0611,0.0632,5.58e-09,5.59e-09,5.2e-09,3.56e-06,3.56e-06,9.86e-07,0,0,0,0,0,0,0,0 11790000,0.704,0.00208,-0.0135,0.71,-0.0112,0.0109,-0.0139,0.0017,0.000401,-365,-1.47e-05,-5.7e-05,-3.61e-06,-2.53e-05,2.94e-05,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000334,0.000334,0.000157,0.0865,0.0865,0.0368,0.0512,0.0512,0.0607,5.21e-09,5.22e-09,5.05e-09,3.52e-06,3.53e-06,9.81e-07,0,0,0,0,0,0,0,0 -11890000,0.704,0.00209,-0.0135,0.71,-0.0129,0.0117,-0.015,0.000506,0.00154,-365,-1.48e-05,-5.7e-05,-4.36e-06,-2.53e-05,2.95e-05,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000343,0.000343,0.000157,0.104,0.104,0.0348,0.0594,0.0594,0.0608,5.21e-09,5.22e-09,4.91e-09,3.52e-06,3.53e-06,9.78e-07,0,0,0,0,0,0,0,0 +11890000,0.704,0.00209,-0.0135,0.71,-0.0129,0.0117,-0.015,0.000506,0.00154,-365,-1.48e-05,-5.7e-05,-4.35e-06,-2.53e-05,2.95e-05,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000343,0.000343,0.000157,0.104,0.104,0.0348,0.0594,0.0594,0.0608,5.21e-09,5.22e-09,4.91e-09,3.52e-06,3.53e-06,9.78e-07,0,0,0,0,0,0,0,0 11990000,0.704,0.00211,-0.0135,0.71,-0.0143,0.0121,-0.0201,-0.000443,0.00218,-365,-1.47e-05,-5.71e-05,-4.16e-06,-2.49e-05,3.03e-05,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000296,0.000295,0.000157,0.083,0.083,0.0315,0.05,0.05,0.0594,4.89e-09,4.89e-09,4.79e-09,3.5e-06,3.5e-06,9.73e-07,0,0,0,0,0,0,0,0 12090000,0.704,0.00212,-0.0135,0.71,-0.0158,0.0142,-0.0257,-0.00194,0.00348,-365,-1.47e-05,-5.71e-05,-3.44e-06,-2.48e-05,3.02e-05,-0.00107,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000304,0.000304,0.000156,0.0987,0.0986,0.0301,0.0584,0.0584,0.0593,4.89e-09,4.89e-09,4.65e-09,3.5e-06,3.5e-06,9.71e-07,0,0,0,0,0,0,0,0 12190000,0.704,0.0018,-0.0136,0.71,-0.00961,0.0118,-0.0208,0.00113,0.00192,-365,-1.4e-05,-5.76e-05,-3.16e-06,-2.29e-05,3.6e-05,-0.00108,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000265,0.000265,0.000156,0.0786,0.0786,0.0276,0.0492,0.0492,0.0572,4.61e-09,4.62e-09,4.52e-09,3.49e-06,3.49e-06,9.63e-07,0,0,0,0,0,0,0,0 12290000,0.704,0.00177,-0.0136,0.71,-0.0124,0.0133,-0.0203,3.95e-05,0.00318,-365,-1.4e-05,-5.76e-05,-2.95e-06,-2.29e-05,3.61e-05,-0.00108,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000272,0.000272,0.000156,0.0926,0.0926,0.0272,0.0577,0.0577,0.0578,4.61e-09,4.62e-09,4.4e-09,3.49e-06,3.49e-06,9.61e-07,0,0,0,0,0,0,0,0 -12390000,0.704,0.00148,-0.0136,0.71,-0.00698,0.0104,-0.0189,0.00257,0.00173,-365,-1.35e-05,-5.81e-05,-3.45e-06,-2.15e-05,4.01e-05,-0.00108,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000241,0.000241,0.000155,0.074,0.074,0.0255,0.0488,0.0488,0.0558,4.38e-09,4.38e-09,4.28e-09,3.48e-06,3.48e-06,9.51e-07,0,0,0,0,0,0,0,0 +12390000,0.704,0.00148,-0.0136,0.71,-0.00698,0.0104,-0.0189,0.00257,0.00173,-365,-1.35e-05,-5.81e-05,-3.44e-06,-2.15e-05,4.01e-05,-0.00108,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000241,0.000241,0.000155,0.074,0.074,0.0255,0.0488,0.0488,0.0558,4.38e-09,4.38e-09,4.28e-09,3.48e-06,3.48e-06,9.51e-07,0,0,0,0,0,0,0,0 12490000,0.704,0.00146,-0.0136,0.71,-0.0084,0.0123,-0.0219,0.00182,0.00287,-365,-1.35e-05,-5.81e-05,-4.12e-06,-2.15e-05,4.01e-05,-0.00108,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000248,0.000248,0.000155,0.0864,0.0864,0.0253,0.0572,0.0572,0.0556,4.38e-09,4.38e-09,4.15e-09,3.48e-06,3.48e-06,9.48e-07,0,0,0,0,0,0,0,0 12590000,0.704,0.00154,-0.0134,0.71,-0.0152,0.0104,-0.0274,-0.00301,0.00158,-365,-1.4e-05,-5.83e-05,-4.04e-06,-1.93e-05,3.79e-05,-0.00108,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.000224,0.000224,0.000155,0.0695,0.0695,0.0244,0.0485,0.0485,0.0545,4.17e-09,4.17e-09,4.04e-09,3.47e-06,3.47e-06,9.36e-07,0,0,0,0,0,0,0,0 12690000,0.704,0.00158,-0.0134,0.71,-0.0159,0.0118,-0.031,-0.00459,0.0027,-365,-1.4e-05,-5.83e-05,-4.47e-06,-1.93e-05,3.79e-05,-0.00108,0.209,0.00206,0.432,0,0,0,0,0,0.000159,0.00023,0.00023,0.000155,0.0804,0.0804,0.0246,0.0568,0.0568,0.0543,4.17e-09,4.17e-09,3.92e-09,3.47e-06,3.47e-06,9.32e-07,0,0,0,0,0,0,0,0 @@ -140,7 +140,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 13790000,0.704,0.000721,-0.0133,0.71,6.74e-05,0.00364,-0.0313,0.00309,-0.000477,-365,-1.21e-05,-5.98e-05,-1.49e-06,-2.24e-05,4.01e-05,-0.00115,0.209,0.00206,0.432,0,0,0,0,0,0.000156,0.000183,0.000183,0.000151,0.0491,0.0491,0.0279,0.0474,0.0474,0.0493,3.23e-09,3.24e-09,2.83e-09,3.47e-06,3.47e-06,7.42e-07,0,0,0,0,0,0,0,0 13890000,0.704,0.000689,-0.0133,0.71,0.0004,0.00355,-0.0356,0.00311,-0.000139,-365,-1.21e-05,-5.98e-05,-1.02e-06,-2.23e-05,4e-05,-0.00115,0.209,0.00206,0.432,0,0,0,0,0,0.000156,0.000189,0.000188,0.00015,0.0555,0.0555,0.0292,0.0548,0.0548,0.0503,3.24e-09,3.24e-09,2.76e-09,3.47e-06,3.47e-06,7.32e-07,0,0,0,0,0,0,0,0 13990000,0.704,0.000623,-0.0133,0.71,0.000855,0.00112,-0.0348,0.00407,-0.00186,-365,-1.19e-05,-6.01e-05,-9.04e-07,-2.4e-05,3.92e-05,-0.00116,0.209,0.00206,0.432,0,0,0,0,0,0.000156,0.000181,0.000181,0.00015,0.047,0.047,0.0288,0.0472,0.0472,0.0495,3.09e-09,3.1e-09,2.68e-09,3.46e-06,3.46e-06,6.95e-07,0,0,0,0,0,0,0,0 -14090000,0.704,0.000605,-0.0133,0.71,0.00075,0.00126,-0.0361,0.00413,-0.00176,-365,-1.19e-05,-6.01e-05,-6.82e-08,-2.4e-05,3.92e-05,-0.00115,0.209,0.00206,0.432,0,0,0,0,0,0.000155,0.000187,0.000186,0.000149,0.053,0.053,0.0298,0.0545,0.0545,0.05,3.09e-09,3.1e-09,2.6e-09,3.46e-06,3.46e-06,6.83e-07,0,0,0,0,0,0,0,0 +14090000,0.704,0.000605,-0.0133,0.71,0.00075,0.00126,-0.0361,0.00413,-0.00176,-365,-1.19e-05,-6.01e-05,-6.81e-08,-2.4e-05,3.92e-05,-0.00115,0.209,0.00206,0.432,0,0,0,0,0,0.000155,0.000187,0.000186,0.000149,0.053,0.053,0.0298,0.0545,0.0545,0.05,3.09e-09,3.1e-09,2.6e-09,3.46e-06,3.46e-06,6.83e-07,0,0,0,0,0,0,0,0 14190000,0.705,0.0005,-0.0134,0.71,0.00426,0.000711,-0.0377,0.00635,-0.0015,-365,-1.15e-05,-6.02e-05,3.71e-07,-2.43e-05,3.68e-05,-0.00116,0.209,0.00206,0.432,0,0,0,0,0,0.000155,0.00018,0.00018,0.000149,0.0452,0.0452,0.0295,0.047,0.047,0.0499,2.95e-09,2.95e-09,2.53e-09,3.46e-06,3.46e-06,6.47e-07,0,0,0,0,0,0,0,0 14290000,0.705,0.000511,-0.0133,0.709,0.00488,0.00149,-0.0367,0.00681,-0.00141,-365,-1.15e-05,-6.02e-05,6.89e-07,-2.44e-05,3.69e-05,-0.00116,0.209,0.00206,0.432,0,0,0,0,0,0.000155,0.000185,0.000185,0.000149,0.051,0.051,0.0304,0.0541,0.0541,0.0505,2.95e-09,2.95e-09,2.45e-09,3.46e-06,3.46e-06,6.34e-07,0,0,0,0,0,0,0,0 14390000,0.705,0.00042,-0.0133,0.709,0.00685,0.00239,-0.0386,0.00828,-0.00121,-365,-1.12e-05,-6.02e-05,1.5e-06,-2.48e-05,3.47e-05,-0.00116,0.209,0.00206,0.432,0,0,0,0,0,0.000154,0.000179,0.000178,0.000148,0.0437,0.0437,0.0297,0.0468,0.0468,0.0498,2.81e-09,2.81e-09,2.38e-09,3.45e-06,3.45e-06,5.96e-07,0,0,0,0,0,0,0,0 @@ -153,7 +153,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 15090000,0.705,0.000282,-0.0128,0.709,0.00242,-0.00181,-0.0363,0.00305,-0.00294,-365,-1.2e-05,-6.06e-05,2.58e-06,-2.85e-05,4.18e-05,-0.0012,0.209,0.00206,0.432,0,0,0,0,0,0.000151,0.000179,0.000179,0.000145,0.0457,0.0457,0.0296,0.053,0.053,0.0514,2.37e-09,2.37e-09,1.95e-09,3.42e-06,3.42e-06,4.38e-07,0,0,0,0,0,0,0,0 15190000,0.705,0.000293,-0.0128,0.709,0.00199,-0.000586,-0.0338,0.00245,-0.00232,-365,-1.21e-05,-6.06e-05,2.48e-06,-2.82e-05,4.25e-05,-0.00121,0.209,0.00206,0.432,0,0,0,0,0,0.000151,0.000173,0.000173,0.000145,0.0399,0.0399,0.0287,0.0461,0.0461,0.0512,2.22e-09,2.22e-09,1.9e-09,3.41e-06,3.41e-06,4.09e-07,0,0,0,0,0,0,0,0 15290000,0.705,0.000254,-0.0129,0.709,0.00244,-0.000391,-0.0314,0.00268,-0.00238,-365,-1.21e-05,-6.06e-05,2.82e-06,-2.84e-05,4.27e-05,-0.00122,0.209,0.00206,0.432,0,0,0,0,0,0.000151,0.000177,0.000177,0.000145,0.0449,0.0449,0.0289,0.0527,0.0527,0.0519,2.22e-09,2.22e-09,1.84e-09,3.41e-06,3.41e-06,3.96e-07,0,0,0,0,0,0,0,0 -15390000,0.705,0.000254,-0.0128,0.709,0.00186,-6.42e-05,-0.0291,0.000233,-0.00193,-365,-1.22e-05,-6.06e-05,3.57e-06,-2.83e-05,4.39e-05,-0.00123,0.209,0.00206,0.432,0,0,0,0,0,0.00015,0.000171,0.000171,0.000144,0.0393,0.0393,0.0277,0.046,0.046,0.051,2.07e-09,2.07e-09,1.79e-09,3.39e-06,3.39e-06,3.68e-07,0,0,0,0,0,0,0,0 +15390000,0.705,0.000254,-0.0128,0.709,0.00186,-6.43e-05,-0.0291,0.000233,-0.00193,-365,-1.22e-05,-6.06e-05,3.57e-06,-2.83e-05,4.39e-05,-0.00123,0.209,0.00206,0.432,0,0,0,0,0,0.00015,0.000171,0.000171,0.000144,0.0393,0.0393,0.0277,0.046,0.046,0.051,2.07e-09,2.07e-09,1.79e-09,3.39e-06,3.39e-06,3.68e-07,0,0,0,0,0,0,0,0 15490000,0.705,0.000273,-0.0128,0.709,0.003,-0.000423,-0.0291,0.000486,-0.00197,-365,-1.22e-05,-6.06e-05,3.11e-06,-2.82e-05,4.38e-05,-0.00122,0.209,0.00206,0.432,0,0,0,0,0,0.00015,0.000175,0.000175,0.000144,0.0442,0.0442,0.0281,0.0525,0.0525,0.0522,2.07e-09,2.07e-09,1.75e-09,3.39e-06,3.39e-06,3.57e-07,0,0,0,0,0,0,0,0 15590000,0.705,0.000283,-0.0128,0.709,0.00128,-0.000434,-0.0275,-0.00163,-0.00163,-365,-1.24e-05,-6.05e-05,2.8e-06,-2.8e-05,4.51e-05,-0.00123,0.209,0.00206,0.432,0,0,0,0,0,0.00015,0.000169,0.000168,0.000144,0.0387,0.0387,0.0269,0.0458,0.0458,0.0513,1.93e-09,1.93e-09,1.7e-09,3.37e-06,3.37e-06,3.31e-07,0,0,0,0,0,0,0,0 15690000,0.705,0.000287,-0.0128,0.709,0.00148,-0.00058,-0.0279,-0.00151,-0.00167,-365,-1.24e-05,-6.05e-05,2.77e-06,-2.8e-05,4.51e-05,-0.00123,0.209,0.00206,0.432,0,0,0,0,0,0.000149,0.000173,0.000173,0.000143,0.0436,0.0436,0.027,0.0524,0.0524,0.0518,1.93e-09,1.93e-09,1.65e-09,3.37e-06,3.37e-06,3.19e-07,0,0,0,0,0,0,0,0 @@ -165,7 +165,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 16290000,0.706,0.000176,-0.0128,0.708,0.00628,-0.00384,-0.0197,-0.000119,-0.0037,-365,-1.25e-05,-6.08e-05,4.75e-06,-3.1e-05,4.77e-05,-0.00125,0.209,0.00206,0.432,0,0,0,0,0,0.000147,0.000164,0.000163,0.000141,0.042,0.042,0.0237,0.0519,0.0519,0.0513,1.51e-09,1.52e-09,1.4e-09,3.32e-06,3.32e-06,2.31e-07,0,0,0,0,0,0,0,0 16390000,0.706,0.000158,-0.0128,0.708,0.0053,-0.0041,-0.0187,-0.000337,-0.00295,-365,-1.26e-05,-6.07e-05,4.52e-06,-2.98e-05,4.93e-05,-0.00126,0.209,0.00206,0.432,0,0,0,0,0,0.000146,0.000157,0.000157,0.00014,0.0369,0.0369,0.0226,0.0454,0.0454,0.0503,1.39e-09,1.39e-09,1.37e-09,3.3e-06,3.3e-06,2.15e-07,0,0,0,0,0,0,0,0 16490000,0.706,0.000175,-0.0128,0.708,0.00442,-0.00362,-0.0216,0.000121,-0.00333,-365,-1.26e-05,-6.07e-05,4.63e-06,-2.97e-05,4.92e-05,-0.00125,0.209,0.00206,0.432,0,0,0,0,0,0.000146,0.00016,0.00016,0.00014,0.0414,0.0414,0.0227,0.0518,0.0518,0.0513,1.39e-09,1.39e-09,1.33e-09,3.3e-06,3.3e-06,2.08e-07,0,0,0,0,0,0,0,0 -16590000,0.706,0.000418,-0.0128,0.708,0.00097,-0.000925,-0.0219,-0.00271,8.84e-06,-365,-1.31e-05,-6.02e-05,4.68e-06,-2.36e-05,5.51e-05,-0.00126,0.209,0.00206,0.432,0,0,0,0,0,0.000146,0.000153,0.000153,0.00014,0.0365,0.0365,0.0217,0.0454,0.0454,0.0502,1.27e-09,1.27e-09,1.3e-09,3.28e-06,3.28e-06,1.94e-07,0,0,0,0,0,0,0,0 +16590000,0.706,0.000418,-0.0128,0.708,0.00097,-0.000925,-0.0219,-0.00271,8.83e-06,-365,-1.31e-05,-6.02e-05,4.68e-06,-2.36e-05,5.51e-05,-0.00126,0.209,0.00206,0.432,0,0,0,0,0,0.000146,0.000153,0.000153,0.00014,0.0365,0.0365,0.0217,0.0454,0.0454,0.0502,1.27e-09,1.27e-09,1.3e-09,3.28e-06,3.28e-06,1.94e-07,0,0,0,0,0,0,0,0 16690000,0.706,0.000408,-0.0127,0.708,0.0011,-0.000426,-0.0183,-0.00258,-5.52e-05,-365,-1.31e-05,-6.02e-05,4.37e-06,-2.37e-05,5.52e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000145,0.000156,0.000156,0.000139,0.0408,0.0408,0.0215,0.0517,0.0517,0.0504,1.27e-09,1.27e-09,1.26e-09,3.28e-06,3.28e-06,1.86e-07,0,0,0,0,0,0,0,0 16790000,0.706,0.000542,-0.0127,0.708,-0.00216,0.00175,-0.0173,-0.00487,0.0026,-365,-1.34e-05,-5.98e-05,4.38e-06,-1.87e-05,6.01e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000145,0.00015,0.00015,0.000139,0.036,0.036,0.0207,0.0453,0.0453,0.0501,1.16e-09,1.16e-09,1.24e-09,3.26e-06,3.26e-06,1.75e-07,0,0,0,0,0,0,0,0 16890000,0.706,0.000561,-0.0127,0.708,-0.0025,0.00264,-0.0146,-0.00508,0.0028,-365,-1.35e-05,-5.98e-05,4.21e-06,-1.87e-05,6.02e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000145,0.000153,0.000153,0.000139,0.0402,0.0402,0.0205,0.0516,0.0516,0.0502,1.16e-09,1.16e-09,1.2e-09,3.26e-06,3.26e-06,1.68e-07,0,0,0,0,0,0,0,0 @@ -177,32 +177,32 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 17490000,0.706,0.00039,-0.0125,0.708,0.00221,0.00135,-0.00595,-0.00469,-0.00139,-365,-1.36e-05,-6.04e-05,4.12e-06,-2.77e-05,6.32e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.000142,0.000142,0.000141,0.000136,0.0382,0.0382,0.0177,0.0513,0.0513,0.0488,8.67e-10,8.68e-10,1.04e-09,3.21e-06,3.21e-06,1.25e-07,0,0,0,0,0,0,0,0 17590000,0.706,0.0003,-0.0124,0.708,0.00357,0.000153,-0.00041,-0.00391,-0.0025,-365,-1.36e-05,-6.06e-05,4.21e-06,-3.01e-05,6.34e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000142,0.000136,0.000136,0.000136,0.0336,0.0336,0.017,0.045,0.045,0.0478,7.86e-10,7.87e-10,1.01e-09,3.19e-06,3.19e-06,1.18e-07,0,0,0,0,0,0,0,0 17690000,0.706,0.000271,-0.0124,0.708,0.0044,0.00088,-0.000986,-0.0035,-0.00247,-365,-1.36e-05,-6.06e-05,4.33e-06,-3.01e-05,6.34e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000142,0.000138,0.000138,0.000136,0.0374,0.0374,0.0167,0.0512,0.0512,0.0478,7.86e-10,7.87e-10,9.86e-10,3.19e-06,3.19e-06,1.14e-07,0,0,0,0,0,0,0,0 -17790000,0.706,0.000178,-0.0124,0.708,0.00705,0.000571,-0.00219,-0.00229,-0.00212,-365,-1.34e-05,-6.06e-05,5e-06,-3.01e-05,6.07e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.000141,0.000133,0.000132,0.000135,0.033,0.033,0.0162,0.0449,0.0449,0.0475,7.12e-10,7.13e-10,9.65e-10,3.18e-06,3.18e-06,1.08e-07,0,0,0,0,0,0,0,0 -17890000,0.706,0.000188,-0.0124,0.708,0.00853,-0.000172,-0.00205,-0.00151,-0.00206,-365,-1.34e-05,-6.06e-05,5.25e-06,-3.01e-05,6.06e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.000141,0.000135,0.000134,0.000135,0.0366,0.0366,0.016,0.0511,0.0511,0.0475,7.12e-10,7.13e-10,9.41e-10,3.18e-06,3.18e-06,1.04e-07,0,0,0,0,0,0,0,0 -17990000,0.706,0.000129,-0.0125,0.708,0.0103,-0.00193,-0.000714,-0.000757,-0.00179,-365,-1.34e-05,-6.06e-05,5.16e-06,-2.99e-05,5.91e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.00014,0.000129,0.000129,0.000135,0.0323,0.0323,0.0154,0.0449,0.0449,0.0466,6.45e-10,6.46e-10,9.18e-10,3.16e-06,3.16e-06,9.82e-08,0,0,0,0,0,0,0,0 +17790000,0.706,0.000178,-0.0124,0.708,0.00705,0.000572,-0.00219,-0.00229,-0.00212,-365,-1.34e-05,-6.06e-05,5e-06,-3.01e-05,6.07e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.000141,0.000133,0.000132,0.000135,0.033,0.033,0.0162,0.0449,0.0449,0.0475,7.12e-10,7.13e-10,9.65e-10,3.18e-06,3.18e-06,1.08e-07,0,0,0,0,0,0,0,0 +17890000,0.706,0.000188,-0.0124,0.708,0.00853,-0.000171,-0.00205,-0.00151,-0.00206,-365,-1.34e-05,-6.06e-05,5.25e-06,-3.01e-05,6.06e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.000141,0.000135,0.000134,0.000135,0.0366,0.0366,0.016,0.0511,0.0511,0.0475,7.12e-10,7.13e-10,9.41e-10,3.18e-06,3.18e-06,1.04e-07,0,0,0,0,0,0,0,0 +17990000,0.706,0.000129,-0.0125,0.708,0.0103,-0.00193,-0.000713,-0.000757,-0.00179,-365,-1.34e-05,-6.06e-05,5.16e-06,-2.99e-05,5.91e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.00014,0.000129,0.000129,0.000135,0.0323,0.0323,0.0154,0.0449,0.0449,0.0466,6.45e-10,6.46e-10,9.18e-10,3.16e-06,3.16e-06,9.82e-08,0,0,0,0,0,0,0,0 18090000,0.706,0.000135,-0.0125,0.708,0.0109,-0.00208,0.00168,0.000308,-0.00202,-365,-1.34e-05,-6.06e-05,4.7e-06,-2.99e-05,5.92e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.00014,0.000131,0.000131,0.000134,0.0358,0.0358,0.0153,0.0509,0.0509,0.0471,6.45e-10,6.46e-10,8.99e-10,3.16e-06,3.16e-06,9.52e-08,0,0,0,0,0,0,0,0 18190000,0.706,9.86e-05,-0.0124,0.708,0.0116,-0.00103,0.00308,0.00123,-0.00157,-365,-1.34e-05,-6.05e-05,4.94e-06,-2.93e-05,5.93e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.00014,0.000126,0.000126,0.000134,0.0316,0.0316,0.0147,0.0448,0.0448,0.0463,5.85e-10,5.85e-10,8.78e-10,3.15e-06,3.15e-06,9.02e-08,0,0,0,0,0,0,0,0 18290000,0.706,4.04e-05,-0.0124,0.708,0.0116,-0.00158,0.00426,0.00239,-0.0017,-365,-1.34e-05,-6.05e-05,4.74e-06,-2.93e-05,5.94e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000139,0.000128,0.000128,0.000134,0.035,0.035,0.0145,0.0508,0.0508,0.0462,5.85e-10,5.85e-10,8.57e-10,3.15e-06,3.15e-06,8.71e-08,0,0,0,0,0,0,0,0 -18390000,0.706,5.25e-05,-0.0124,0.708,0.013,4.8e-05,0.00551,0.00299,-0.00128,-365,-1.34e-05,-6.05e-05,5.08e-06,-2.88e-05,5.99e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000139,0.000123,0.000123,0.000133,0.0309,0.0309,0.014,0.0447,0.0447,0.0454,5.3e-10,5.3e-10,8.36e-10,3.14e-06,3.14e-06,8.27e-08,0,0,0,0,0,0,0,0 +18390000,0.706,5.25e-05,-0.0124,0.708,0.013,4.79e-05,0.00551,0.00299,-0.00128,-365,-1.34e-05,-6.05e-05,5.08e-06,-2.88e-05,5.99e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000139,0.000123,0.000123,0.000133,0.0309,0.0309,0.014,0.0447,0.0447,0.0454,5.3e-10,5.3e-10,8.36e-10,3.14e-06,3.14e-06,8.27e-08,0,0,0,0,0,0,0,0 18490000,0.706,6.8e-05,-0.0124,0.708,0.0138,0.000479,0.00517,0.00438,-0.00125,-365,-1.34e-05,-6.05e-05,5.15e-06,-2.88e-05,5.99e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000139,0.000125,0.000125,0.000133,0.0342,0.0342,0.0139,0.0506,0.0506,0.0458,5.3e-10,5.3e-10,8.19e-10,3.14e-06,3.14e-06,8.03e-08,0,0,0,0,0,0,0,0 18590000,0.706,6.86e-05,-0.0123,0.708,0.0129,0.000693,0.00344,0.00333,-0.00108,-365,-1.36e-05,-6.05e-05,5.56e-06,-2.88e-05,6.27e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000139,0.000121,0.000121,0.000133,0.0302,0.0302,0.0134,0.0446,0.0446,0.045,4.8e-10,4.81e-10,8e-10,3.13e-06,3.13e-06,7.64e-08,0,0,0,0,0,0,0,0 -18690000,0.706,3.8e-05,-0.0123,0.708,0.0132,1.31e-05,0.00161,0.00463,-0.00102,-365,-1.36e-05,-6.05e-05,5.42e-06,-2.87e-05,6.27e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000138,0.000122,0.000122,0.000132,0.0334,0.0334,0.0133,0.0505,0.0505,0.0449,4.81e-10,4.81e-10,7.82e-10,3.13e-06,3.13e-06,7.39e-08,0,0,0,0,0,0,0,0 +18690000,0.706,3.8e-05,-0.0123,0.708,0.0132,1.3e-05,0.00161,0.00463,-0.00102,-365,-1.36e-05,-6.05e-05,5.42e-06,-2.87e-05,6.27e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000138,0.000122,0.000122,0.000132,0.0334,0.0334,0.0133,0.0505,0.0505,0.0449,4.81e-10,4.81e-10,7.82e-10,3.13e-06,3.13e-06,7.39e-08,0,0,0,0,0,0,0,0 18790000,0.706,6.44e-05,-0.0123,0.708,0.0117,0.000295,0.00138,0.00354,-0.000809,-365,-1.38e-05,-6.05e-05,5.27e-06,-2.86e-05,6.54e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000138,0.000118,0.000118,0.000132,0.0295,0.0295,0.0129,0.0445,0.0445,0.0447,4.36e-10,4.36e-10,7.66e-10,3.12e-06,3.12e-06,7.08e-08,0,0,0,0,0,0,0,0 18890000,0.706,8.79e-05,-0.0123,0.708,0.0123,0.000805,0.00204,0.00474,-0.00072,-365,-1.37e-05,-6.05e-05,5.67e-06,-2.86e-05,6.54e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000138,0.000119,0.000119,0.000132,0.0326,0.0326,0.0128,0.0503,0.0503,0.0446,4.36e-10,4.36e-10,7.48e-10,3.12e-06,3.12e-06,6.85e-08,0,0,0,0,0,0,0,0 18990000,0.707,7.36e-05,-0.0123,0.708,0.0136,0.00169,0.000837,0.00612,-0.000603,-365,-1.37e-05,-6.05e-05,5.82e-06,-2.87e-05,6.45e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000137,0.000116,0.000116,0.000132,0.0288,0.0288,0.0123,0.0444,0.0444,0.0438,3.96e-10,3.97e-10,7.31e-10,3.11e-06,3.11e-06,6.54e-08,0,0,0,0,0,0,0,0 19090000,0.707,5.84e-05,-0.0122,0.708,0.0142,0.0023,0.00391,0.0075,-0.000376,-365,-1.37e-05,-6.05e-05,5.79e-06,-2.87e-05,6.45e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000137,0.000117,0.000117,0.000131,0.0317,0.0317,0.0123,0.0501,0.0501,0.0442,3.96e-10,3.97e-10,7.17e-10,3.11e-06,3.11e-06,6.37e-08,0,0,0,0,0,0,0,0 19190000,0.707,5.97e-05,-0.0121,0.708,0.0142,0.00228,0.00399,0.00837,-0.000352,-365,-1.37e-05,-6.05e-05,5.94e-06,-2.9e-05,6.42e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000137,0.000113,0.000113,0.000131,0.0281,0.0281,0.0119,0.0442,0.0442,0.0435,3.61e-10,3.61e-10,7.01e-10,3.1e-06,3.1e-06,6.09e-08,0,0,0,0,0,0,0,0 19290000,0.707,8.28e-05,-0.0121,0.708,0.0146,0.00154,0.00673,0.00977,-0.000143,-365,-1.37e-05,-6.05e-05,5.73e-06,-2.9e-05,6.42e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000136,0.000115,0.000115,0.000131,0.0309,0.0309,0.0117,0.0499,0.0499,0.0433,3.61e-10,3.61e-10,6.85e-10,3.1e-06,3.1e-06,5.91e-08,0,0,0,0,0,0,0,0 -19390000,0.707,9.15e-05,-0.012,0.708,0.0121,0.000595,0.0106,0.00783,-0.000181,-365,-1.39e-05,-6.06e-05,5.88e-06,-2.92e-05,6.71e-05,-0.00131,0.209,0.00206,0.432,0,0,0,0,0,0.000136,0.000111,0.000111,0.000131,0.0275,0.0275,0.0115,0.0441,0.0441,0.0431,3.29e-10,3.29e-10,6.72e-10,3.09e-06,3.09e-06,5.69e-08,0,0,0,0,0,0,0,0 +19390000,0.707,9.15e-05,-0.012,0.708,0.0121,0.000594,0.0106,0.00783,-0.000181,-365,-1.39e-05,-6.06e-05,5.88e-06,-2.92e-05,6.71e-05,-0.00131,0.209,0.00206,0.432,0,0,0,0,0,0.000136,0.000111,0.000111,0.000131,0.0275,0.0275,0.0115,0.0441,0.0441,0.0431,3.29e-10,3.29e-10,6.72e-10,3.09e-06,3.09e-06,5.69e-08,0,0,0,0,0,0,0,0 19490000,0.707,0.000115,-0.012,0.707,0.0112,-0.000105,0.00696,0.00898,-0.00016,-365,-1.39e-05,-6.06e-05,6.18e-06,-2.92e-05,6.71e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000136,0.000112,0.000112,0.00013,0.0301,0.0301,0.0113,0.0498,0.0498,0.043,3.29e-10,3.29e-10,6.57e-10,3.09e-06,3.09e-06,5.53e-08,0,0,0,0,0,0,0,0 19590000,0.707,0.000161,-0.0119,0.707,0.00927,-0.00115,0.00631,0.00725,-0.000203,-365,-1.4e-05,-6.06e-05,6.55e-06,-2.92e-05,6.95e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000135,0.000109,0.000109,0.00013,0.0268,0.0268,0.011,0.044,0.044,0.0423,3e-10,3e-10,6.43e-10,3.08e-06,3.08e-06,5.31e-08,0,0,0,0,0,0,0,0 19690000,0.707,0.000161,-0.012,0.707,0.00962,-0.00333,0.00785,0.0082,-0.000432,-365,-1.4e-05,-6.06e-05,6.32e-06,-2.92e-05,6.95e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000135,0.00011,0.00011,0.00013,0.0294,0.0294,0.0109,0.0495,0.0495,0.0422,3e-10,3e-10,6.29e-10,3.08e-06,3.08e-06,5.16e-08,0,0,0,0,0,0,0,0 19790000,0.707,0.000225,-0.0119,0.707,0.00733,-0.00418,0.00835,0.00664,-0.000349,-365,-1.41e-05,-6.05e-05,6.33e-06,-2.87e-05,7.14e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000135,0.000108,0.000107,0.000129,0.0261,0.0261,0.0106,0.0438,0.0438,0.042,2.74e-10,2.74e-10,6.17e-10,3.07e-06,3.07e-06,5e-08,0,0,0,0,0,0,0,0 19890000,0.707,0.000173,-0.0119,0.707,0.00608,-0.00445,0.00953,0.00731,-0.000795,-365,-1.41e-05,-6.05e-05,6.75e-06,-2.87e-05,7.14e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000135,0.000108,0.000108,0.000129,0.0286,0.0286,0.0105,0.0493,0.0493,0.0419,2.74e-10,2.74e-10,6.04e-10,3.07e-06,3.07e-06,5e-08,0,0,0,0,0,0,0,0 19990000,0.707,0.000156,-0.0119,0.707,0.00366,-0.00516,0.0123,0.00595,-0.000669,-365,-1.42e-05,-6.05e-05,7.3e-06,-2.81e-05,7.27e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000134,0.000106,0.000106,0.000129,0.0255,0.0255,0.0102,0.0437,0.0437,0.0412,2.51e-10,2.51e-10,5.91e-10,3.07e-06,3.07e-06,5e-08,0,0,0,0,0,0,0,0 -20090000,0.707,0.00015,-0.0119,0.707,0.00342,-0.0071,0.0126,0.00631,-0.00127,-365,-1.42e-05,-6.05e-05,7.76e-06,-2.81e-05,7.27e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000134,0.000107,0.000107,0.000129,0.0279,0.0279,0.0102,0.0491,0.0491,0.0415,2.51e-10,2.51e-10,5.8e-10,3.07e-06,3.07e-06,5e-08,0,0,0,0,0,0,0,0 +20090000,0.707,0.00015,-0.0119,0.707,0.00342,-0.00711,0.0126,0.00631,-0.00127,-365,-1.42e-05,-6.05e-05,7.76e-06,-2.81e-05,7.27e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000134,0.000107,0.000107,0.000129,0.0279,0.0279,0.0102,0.0491,0.0491,0.0415,2.51e-10,2.51e-10,5.8e-10,3.07e-06,3.07e-06,5e-08,0,0,0,0,0,0,0,0 20190000,0.707,0.000251,-0.0118,0.707,0.00112,-0.0078,0.0149,0.00405,-0.001,-365,-1.43e-05,-6.05e-05,7.96e-06,-2.7e-05,7.48e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000134,0.000104,0.000104,0.000128,0.0248,0.0248,0.00991,0.0435,0.0435,0.0409,2.3e-10,2.31e-10,5.68e-10,3.06e-06,3.06e-06,5e-08,0,0,0,0,0,0,0,0 -20290000,0.707,0.000211,-0.0118,0.707,-3e-05,-0.00937,0.0129,0.0041,-0.00185,-365,-1.43e-05,-6.05e-05,8.08e-06,-2.71e-05,7.48e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000133,0.000105,0.000105,0.000128,0.0271,0.0271,0.00982,0.0489,0.0489,0.0408,2.31e-10,2.31e-10,5.56e-10,3.06e-06,3.06e-06,5e-08,0,0,0,0,0,0,0,0 +20290000,0.707,0.000211,-0.0118,0.707,-3.04e-05,-0.00938,0.0129,0.0041,-0.00185,-365,-1.43e-05,-6.05e-05,8.08e-06,-2.71e-05,7.48e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000133,0.000105,0.000105,0.000128,0.0271,0.0271,0.00982,0.0489,0.0489,0.0408,2.31e-10,2.31e-10,5.56e-10,3.06e-06,3.06e-06,5e-08,0,0,0,0,0,0,0,0 20390000,0.707,0.000227,-0.0119,0.707,-0.00245,-0.00996,0.015,0.00225,-0.00146,-365,-1.44e-05,-6.04e-05,8.06e-06,-2.57e-05,7.62e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000133,0.000103,0.000103,0.000128,0.0242,0.0242,0.00963,0.0434,0.0434,0.0406,2.12e-10,2.12e-10,5.46e-10,3.06e-06,3.06e-06,5e-08,0,0,0,0,0,0,0,0 20490000,0.707,0.000283,-0.0119,0.707,-0.00293,-0.0107,0.0148,0.00197,-0.00249,-365,-1.44e-05,-6.04e-05,7.87e-06,-2.57e-05,7.63e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000133,0.000104,0.000103,0.000128,0.0264,0.0264,0.00955,0.0487,0.0487,0.0405,2.12e-10,2.12e-10,5.35e-10,3.06e-06,3.06e-06,5e-08,0,0,0,0,0,0,0,0 20590000,0.707,0.000301,-0.0119,0.707,-0.00255,-0.0106,0.0117,0.00168,-0.00199,-365,-1.44e-05,-6.03e-05,7.7e-06,-2.44e-05,7.61e-05,-0.0013,0.209,0.00206,0.432,0,0,0,0,0,0.000133,0.000101,0.000101,0.000127,0.0237,0.0237,0.00931,0.0432,0.0432,0.0399,1.95e-10,1.95e-10,5.24e-10,3.05e-06,3.05e-06,5e-08,0,0,0,0,0,0,0,0 @@ -217,36 +217,36 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 21490000,0.708,0.000462,-0.012,0.706,-0.00555,-0.018,0.0143,0.00213,-0.00509,-365,-1.42e-05,-5.99e-05,8.31e-06,-1.66e-05,7.34e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.00013,9.74e-05,9.74e-05,0.000125,0.0233,0.0233,0.00846,0.0475,0.0475,0.0384,1.44e-10,1.44e-10,4.41e-10,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0 21590000,0.708,0.000484,-0.012,0.706,-0.00605,-0.0153,0.0141,0.00177,-0.00311,-365,-1.42e-05,-5.97e-05,8.2e-06,-1.39e-05,7.3e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.00013,9.6e-05,9.59e-05,0.000125,0.021,0.021,0.00831,0.0424,0.0423,0.0379,1.34e-10,1.34e-10,4.33e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0 21690000,0.708,0.000493,-0.012,0.706,-0.00595,-0.0164,0.0158,0.00116,-0.0047,-365,-1.42e-05,-5.97e-05,8.29e-06,-1.39e-05,7.3e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.00013,9.65e-05,9.64e-05,0.000125,0.0228,0.0228,0.00834,0.0472,0.0472,0.0382,1.34e-10,1.34e-10,4.26e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0 -21790000,0.708,0.000504,-0.0121,0.706,-0.00653,-0.0113,0.0143,-6.71e-05,-0.000715,-365,-1.42e-05,-5.95e-05,8.04e-06,-9.69e-06,7.33e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.00013,9.51e-05,9.5e-05,0.000124,0.0205,0.0205,0.0082,0.0422,0.0422,0.0377,1.25e-10,1.25e-10,4.18e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0 -21890000,0.708,0.000507,-0.012,0.706,-0.00652,-0.0116,0.0147,-0.000722,-0.00186,-365,-1.42e-05,-5.95e-05,7.98e-06,-9.73e-06,7.34e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.00013,9.56e-05,9.55e-05,0.000124,0.0222,0.0222,0.00818,0.047,0.047,0.0376,1.25e-10,1.25e-10,4.1e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0 +21790000,0.708,0.000504,-0.0121,0.706,-0.00653,-0.0113,0.0143,-6.73e-05,-0.000715,-365,-1.42e-05,-5.95e-05,8.04e-06,-9.69e-06,7.33e-05,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.00013,9.51e-05,9.5e-05,0.000124,0.0205,0.0205,0.0082,0.0422,0.0422,0.0377,1.25e-10,1.25e-10,4.18e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0 +21890000,0.708,0.000507,-0.012,0.706,-0.00652,-0.0116,0.0147,-0.000723,-0.00186,-365,-1.42e-05,-5.95e-05,7.98e-06,-9.73e-06,7.34e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.00013,9.56e-05,9.55e-05,0.000124,0.0222,0.0222,0.00818,0.047,0.047,0.0376,1.25e-10,1.25e-10,4.1e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0 21990000,0.708,0.000554,-0.0121,0.706,-0.00699,-0.009,0.0155,-0.0016,0.0015,-365,-1.42e-05,-5.93e-05,7.93e-06,-6.24e-06,7.35e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000129,9.43e-05,9.42e-05,0.000124,0.0201,0.0201,0.00811,0.042,0.042,0.0375,1.17e-10,1.17e-10,4.03e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0 -22090000,0.708,0.000565,-0.0121,0.706,-0.00733,-0.00813,0.0139,-0.00231,0.000663,-365,-1.42e-05,-5.93e-05,7.85e-06,-6.27e-06,7.36e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000129,9.48e-05,9.47e-05,0.000124,0.0217,0.0217,0.0081,0.0468,0.0468,0.0375,1.17e-10,1.17e-10,3.96e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0 +22090000,0.708,0.000565,-0.0121,0.706,-0.00733,-0.00813,0.0139,-0.00231,0.000662,-365,-1.42e-05,-5.93e-05,7.85e-06,-6.27e-06,7.36e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000129,9.48e-05,9.47e-05,0.000124,0.0217,0.0217,0.0081,0.0468,0.0468,0.0375,1.17e-10,1.17e-10,3.96e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0 22190000,0.708,0.000536,-0.0121,0.706,-0.00712,-0.00723,0.0143,-0.00193,0.000612,-365,-1.42e-05,-5.92e-05,7.86e-06,-5.73e-06,7.29e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000129,9.36e-05,9.35e-05,0.000124,0.0196,0.0196,0.00799,0.0418,0.0418,0.037,1.1e-10,1.1e-10,3.89e-10,3.02e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0 22290000,0.708,0.000576,-0.0121,0.706,-0.00848,-0.00796,0.0143,-0.0027,-0.000156,-365,-1.42e-05,-5.92e-05,7.7e-06,-5.75e-06,7.29e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000129,9.4e-05,9.39e-05,0.000123,0.0213,0.0213,0.00799,0.0465,0.0465,0.0369,1.1e-10,1.1e-10,3.82e-10,3.02e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0 -22390000,0.708,0.00055,-0.0121,0.706,-0.00902,-0.00745,0.0161,-0.00232,-0.000152,-365,-1.42e-05,-5.92e-05,7.75e-06,-5.18e-06,7.21e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000128,9.29e-05,9.28e-05,0.000123,0.0192,0.0192,0.00793,0.0416,0.0416,0.0369,1.03e-10,1.03e-10,3.76e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 -22490000,0.708,0.000555,-0.012,0.706,-0.00969,-0.00736,0.0173,-0.00324,-0.000912,-365,-1.42e-05,-5.92e-05,7.68e-06,-5.16e-06,7.21e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000128,9.33e-05,9.32e-05,0.000123,0.0208,0.0208,0.00794,0.0463,0.0463,0.0368,1.03e-10,1.03e-10,3.69e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 +22390000,0.708,0.00055,-0.0121,0.706,-0.00902,-0.00745,0.0161,-0.00232,-0.000152,-365,-1.42e-05,-5.92e-05,7.75e-06,-5.17e-06,7.21e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000128,9.29e-05,9.28e-05,0.000123,0.0192,0.0192,0.00793,0.0416,0.0416,0.0369,1.03e-10,1.03e-10,3.76e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 +22490000,0.708,0.000555,-0.012,0.706,-0.00969,-0.00736,0.0173,-0.00324,-0.000913,-365,-1.42e-05,-5.92e-05,7.68e-06,-5.16e-06,7.21e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000128,9.33e-05,9.32e-05,0.000123,0.0208,0.0208,0.00794,0.0463,0.0463,0.0368,1.03e-10,1.03e-10,3.69e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 22590000,0.708,0.000535,-0.012,0.706,-0.00939,-0.0069,0.0164,-0.00352,0.000161,-365,-1.41e-05,-5.91e-05,7.67e-06,-3.96e-06,7.11e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000128,9.22e-05,9.22e-05,0.000123,0.0188,0.0188,0.00784,0.0415,0.0415,0.0364,9.7e-11,9.7e-11,3.62e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 22690000,0.708,0.000571,-0.0121,0.706,-0.0106,-0.00663,0.0176,-0.00452,-0.000511,-365,-1.41e-05,-5.91e-05,7.75e-06,-3.97e-06,7.11e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000128,9.26e-05,9.26e-05,0.000123,0.0204,0.0204,0.0079,0.0461,0.0461,0.0367,9.71e-11,9.71e-11,3.57e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 22790000,0.708,0.000553,-0.0121,0.706,-0.0111,-0.00543,0.0187,-0.00562,-0.000413,-365,-1.41e-05,-5.91e-05,7.31e-06,-3.47e-06,7.07e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000128,9.16e-05,9.16e-05,0.000122,0.0185,0.0185,0.00781,0.0413,0.0413,0.0363,9.15e-11,9.16e-11,3.5e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 -22890000,0.708,0.000564,-0.012,0.706,-0.0126,-0.00505,0.0204,-0.00679,-0.00094,-365,-1.41e-05,-5.91e-05,7.23e-06,-3.46e-06,7.07e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000127,9.2e-05,9.2e-05,0.000122,0.0199,0.0199,0.00783,0.0458,0.0458,0.0363,9.16e-11,9.16e-11,3.44e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 -22990000,0.708,0.000547,-0.0121,0.706,-0.0125,-0.00552,0.0214,-0.00752,-0.000835,-365,-1.41e-05,-5.91e-05,7.33e-06,-3.11e-06,7e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000127,9.11e-05,9.1e-05,0.000122,0.0181,0.0181,0.00779,0.0411,0.0411,0.0362,8.65e-11,8.66e-11,3.39e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 -23090000,0.708,0.000512,-0.012,0.706,-0.0132,-0.00551,0.022,-0.00882,-0.00137,-365,-1.41e-05,-5.91e-05,7.03e-06,-3.06e-06,7.01e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000127,9.15e-05,9.14e-05,0.000122,0.0195,0.0195,0.00782,0.0456,0.0456,0.0362,8.66e-11,8.67e-11,3.33e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 +22890000,0.708,0.000564,-0.012,0.706,-0.0126,-0.00505,0.0204,-0.00679,-0.000941,-365,-1.41e-05,-5.91e-05,7.23e-06,-3.46e-06,7.07e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000127,9.2e-05,9.2e-05,0.000122,0.0199,0.0199,0.00783,0.0458,0.0458,0.0363,9.16e-11,9.16e-11,3.44e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 +22990000,0.708,0.000547,-0.0121,0.706,-0.0125,-0.00552,0.0214,-0.00752,-0.000835,-365,-1.41e-05,-5.91e-05,7.33e-06,-3.1e-06,7e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000127,9.11e-05,9.1e-05,0.000122,0.0181,0.0181,0.00779,0.0411,0.0411,0.0362,8.65e-11,8.66e-11,3.39e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 +23090000,0.708,0.000512,-0.012,0.706,-0.0132,-0.00551,0.022,-0.00882,-0.00137,-365,-1.41e-05,-5.91e-05,7.03e-06,-3.06e-06,7e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000127,9.15e-05,9.14e-05,0.000122,0.0195,0.0195,0.00782,0.0456,0.0456,0.0362,8.66e-11,8.67e-11,3.33e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 23190000,0.708,0.000578,-0.012,0.706,-0.0146,-0.00648,0.0236,-0.0121,-0.00123,-365,-1.41e-05,-5.91e-05,6.97e-06,-2.57e-06,7.12e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000127,9.06e-05,9.05e-05,0.000122,0.0178,0.0178,0.00774,0.0409,0.0409,0.0359,8.2e-11,8.2e-11,3.27e-10,3.01e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 -23290000,0.708,0.000518,-0.012,0.706,-0.0154,-0.00772,0.024,-0.0136,-0.00195,-365,-1.41e-05,-5.91e-05,6.95e-06,-2.6e-06,7.12e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000127,9.09e-05,9.09e-05,0.000121,0.0192,0.0192,0.00781,0.0454,0.0454,0.0361,8.21e-11,8.21e-11,3.22e-10,3.01e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 +23290000,0.708,0.000518,-0.012,0.706,-0.0154,-0.00773,0.024,-0.0136,-0.00196,-365,-1.41e-05,-5.91e-05,6.95e-06,-2.6e-06,7.12e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000127,9.09e-05,9.09e-05,0.000121,0.0192,0.0192,0.00781,0.0454,0.0454,0.0361,8.21e-11,8.21e-11,3.22e-10,3.01e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 23390000,0.708,0.000607,-0.0119,0.706,-0.0162,-0.00796,0.0215,-0.0161,-0.00173,-365,-1.42e-05,-5.9e-05,6.9e-06,-2.08e-06,7.2e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000126,9.01e-05,9e-05,0.000121,0.0174,0.0174,0.00774,0.0408,0.0408,0.0358,7.78e-11,7.79e-11,3.17e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 23490000,0.708,0.003,-0.00951,0.706,-0.0233,-0.0088,-0.012,-0.018,-0.00258,-365,-1.42e-05,-5.9e-05,6.98e-06,-2.12e-06,7.2e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000126,9.04e-05,9.04e-05,0.000121,0.0189,0.0189,0.00778,0.0452,0.0452,0.0358,7.79e-11,7.8e-11,3.12e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 -23590000,0.708,0.00823,-0.0017,0.706,-0.0337,-0.00752,-0.0435,-0.0167,-0.00128,-365,-1.41e-05,-5.9e-05,6.82e-06,-4.15e-07,7.03e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000126,8.97e-05,8.95e-05,0.000121,0.0172,0.0172,0.00771,0.0406,0.0406,0.0355,7.4e-11,7.41e-11,3.06e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 -23690000,0.707,0.00786,0.00407,0.707,-0.0648,-0.0161,-0.094,-0.0215,-0.00238,-365,-1.41e-05,-5.9e-05,6.77e-06,-3.37e-07,7.03e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000126,9e-05,8.98e-05,0.000121,0.0186,0.0186,0.00779,0.045,0.045,0.0358,7.41e-11,7.42e-11,3.02e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 +23590000,0.708,0.00823,-0.0017,0.706,-0.0337,-0.00752,-0.0435,-0.0167,-0.00128,-365,-1.41e-05,-5.9e-05,6.82e-06,-4.14e-07,7.03e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000126,8.97e-05,8.95e-05,0.000121,0.0172,0.0172,0.00771,0.0406,0.0406,0.0355,7.4e-11,7.41e-11,3.06e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 +23690000,0.707,0.00786,0.00407,0.707,-0.0648,-0.0161,-0.094,-0.0215,-0.00238,-365,-1.41e-05,-5.9e-05,6.77e-06,-3.35e-07,7.03e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000126,9e-05,8.98e-05,0.000121,0.0186,0.0186,0.00779,0.045,0.045,0.0358,7.41e-11,7.42e-11,3.02e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 23790000,0.707,0.00493,0.000721,0.707,-0.0887,-0.0273,-0.148,-0.0208,-0.00173,-365,-1.39e-05,-5.89e-05,6.78e-06,1.53e-06,6.52e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000125,8.92e-05,8.91e-05,0.000121,0.0171,0.0171,0.00773,0.0405,0.0405,0.0355,7.05e-11,7.06e-11,2.97e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 -23890000,0.707,0.0023,-0.00536,0.708,-0.105,-0.0363,-0.201,-0.0306,-0.00494,-365,-1.39e-05,-5.89e-05,6.69e-06,1.65e-06,6.53e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000125,8.95e-05,8.94e-05,0.000121,0.0185,0.0185,0.00777,0.0448,0.0448,0.0354,7.06e-11,7.07e-11,2.92e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 +23890000,0.707,0.0023,-0.00536,0.708,-0.105,-0.0363,-0.201,-0.0306,-0.00494,-365,-1.39e-05,-5.89e-05,6.69e-06,1.66e-06,6.53e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000125,8.95e-05,8.94e-05,0.000121,0.0185,0.0185,0.00777,0.0448,0.0448,0.0354,7.06e-11,7.07e-11,2.92e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 23990000,0.707,0.000896,-0.00996,0.708,-0.106,-0.0395,-0.254,-0.0342,-0.00816,-366,-1.37e-05,-5.89e-05,6.73e-06,2.62e-06,6.19e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000125,8.87e-05,8.86e-05,0.00012,0.0169,0.0169,0.00775,0.0403,0.0403,0.0355,6.73e-11,6.73e-11,2.88e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 24090000,0.707,0.00218,-0.00869,0.708,-0.108,-0.0399,-0.302,-0.0448,-0.0121,-366,-1.37e-05,-5.89e-05,6.82e-06,2.58e-06,6.18e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000125,8.9e-05,8.89e-05,0.00012,0.0183,0.0183,0.00779,0.0446,0.0446,0.0355,6.74e-11,6.74e-11,2.83e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 24190000,0.707,0.00325,-0.00644,0.708,-0.11,-0.0408,-0.35,-0.0463,-0.0141,-366,-1.36e-05,-5.88e-05,6.83e-06,4.42e-06,5.72e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000125,8.81e-05,8.8e-05,0.00012,0.0168,0.0168,0.00773,0.0402,0.0402,0.0352,6.43e-11,6.43e-11,2.79e-10,3e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 24290000,0.707,0.00374,-0.00562,0.708,-0.121,-0.0448,-0.405,-0.0579,-0.0184,-366,-1.36e-05,-5.88e-05,6.72e-06,4.55e-06,5.73e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000124,8.84e-05,8.83e-05,0.00012,0.0181,0.0181,0.00782,0.0444,0.0444,0.0355,6.44e-11,6.44e-11,2.75e-10,3e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 24390000,0.706,0.00379,-0.00583,0.708,-0.129,-0.052,-0.457,-0.0638,-0.03,-366,-1.35e-05,-5.89e-05,6.53e-06,1.85e-06,5.44e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000124,8.76e-05,8.75e-05,0.00012,0.0166,0.0166,0.00776,0.0401,0.0401,0.0352,6.16e-11,6.16e-11,2.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -24490000,0.706,0.00466,-0.00168,0.708,-0.143,-0.0573,-0.507,-0.0773,-0.0354,-366,-1.35e-05,-5.89e-05,6.47e-06,1.99e-06,5.44e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000124,8.78e-05,8.77e-05,0.00012,0.0179,0.0179,0.00781,0.0443,0.0443,0.0352,6.17e-11,6.17e-11,2.66e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -24590000,0.707,0.00511,0.00194,0.708,-0.157,-0.0685,-0.558,-0.0808,-0.0447,-366,-1.33e-05,-5.9e-05,6.6e-06,7.34e-07,4.82e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000124,8.7e-05,8.69e-05,0.00012,0.0165,0.0164,0.00779,0.04,0.04,0.0353,5.9e-11,5.9e-11,2.62e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -24690000,0.707,0.00515,0.00289,0.708,-0.182,-0.0822,-0.641,-0.0977,-0.0522,-366,-1.33e-05,-5.9e-05,6.69e-06,5.36e-07,4.83e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000124,8.72e-05,8.71e-05,0.000119,0.0178,0.0178,0.00784,0.0442,0.0442,0.0353,5.91e-11,5.91e-11,2.58e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +24490000,0.706,0.00466,-0.00168,0.708,-0.143,-0.0573,-0.507,-0.0773,-0.0354,-366,-1.35e-05,-5.89e-05,6.47e-06,2e-06,5.44e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000124,8.78e-05,8.77e-05,0.00012,0.0179,0.0179,0.00781,0.0443,0.0443,0.0352,6.17e-11,6.17e-11,2.66e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +24590000,0.707,0.00511,0.00194,0.708,-0.157,-0.0685,-0.558,-0.0808,-0.0447,-366,-1.33e-05,-5.9e-05,6.6e-06,7.35e-07,4.82e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000124,8.7e-05,8.69e-05,0.00012,0.0165,0.0164,0.00779,0.04,0.04,0.0353,5.9e-11,5.9e-11,2.62e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +24690000,0.707,0.00515,0.00289,0.708,-0.182,-0.0822,-0.641,-0.0977,-0.0522,-366,-1.33e-05,-5.9e-05,6.69e-06,5.38e-07,4.83e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000124,8.72e-05,8.71e-05,0.000119,0.0178,0.0178,0.00784,0.0442,0.0442,0.0353,5.91e-11,5.91e-11,2.58e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 24790000,0.706,0.00486,0.00152,0.708,-0.198,-0.0945,-0.724,-0.105,-0.0633,-366,-1.3e-05,-5.89e-05,6.51e-06,4.56e-06,4.07e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000124,8.63e-05,8.62e-05,0.000119,0.0164,0.0164,0.00778,0.0399,0.0399,0.035,5.67e-11,5.67e-11,2.54e-10,2.99e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 24890000,0.706,0.00661,0.00321,0.708,-0.221,-0.106,-0.748,-0.126,-0.0733,-366,-1.3e-05,-5.89e-05,6.39e-06,4.77e-06,4.07e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000123,8.66e-05,8.65e-05,0.000119,0.0176,0.0176,0.00783,0.044,0.044,0.0351,5.68e-11,5.68e-11,2.5e-10,2.99e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 24990000,0.706,0.00842,0.00481,0.708,-0.238,-0.114,-0.805,-0.129,-0.0813,-366,-1.27e-05,-5.88e-05,6.2e-06,1.3e-05,2.69e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000123,8.57e-05,8.56e-05,0.000119,0.0162,0.0162,0.00781,0.0398,0.0398,0.0351,5.45e-11,5.45e-11,2.47e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0 @@ -255,20 +255,20 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 25290000,0.706,0.0101,0.00961,0.708,-0.321,-0.147,-0.958,-0.204,-0.133,-366,-1.26e-05,-5.89e-05,6.06e-06,1e-05,2.19e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000123,8.53e-05,8.51e-05,0.000119,0.0173,0.0172,0.0079,0.0438,0.0438,0.0353,5.26e-11,5.26e-11,2.36e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0 25390000,0.706,0.0114,0.016,0.708,-0.351,-0.166,-1.01,-0.216,-0.153,-366,-1.23e-05,-5.89e-05,6.07e-06,1.2e-05,7.67e-06,-0.00129,0.209,0.00206,0.432,0,0,0,0,0,0.000122,8.44e-05,8.42e-05,0.000118,0.0159,0.0158,0.00784,0.0396,0.0396,0.035,5.06e-11,5.06e-11,2.33e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0 25490000,0.706,0.0116,0.0172,0.707,-0.4,-0.19,-1.06,-0.253,-0.171,-366,-1.23e-05,-5.89e-05,6.11e-06,1.19e-05,7.76e-06,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000122,8.46e-05,8.44e-05,0.000118,0.0171,0.017,0.00789,0.0436,0.0436,0.0351,5.07e-11,5.07e-11,2.29e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0 -25590000,0.707,0.011,0.0153,0.707,-0.439,-0.219,-1.12,-0.28,-0.208,-367,-1.21e-05,-5.91e-05,6.09e-06,9.24e-06,-7.77e-07,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000122,8.37e-05,8.35e-05,0.000118,0.0157,0.0157,0.00788,0.0395,0.0395,0.0351,4.89e-11,4.89e-11,2.26e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0 -25690000,0.706,0.0146,0.022,0.707,-0.488,-0.24,-1.17,-0.326,-0.231,-367,-1.21e-05,-5.91e-05,6.08e-06,9.12e-06,-5.63e-07,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000122,8.39e-05,8.37e-05,0.000118,0.0169,0.0168,0.00793,0.0435,0.0435,0.0352,4.9e-11,4.9e-11,2.23e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0 +25590000,0.707,0.011,0.0153,0.707,-0.439,-0.219,-1.12,-0.28,-0.208,-367,-1.21e-05,-5.91e-05,6.09e-06,9.25e-06,-7.79e-07,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000122,8.37e-05,8.35e-05,0.000118,0.0157,0.0157,0.00788,0.0395,0.0395,0.0351,4.89e-11,4.89e-11,2.26e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0 +25690000,0.706,0.0146,0.022,0.707,-0.488,-0.24,-1.17,-0.326,-0.231,-367,-1.21e-05,-5.91e-05,6.08e-06,9.12e-06,-5.64e-07,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000122,8.39e-05,8.37e-05,0.000118,0.0169,0.0168,0.00793,0.0435,0.0435,0.0352,4.9e-11,4.9e-11,2.23e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0 25790000,0.706,0.0171,0.0282,0.707,-0.533,-0.266,-1.22,-0.343,-0.261,-367,-1.16e-05,-5.9e-05,6.15e-06,1.69e-05,-2.48e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000122,8.3e-05,8.28e-05,0.000118,0.0156,0.0155,0.00787,0.0394,0.0394,0.0349,4.73e-11,4.73e-11,2.2e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0 25890000,0.706,0.0174,0.0286,0.707,-0.604,-0.296,-1.27,-0.4,-0.289,-367,-1.16e-05,-5.9e-05,6.26e-06,1.66e-05,-2.5e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000122,8.32e-05,8.3e-05,0.000118,0.0168,0.0166,0.00796,0.0434,0.0434,0.0353,4.74e-11,4.74e-11,2.17e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0 25990000,0.706,0.0163,0.0254,0.707,-0.656,-0.332,-1.32,-0.439,-0.344,-367,-1.12e-05,-5.92e-05,6.28e-06,1.31e-05,-4.05e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000121,8.23e-05,8.22e-05,0.000117,0.0155,0.0153,0.0079,0.0393,0.0393,0.0351,4.59e-11,4.59e-11,2.14e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0 26090000,0.702,0.021,0.0353,0.711,-0.723,-0.359,-1.34,-0.508,-0.379,-367,-1.13e-05,-5.92e-05,6.07e-06,1.34e-05,-3.97e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.000121,8.25e-05,8.23e-05,0.000118,0.0166,0.0164,0.00796,0.0433,0.0432,0.0351,4.6e-11,4.6e-11,2.11e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0 -26190000,0.701,0.0232,0.0446,0.712,-0.775,-0.394,-1.31,-0.533,-0.422,-367,-1.06e-05,-5.91e-05,6.07e-06,2.43e-05,-7.58e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.00012,8.16e-05,8.15e-05,0.000118,0.0153,0.015,0.0079,0.0392,0.0392,0.0349,4.45e-11,4.45e-11,2.08e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0 +26190000,0.701,0.0232,0.0446,0.712,-0.775,-0.394,-1.31,-0.533,-0.422,-367,-1.06e-05,-5.91e-05,6.07e-06,2.44e-05,-7.58e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.00012,8.16e-05,8.15e-05,0.000118,0.0153,0.015,0.0079,0.0392,0.0392,0.0349,4.45e-11,4.45e-11,2.08e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0 26290000,0.701,0.0241,0.0469,0.711,-0.869,-0.436,-1.3,-0.616,-0.463,-368,-1.06e-05,-5.91e-05,5.97e-06,2.44e-05,-7.51e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.00012,8.18e-05,8.17e-05,0.000118,0.0164,0.016,0.00799,0.0431,0.0431,0.0352,4.46e-11,4.46e-11,2.05e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0 26390000,0.702,0.023,0.0435,0.711,-0.945,-0.492,-1.31,-0.679,-0.548,-368,-1.03e-05,-5.94e-05,5.99e-06,1.23e-05,-8.77e-05,-0.00128,0.209,0.00206,0.432,0,0,0,0,0,0.00012,8.1e-05,8.09e-05,0.000117,0.0151,0.0147,0.00793,0.0391,0.039,0.035,4.33e-11,4.33e-11,2.02e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0 26490000,0.702,0.0308,0.0593,0.709,-1.04,-0.531,-1.31,-0.778,-0.599,-368,-1.03e-05,-5.94e-05,5.94e-06,1.22e-05,-8.72e-05,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.00012,8.12e-05,8.11e-05,0.000117,0.0162,0.0158,0.00799,0.043,0.0429,0.0351,4.34e-11,4.34e-11,1.99e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0 26590000,0.702,0.0369,0.0752,0.707,-1.14,-0.586,-1.3,-0.822,-0.666,-368,-9.5e-06,-5.93e-05,5.58e-06,2.12e-05,-0.000121,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.00012,8.04e-05,8.04e-05,0.000117,0.015,0.0145,0.00797,0.039,0.0389,0.0351,4.22e-11,4.21e-11,1.97e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0 26690000,0.703,0.0381,0.078,0.706,-1.28,-0.648,-1.29,-0.943,-0.728,-368,-9.49e-06,-5.93e-05,5.65e-06,2.08e-05,-0.000121,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000119,8.06e-05,8.06e-05,0.000116,0.0162,0.0155,0.00803,0.0429,0.0427,0.0352,4.23e-11,4.22e-11,1.94e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0 -26790000,0.704,0.0358,0.0725,0.705,-1.4,-0.73,-1.29,-1.04,-0.855,-368,-9.05e-06,-5.98e-05,5.49e-06,-4.03e-07,-0.000139,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000119,8e-05,7.98e-05,0.000116,0.0151,0.0143,0.00797,0.0389,0.0388,0.035,4.12e-11,4.11e-11,1.91e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0 -26890000,0.704,0.0447,0.0944,0.703,-1.54,-0.789,-1.3,-1.18,-0.931,-368,-9.04e-06,-5.98e-05,5.52e-06,-8.2e-07,-0.000139,-0.00126,0.209,0.00206,0.432,0,0,0,0,0,0.000119,8e-05,8.01e-05,0.000116,0.0163,0.0154,0.00807,0.0427,0.0426,0.0353,4.13e-11,4.12e-11,1.89e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0 +26790000,0.704,0.0358,0.0725,0.705,-1.4,-0.73,-1.29,-1.04,-0.855,-368,-9.05e-06,-5.98e-05,5.49e-06,-4.01e-07,-0.000139,-0.00127,0.209,0.00206,0.432,0,0,0,0,0,0.000119,8e-05,7.98e-05,0.000116,0.0151,0.0143,0.00797,0.0389,0.0388,0.035,4.12e-11,4.11e-11,1.91e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0 +26890000,0.704,0.0447,0.0944,0.703,-1.54,-0.789,-1.3,-1.18,-0.931,-368,-9.04e-06,-5.98e-05,5.52e-06,-8.18e-07,-0.000139,-0.00126,0.209,0.00206,0.432,0,0,0,0,0,0.000119,8e-05,8.01e-05,0.000116,0.0163,0.0154,0.00807,0.0427,0.0426,0.0353,4.13e-11,4.12e-11,1.89e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0 26990000,0.703,0.051,0.116,0.699,-1.68,-0.871,-1.28,-1.24,-1.03,-368,-7.89e-06,-5.97e-05,5.42e-06,6.6e-06,-0.000187,-0.00126,0.209,0.00206,0.432,0,0,0,0,0,0.000119,7.93e-05,7.96e-05,0.000115,0.0153,0.0142,0.00802,0.0388,0.0386,0.0351,4.02e-11,4.01e-11,1.86e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0 27090000,0.704,0.0519,0.12,0.698,-1.88,-0.963,-1.25,-1.42,-1.12,-369,-7.89e-06,-5.97e-05,5.36e-06,6.59e-06,-0.000185,-0.00126,0.209,0.00206,0.432,0,0,0,0,0,0.000119,7.94e-05,7.98e-05,0.000115,0.0167,0.0152,0.00809,0.0426,0.0424,0.0352,4.03e-11,4.02e-11,1.84e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0 27190000,0.706,0.0484,0.109,0.698,-2.08,-1.03,-1.23,-1.62,-1.2,-369,-7.86e-06,-5.94e-05,5.44e-06,1.56e-05,-0.000181,-0.00126,0.209,0.00206,0.432,0,0,0,0,0,0.000118,7.93e-05,7.94e-05,0.000114,0.017,0.0154,0.00809,0.0451,0.0448,0.0353,3.99e-11,3.98e-11,1.82e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0 @@ -282,18 +282,18 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 27990000,0.709,0.0244,0.0448,0.704,-2.66,-1.24,-1.21,-3.6,-2.07,-370,-8.01e-06,-5.82e-05,5.39e-06,2.19e-05,-0.000143,-0.00122,0.209,0.00206,0.432,0,0,0,0,0,0.000113,7.94e-05,7.89e-05,0.000111,0.021,0.019,0.00833,0.0766,0.0755,0.0353,3.84e-11,3.79e-11,1.64e-10,2.95e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0 28090000,0.708,0.0301,0.0581,0.703,-2.7,-1.25,-1.22,-3.87,-2.19,-370,-8.01e-06,-5.81e-05,5.13e-06,2.12e-05,-0.000139,-0.00122,0.209,0.00206,0.432,0,0,0,0,0,0.000113,7.95e-05,7.89e-05,0.000111,0.0222,0.0202,0.00842,0.0836,0.0822,0.0353,3.85e-11,3.8e-11,1.62e-10,2.95e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0 28190000,0.708,0.0353,0.0714,0.702,-2.76,-1.27,-0.946,-4.16,-2.3,-370,-8.26e-06,-5.8e-05,5.18e-06,1.68e-05,-0.000127,-0.00121,0.209,0.00206,0.432,0,0,0,0,0,0.000112,7.92e-05,7.86e-05,0.00011,0.0213,0.0195,0.00845,0.0857,0.0844,0.0354,3.8e-11,3.74e-11,1.6e-10,2.95e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0 -28290000,0.71,0.0275,0.0544,0.702,-2.76,-1.28,-0.083,-4.44,-2.43,-370,-8.26e-06,-5.8e-05,5e-06,1.56e-05,-0.000121,-0.00121,0.209,0.00206,0.432,0,0,0,0,0,0.000112,7.95e-05,7.88e-05,0.00011,0.0218,0.0201,0.00859,0.093,0.0914,0.0355,3.81e-11,3.75e-11,1.58e-10,2.95e-06,2.93e-06,5e-08,0,0,0,0,0,0,0,0 -28390000,0.712,0.0115,0.023,0.702,-2.78,-1.28,0.777,-4.76,-2.55,-370,-8.69e-06,-5.78e-05,4.94e-06,1.05e-07,-0.000149,-0.0012,0.209,0.00206,0.432,0,0,0,0,0,0.000111,7.98e-05,7.93e-05,0.000108,0.021,0.0196,0.00869,0.0949,0.0934,0.0356,3.77e-11,3.7e-11,1.56e-10,2.94e-06,2.93e-06,5e-08,0,0,0,0,0,0,0,0 +28290000,0.71,0.0275,0.0544,0.702,-2.76,-1.28,-0.083,-4.44,-2.43,-370,-8.26e-06,-5.8e-05,4.99e-06,1.56e-05,-0.000121,-0.00121,0.209,0.00206,0.432,0,0,0,0,0,0.000112,7.95e-05,7.88e-05,0.00011,0.0218,0.0201,0.00859,0.093,0.0914,0.0355,3.81e-11,3.75e-11,1.58e-10,2.95e-06,2.93e-06,5e-08,0,0,0,0,0,0,0,0 +28390000,0.712,0.0115,0.023,0.702,-2.78,-1.28,0.777,-4.76,-2.55,-370,-8.69e-06,-5.78e-05,4.94e-06,1.06e-07,-0.000149,-0.0012,0.209,0.00206,0.432,0,0,0,0,0,0.000111,7.98e-05,7.93e-05,0.000108,0.021,0.0196,0.00869,0.0949,0.0934,0.0356,3.77e-11,3.7e-11,1.56e-10,2.94e-06,2.93e-06,5e-08,0,0,0,0,0,0,0,0 28490000,0.712,0.00264,0.00476,0.702,-2.74,-1.28,1.07,-5.04,-2.68,-370,-8.68e-06,-5.78e-05,4.89e-06,-2.52e-06,-0.000143,-0.0012,0.209,0.00206,0.432,0,0,0,0,0,0.000111,8.01e-05,7.98e-05,0.000108,0.022,0.0208,0.00882,0.102,0.101,0.036,3.78e-11,3.71e-11,1.54e-10,2.94e-06,2.93e-06,5e-08,0,0,0,0,0,0,0,0 28590000,0.711,0.000797,0.00121,0.703,-2.69,-1.25,0.969,-5.36,-2.79,-370,-9.13e-06,-5.77e-05,4.98e-06,-2.41e-05,-0.000209,-0.00119,0.209,0.00206,0.432,0,0,0,0,0,0.00011,8.03e-05,7.99e-05,0.000108,0.0212,0.0203,0.0089,0.104,0.103,0.0361,3.73e-11,3.65e-11,1.52e-10,2.93e-06,2.91e-06,5e-08,0,0,0,0,0,0,0,0 -28690000,0.71,9.64e-05,0.000303,0.704,-2.62,-1.23,0.972,-5.62,-2.92,-370,-9.12e-06,-5.77e-05,4.91e-06,-2.85e-05,-0.000198,-0.00119,0.209,0.00206,0.432,0,0,0,0,0,0.00011,8.04e-05,8.01e-05,0.000108,0.0221,0.0214,0.00899,0.112,0.11,0.0362,3.74e-11,3.66e-11,1.5e-10,2.93e-06,2.91e-06,5e-08,0,0,0,0,0,0,0,0 -28790000,0.709,-0.00022,1.98e-05,0.705,-2.58,-1.21,0.976,-5.94,-3.03,-370,-9.63e-06,-5.76e-05,4.84e-06,-5.45e-05,-0.000255,-0.00118,0.209,0.00206,0.432,0,0,0,0,0,0.000109,8.06e-05,8.01e-05,0.000107,0.0213,0.0209,0.00893,0.114,0.112,0.036,3.7e-11,3.61e-11,1.49e-10,2.91e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +28690000,0.71,9.63e-05,0.000303,0.704,-2.62,-1.23,0.972,-5.62,-2.92,-370,-9.12e-06,-5.77e-05,4.91e-06,-2.85e-05,-0.000198,-0.00119,0.209,0.00206,0.432,0,0,0,0,0,0.00011,8.04e-05,8.01e-05,0.000108,0.0221,0.0214,0.00899,0.112,0.11,0.0362,3.74e-11,3.66e-11,1.5e-10,2.93e-06,2.91e-06,5e-08,0,0,0,0,0,0,0,0 +28790000,0.709,-0.00022,1.97e-05,0.705,-2.58,-1.21,0.976,-5.94,-3.03,-370,-9.63e-06,-5.76e-05,4.84e-06,-5.45e-05,-0.000255,-0.00118,0.209,0.00206,0.432,0,0,0,0,0,0.000109,8.06e-05,8.01e-05,0.000107,0.0213,0.0209,0.00893,0.114,0.112,0.036,3.7e-11,3.61e-11,1.49e-10,2.91e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 28890000,0.709,-0.000234,0.000244,0.705,-2.51,-1.19,0.965,-6.2,-3.15,-370,-9.62e-06,-5.76e-05,4.8e-06,-5.91e-05,-0.000243,-0.00117,0.209,0.00206,0.432,0,0,0,0,0,0.000109,8.07e-05,8.03e-05,0.000107,0.0224,0.0221,0.00906,0.122,0.12,0.0364,3.71e-11,3.62e-11,1.47e-10,2.91e-06,2.89e-06,5e-08,0,0,0,0,0,0,0,0 28990000,0.708,-7.44e-05,0.000643,0.706,-2.49,-1.17,0.959,-6.53,-3.26,-370,-1.03e-05,-5.75e-05,4.66e-06,-7.61e-05,-0.000312,-0.00116,0.209,0.00206,0.432,0,0,0,0,0,0.000108,8.09e-05,8.03e-05,0.000107,0.0215,0.0215,0.00899,0.124,0.122,0.0361,3.66e-11,3.57e-11,1.45e-10,2.9e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 29090000,0.708,8.28e-05,0.00105,0.706,-2.42,-1.16,0.95,-6.77,-3.38,-369,-1.03e-05,-5.75e-05,4.58e-06,-8.12e-05,-0.000299,-0.00115,0.209,0.00206,0.432,0,0,0,0,0,0.000108,8.1e-05,8.04e-05,0.000107,0.0226,0.0228,0.00907,0.133,0.131,0.0362,3.67e-11,3.57e-11,1.44e-10,2.9e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 29190000,0.708,0.00028,0.00145,0.706,-2.38,-1.14,0.943,-7.06,-3.48,-369,-1.07e-05,-5.74e-05,4.63e-06,-9.81e-05,-0.000321,-0.00114,0.209,0.00206,0.432,0,0,0,0,0,0.000108,8.11e-05,8.04e-05,0.000107,0.0218,0.0221,0.00905,0.133,0.132,0.0363,3.62e-11,3.52e-11,1.42e-10,2.89e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0 29290000,0.708,0.000638,0.00231,0.706,-2.33,-1.13,0.968,-7.29,-3.6,-369,-1.07e-05,-5.74e-05,4.51e-06,-0.000104,-0.000305,-0.00114,0.209,0.00206,0.432,0,0,0,0,0,0.000108,8.13e-05,8.05e-05,0.000106,0.0229,0.0234,0.00912,0.143,0.141,0.0364,3.63e-11,3.53e-11,1.41e-10,2.89e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0 -29390000,0.708,0.00116,0.00379,0.706,-2.31,-1.11,0.977,-7.59,-3.71,-369,-1.12e-05,-5.74e-05,4.25e-06,-0.000118,-0.000334,-0.00112,0.209,0.00206,0.432,0,0,0,0,0,0.000108,8.14e-05,8.04e-05,0.000106,0.0221,0.0227,0.00904,0.143,0.141,0.0362,3.58e-11,3.47e-11,1.39e-10,2.88e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0 +29390000,0.708,0.00116,0.00379,0.706,-2.31,-1.11,0.977,-7.59,-3.71,-369,-1.12e-05,-5.74e-05,4.24e-06,-0.000118,-0.000334,-0.00112,0.209,0.00206,0.432,0,0,0,0,0,0.000108,8.14e-05,8.04e-05,0.000106,0.0221,0.0227,0.00904,0.143,0.141,0.0362,3.58e-11,3.47e-11,1.39e-10,2.88e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0 29490000,0.708,0.00168,0.00493,0.706,-2.26,-1.1,0.973,-7.82,-3.82,-369,-1.12e-05,-5.74e-05,4.22e-06,-0.000123,-0.000322,-0.00112,0.209,0.00206,0.432,0,0,0,0,0,0.000108,8.15e-05,8.05e-05,0.000106,0.0233,0.024,0.00916,0.153,0.151,0.0366,3.59e-11,3.48e-11,1.38e-10,2.88e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 29590000,0.708,0.00206,0.00604,0.706,-2.23,-1.09,0.964,-8.08,-3.92,-369,-1.15e-05,-5.73e-05,4.15e-06,-0.000145,-0.000322,-0.00111,0.209,0.00206,0.432,0,0,0,0,0,0.000107,8.17e-05,8.04e-05,0.000106,0.0224,0.0232,0.00908,0.153,0.151,0.0364,3.54e-11,3.43e-11,1.36e-10,2.87e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 29690000,0.708,0.00236,0.00672,0.706,-2.19,-1.08,0.956,-8.3,-4.03,-369,-1.15e-05,-5.73e-05,4.05e-06,-0.00015,-0.000308,-0.0011,0.209,0.00206,0.432,0,0,0,0,0,0.000107,8.18e-05,8.05e-05,0.000106,0.0236,0.0245,0.00914,0.163,0.161,0.0365,3.55e-11,3.44e-11,1.34e-10,2.87e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 @@ -320,16 +320,16 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 31790000,0.709,0.0009,0.00129,0.705,-1.66,-0.89,0.723,-12.7,-6.02,-368,-1.41e-05,-5.67e-05,2.95e-06,-0.000341,-4.38e-05,-0.000977,0.209,0.00206,0.432,0,0,0,0,0,0.000104,8.33e-05,7.83e-05,9.9e-05,0.0246,0.025,0.00872,0.26,0.258,0.0367,3.06e-11,3.01e-11,1.08e-10,2.83e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0 31890000,0.709,0.000656,0.000601,0.705,-1.62,-0.88,0.718,-12.9,-6.11,-367,-1.41e-05,-5.67e-05,2.93e-06,-0.000348,-2.91e-05,-0.000972,0.209,0.00206,0.432,0,0,0,0,0,0.000103,8.35e-05,7.83e-05,9.89e-05,0.0259,0.0263,0.00874,0.273,0.271,0.0367,3.07e-11,3.02e-11,1.07e-10,2.83e-06,2.66e-06,5e-08,0,0,0,0,0,0,0,0 31990000,0.709,0.00052,0.000151,0.705,-1.6,-0.867,0.712,-13,-6.18,-367,-1.42e-05,-5.67e-05,2.84e-06,-0.000358,-8.62e-06,-0.000966,0.209,0.00206,0.432,0,0,0,0,0,0.000103,8.33e-05,7.79e-05,9.85e-05,0.0247,0.025,0.00863,0.269,0.267,0.0364,3.03e-11,2.98e-11,1.06e-10,2.83e-06,2.65e-06,5e-08,0,0,0,0,0,0,0,0 -32090000,0.709,0.000234,-0.000562,0.705,-1.57,-0.858,0.718,-13.2,-6.27,-367,-1.42e-05,-5.67e-05,2.8e-06,-0.000365,8e-06,-0.000961,0.209,0.00206,0.432,0,0,0,0,0,0.000103,8.35e-05,7.8e-05,9.84e-05,0.0259,0.0262,0.0087,0.282,0.28,0.0368,3.04e-11,2.99e-11,1.05e-10,2.83e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0 +32090000,0.709,0.000234,-0.000562,0.705,-1.57,-0.858,0.718,-13.2,-6.27,-367,-1.42e-05,-5.67e-05,2.8e-06,-0.000365,7.99e-06,-0.000961,0.209,0.00206,0.432,0,0,0,0,0,0.000103,8.35e-05,7.8e-05,9.84e-05,0.0259,0.0262,0.0087,0.282,0.28,0.0368,3.04e-11,2.99e-11,1.05e-10,2.83e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0 32190000,0.709,2.27e-05,-0.00133,0.705,-1.55,-0.848,0.716,-13.4,-6.35,-367,-1.43e-05,-5.66e-05,2.61e-06,-0.000376,2.99e-05,-0.000953,0.209,0.00206,0.432,0,0,0,0,0,0.000103,8.33e-05,7.76e-05,9.79e-05,0.0247,0.0249,0.00859,0.279,0.277,0.0365,2.99e-11,2.95e-11,1.04e-10,2.82e-06,2.64e-06,5e-08,0,0,0,0,0,0,0,0 32290000,0.709,-0.000208,-0.00206,0.705,-1.51,-0.838,0.71,-13.5,-6.44,-367,-1.43e-05,-5.66e-05,2.6e-06,-0.000384,4.74e-05,-0.000948,0.209,0.00206,0.432,0,0,0,0,0,0.000103,8.35e-05,7.76e-05,9.79e-05,0.026,0.0261,0.00861,0.292,0.289,0.0366,3e-11,2.96e-11,1.03e-10,2.82e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0 32390000,0.709,-0.000392,-0.00268,0.705,-1.48,-0.826,0.709,-13.7,-6.52,-367,-1.44e-05,-5.66e-05,2.63e-06,-0.000388,5.73e-05,-0.000944,0.209,0.00206,0.432,0,0,0,0,0,0.000102,8.34e-05,7.73e-05,9.74e-05,0.0247,0.0248,0.00855,0.288,0.286,0.0366,2.96e-11,2.93e-11,1.02e-10,2.82e-06,2.63e-06,5e-08,0,0,0,0,0,0,0,0 32490000,0.709,-0.000511,-0.00292,0.705,-1.45,-0.815,0.714,-13.8,-6.6,-367,-1.44e-05,-5.66e-05,2.63e-06,-0.000394,6.99e-05,-0.00094,0.209,0.00206,0.432,0,0,0,0,0,0.000102,8.35e-05,7.73e-05,9.74e-05,0.026,0.026,0.00857,0.301,0.299,0.0366,2.97e-11,2.94e-11,1.01e-10,2.82e-06,2.62e-06,5e-08,0,0,0,0,0,0,0,0 -32590000,0.709,-0.000508,-0.00312,0.705,-1.42,-0.805,0.711,-14,-6.68,-367,-1.45e-05,-5.66e-05,2.56e-06,-0.000398,7.84e-05,-0.000937,0.209,0.00206,0.432,0,0,0,0,0,0.000102,8.33e-05,7.7e-05,9.69e-05,0.0247,0.0247,0.00846,0.297,0.295,0.0363,2.92e-11,2.9e-11,9.97e-11,2.82e-06,2.61e-06,5e-08,0,0,0,0,0,0,0,0 +32590000,0.709,-0.000508,-0.00312,0.705,-1.42,-0.805,0.711,-14,-6.68,-367,-1.45e-05,-5.66e-05,2.56e-06,-0.000398,7.83e-05,-0.000937,0.209,0.00206,0.432,0,0,0,0,0,0.000102,8.33e-05,7.7e-05,9.69e-05,0.0247,0.0247,0.00846,0.297,0.295,0.0363,2.92e-11,2.9e-11,9.97e-11,2.82e-06,2.61e-06,5e-08,0,0,0,0,0,0,0,0 32690000,0.709,-0.000549,-0.0032,0.705,-1.39,-0.794,0.707,-14.1,-6.76,-367,-1.45e-05,-5.66e-05,2.54e-06,-0.000401,8.5e-05,-0.000935,0.209,0.00206,0.432,0,0,0,0,0,0.000102,8.35e-05,7.7e-05,9.69e-05,0.026,0.0259,0.00848,0.31,0.308,0.0364,2.93e-11,2.91e-11,9.88e-11,2.82e-06,2.61e-06,5e-08,0,0,0,0,0,0,0,0 -32790000,0.709,-0.000511,-0.00314,0.705,-1.37,-0.783,0.703,-14.3,-6.84,-367,-1.45e-05,-5.66e-05,2.52e-06,-0.000405,9.5e-05,-0.000932,0.209,0.00206,0.432,0,0,0,0,0,0.000101,8.33e-05,7.67e-05,9.65e-05,0.0248,0.0247,0.00843,0.307,0.304,0.0364,2.89e-11,2.88e-11,9.79e-11,2.82e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 +32790000,0.709,-0.000512,-0.00314,0.705,-1.37,-0.783,0.703,-14.3,-6.84,-367,-1.45e-05,-5.66e-05,2.52e-06,-0.000405,9.5e-05,-0.000932,0.209,0.00206,0.432,0,0,0,0,0,0.000101,8.33e-05,7.67e-05,9.65e-05,0.0248,0.0247,0.00843,0.307,0.304,0.0364,2.89e-11,2.88e-11,9.79e-11,2.82e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 32890000,0.709,-0.000418,-0.00309,0.706,-1.34,-0.773,0.703,-14.4,-6.91,-367,-1.45e-05,-5.66e-05,2.36e-06,-0.000411,0.000107,-0.000927,0.209,0.00206,0.432,0,0,0,0,0,0.000101,8.35e-05,7.67e-05,9.64e-05,0.026,0.0259,0.00845,0.32,0.317,0.0364,2.9e-11,2.89e-11,9.7e-11,2.82e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -32990000,0.709,-0.000286,-0.00302,0.706,-1.32,-0.765,0.697,-14.6,-6.99,-367,-1.47e-05,-5.66e-05,2.49e-06,-0.000417,0.000121,-0.000923,0.209,0.00206,0.432,0,0,0,0,0,0.000101,8.33e-05,7.64e-05,9.61e-05,0.0248,0.0246,0.00834,0.316,0.313,0.0361,2.86e-11,2.86e-11,9.61e-11,2.81e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 +32990000,0.709,-0.000286,-0.00302,0.706,-1.32,-0.765,0.697,-14.6,-6.99,-367,-1.47e-05,-5.66e-05,2.48e-06,-0.000417,0.000121,-0.000923,0.209,0.00206,0.432,0,0,0,0,0,0.000101,8.33e-05,7.64e-05,9.61e-05,0.0248,0.0246,0.00834,0.316,0.313,0.0361,2.86e-11,2.86e-11,9.61e-11,2.81e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 33090000,0.709,-0.000319,-0.00305,0.706,-1.29,-0.757,0.691,-14.7,-7.07,-367,-1.47e-05,-5.66e-05,2.56e-06,-0.00042,0.000127,-0.000921,0.209,0.00206,0.432,0,0,0,0,0,0.000101,8.34e-05,7.64e-05,9.6e-05,0.026,0.0258,0.00841,0.329,0.326,0.0365,2.87e-11,2.87e-11,9.53e-11,2.81e-06,2.59e-06,5e-08,0,0,0,0,0,0,0,0 33190000,0.705,0.00309,-0.00208,0.71,-1.26,-0.746,0.632,-14.8,-7.14,-367,-1.47e-05,-5.66e-05,2.58e-06,-0.000424,0.000135,-0.000918,0.209,0.00206,0.432,0,0,0,0,0,9.98e-05,8.32e-05,7.61e-05,9.63e-05,0.0248,0.0245,0.00831,0.325,0.322,0.0362,2.83e-11,2.84e-11,9.44e-11,2.81e-06,2.59e-06,5e-08,0,0,0,0,0,0,0,0 33290000,0.653,0.0153,-0.00116,0.757,-1.26,-0.727,0.614,-15,-7.21,-367,-1.47e-05,-5.66e-05,2.63e-06,-0.000426,0.00014,-0.000916,0.209,0.00206,0.432,0,0,0,0,0,9.24e-05,8.27e-05,7.67e-05,0.000104,0.0261,0.0258,0.00833,0.338,0.336,0.0362,2.84e-11,2.85e-11,9.36e-11,2.81e-06,2.58e-06,5e-08,0,0,0,0,0,0,0,0 diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv index d6e7662622..ff4a87a21c 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -18,21 +18,21 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 1590000,0.979,-0.00863,-0.0173,0.205,0.0533,-0.00359,-0.228,0.0128,-0.00094,-0.256,-1.42e-06,-2.63e-06,1.57e-08,1.6e-06,-9.28e-07,4.67e-06,0.203,0.0109,0.434,0,0,0,0,0,4.83e-05,0.007,0.007,0.00102,1.3,1.3,0.182,0.268,0.268,0.118,9.62e-07,9.62e-07,4.38e-07,3.99e-06,3.99e-06,3.87e-06,0,0,0,0,0,0,0,0 1690000,0.979,-0.00854,-0.017,0.205,0.0494,-0.00235,-0.244,0.0101,-0.000622,-0.28,-3.52e-06,-6.61e-06,4.8e-08,3.3e-06,-1.82e-06,4.59e-06,0.203,0.0109,0.434,0,0,0,0,0,4.77e-05,0.00675,0.00675,0.00101,1.1,1.1,0.163,0.179,0.179,0.114,9.06e-07,9.06e-07,3.92e-07,3.98e-06,3.98e-06,3.83e-06,0,0,0,0,0,0,0,0 1790000,0.979,-0.00865,-0.0173,0.205,0.0604,-0.00313,-0.257,0.0157,-0.000918,-0.305,-3.52e-06,-6.61e-06,4.8e-08,3.3e-06,-1.82e-06,4.59e-06,0.203,0.0109,0.434,0,0,0,0,0,4.75e-05,0.00743,0.00743,0.000993,1.44,1.44,0.147,0.262,0.262,0.11,9.06e-07,9.06e-07,3.51e-07,3.98e-06,3.98e-06,3.8e-06,0,0,0,0,0,0,0,0 -1890000,0.979,-0.00832,-0.0166,0.205,0.0501,7.35e-05,-0.269,0.0114,-0.000469,-0.331,-6.76e-06,-1.3e-05,1.05e-07,5.58e-06,-2.98e-06,4.46e-06,0.203,0.0109,0.434,0,0,0,0,0,4.63e-05,0.00657,0.00657,0.000975,1.18,1.18,0.137,0.178,0.178,0.109,8.15e-07,8.16e-07,3.15e-07,3.97e-06,3.97e-06,3.76e-06,0,0,0,0,0,0,0,0 -1990000,0.979,-0.0084,-0.0169,0.205,0.0585,0.000588,-0.282,0.0168,-0.000494,-0.359,-6.76e-06,-1.3e-05,1.05e-07,5.58e-06,-2.98e-06,4.46e-06,0.203,0.0109,0.434,0,0,0,0,0,4.58e-05,0.00722,0.00722,0.000955,1.54,1.54,0.126,0.266,0.266,0.105,8.15e-07,8.16e-07,2.82e-07,3.97e-06,3.97e-06,3.72e-06,0,0,0,0,0,0,0,0 -2090000,0.979,-0.00819,-0.0161,0.205,0.0446,0.0016,-0.296,0.0111,-0.000118,-0.388,-1.04e-05,-2.08e-05,1.73e-07,7.87e-06,-4.05e-06,4.31e-06,0.203,0.0109,0.434,0,0,0,0,0,4.42e-05,0.00588,0.00588,0.000934,1.18,1.18,0.118,0.177,0.177,0.102,7.03e-07,7.03e-07,2.52e-07,3.96e-06,3.96e-06,3.67e-06,0,0,0,0,0,0,0,0 -2190000,0.979,-0.00811,-0.0164,0.205,0.0523,0.00169,-0.293,0.0162,0.000102,-0.4,-1.03e-05,-2.05e-05,1.71e-07,7.17e-06,-3.42e-06,-2.46e-05,0.203,0.0109,0.434,0,0,0,0,0,4.36e-05,0.00645,0.00645,0.000912,1.51,1.51,0.113,0.267,0.267,0.101,7.03e-07,7.03e-07,2.27e-07,3.96e-06,3.96e-06,3.62e-06,0,0,0,0,0,0,0,0 +1890000,0.979,-0.00832,-0.0166,0.205,0.0501,7.36e-05,-0.269,0.0114,-0.000469,-0.331,-6.76e-06,-1.3e-05,1.05e-07,5.58e-06,-2.98e-06,4.46e-06,0.203,0.0109,0.434,0,0,0,0,0,4.63e-05,0.00657,0.00657,0.000975,1.18,1.18,0.137,0.178,0.178,0.109,8.15e-07,8.16e-07,3.15e-07,3.97e-06,3.97e-06,3.76e-06,0,0,0,0,0,0,0,0 +1990000,0.979,-0.0084,-0.0169,0.205,0.0585,0.000588,-0.282,0.0168,-0.000493,-0.359,-6.76e-06,-1.3e-05,1.05e-07,5.58e-06,-2.98e-06,4.46e-06,0.203,0.0109,0.434,0,0,0,0,0,4.58e-05,0.00722,0.00722,0.000955,1.54,1.54,0.126,0.266,0.266,0.105,8.15e-07,8.16e-07,2.82e-07,3.97e-06,3.97e-06,3.72e-06,0,0,0,0,0,0,0,0 +2090000,0.979,-0.00819,-0.0161,0.205,0.0446,0.00161,-0.296,0.0111,-0.000118,-0.388,-1.04e-05,-2.08e-05,1.73e-07,7.87e-06,-4.05e-06,4.31e-06,0.203,0.0109,0.434,0,0,0,0,0,4.42e-05,0.00588,0.00588,0.000934,1.18,1.18,0.118,0.177,0.177,0.102,7.03e-07,7.03e-07,2.52e-07,3.96e-06,3.96e-06,3.67e-06,0,0,0,0,0,0,0,0 +2190000,0.979,-0.00811,-0.0164,0.205,0.0523,0.00169,-0.293,0.0162,0.000103,-0.4,-1.03e-05,-2.05e-05,1.71e-07,7.17e-06,-3.42e-06,-2.46e-05,0.203,0.0109,0.434,0,0,0,0,0,4.36e-05,0.00645,0.00645,0.000912,1.51,1.51,0.113,0.267,0.267,0.101,7.03e-07,7.03e-07,2.27e-07,3.96e-06,3.96e-06,3.62e-06,0,0,0,0,0,0,0,0 2290000,0.979,-0.00794,-0.0156,0.205,0.037,0.00274,-0.275,0.0102,0.000239,-0.394,-1.33e-05,-2.77e-05,2.28e-07,7.55e-06,-2.91e-06,-8.4e-05,0.203,0.0109,0.434,0,0,0,0,0,4.18e-05,0.00497,0.00497,0.00089,1.09,1.09,0.107,0.173,0.173,0.0977,5.9e-07,5.91e-07,2.04e-07,3.95e-06,3.95e-06,3.56e-06,0,0,0,0,0,0,0,0 2390000,0.979,-0.00796,-0.0158,0.205,0.0446,0.00236,-0.263,0.0146,0.000477,-0.391,-1.32e-05,-2.73e-05,2.24e-07,6.19e-06,-1.67e-06,-0.000142,0.203,0.0109,0.434,0,0,0,0,0,4.11e-05,0.00545,0.00545,0.000867,1.38,1.39,0.103,0.259,0.259,0.0949,5.9e-07,5.91e-07,1.84e-07,3.95e-06,3.95e-06,3.49e-06,0,0,0,0,0,0,0,0 2490000,0.979,-0.00769,-0.015,0.205,0.0284,0.00337,-0.259,0.00872,0.000394,-0.4,-1.57e-05,-3.37e-05,2.7e-07,6.44e-06,-1.33e-06,-0.000178,0.203,0.0109,0.434,0,0,0,0,0,3.94e-05,0.00411,0.00411,0.000845,0.963,0.963,0.101,0.166,0.166,0.0946,4.92e-07,4.93e-07,1.66e-07,3.95e-06,3.95e-06,3.43e-06,0,0,0,0,0,0,0,0 -2590000,0.979,-0.00779,-0.0152,0.205,0.0323,0.00208,-0.247,0.012,0.000675,-0.397,-1.56e-05,-3.34e-05,2.68e-07,5.1e-06,-9.65e-08,-0.000238,0.203,0.0109,0.434,0,0,0,0,0,3.86e-05,0.00452,0.00452,0.000823,1.21,1.21,0.0981,0.245,0.245,0.0923,4.92e-07,4.93e-07,1.5e-07,3.95e-06,3.95e-06,3.35e-06,0,0,0,0,0,0,0,0 +2590000,0.979,-0.00779,-0.0152,0.205,0.0323,0.00208,-0.247,0.012,0.000675,-0.397,-1.56e-05,-3.34e-05,2.68e-07,5.1e-06,-9.66e-08,-0.000238,0.203,0.0109,0.434,0,0,0,0,0,3.86e-05,0.00452,0.00452,0.000823,1.21,1.21,0.0981,0.245,0.245,0.0923,4.92e-07,4.93e-07,1.5e-07,3.95e-06,3.95e-06,3.35e-06,0,0,0,0,0,0,0,0 2690000,0.979,-0.00772,-0.0146,0.205,0.0208,0.00295,-0.235,0.00706,0.000467,-0.394,-1.73e-05,-3.82e-05,2.99e-07,4.12e-06,1.04e-06,-0.000299,0.203,0.0109,0.434,0,0,0,0,0,3.7e-05,0.00342,0.00342,0.000802,0.836,0.836,0.096,0.157,0.157,0.0903,4.12e-07,4.12e-07,1.36e-07,3.95e-06,3.95e-06,3.26e-06,0,0,0,0,0,0,0,0 -2790000,0.979,-0.00762,-0.0147,0.205,0.0256,0.00351,-0.226,0.00965,0.000813,-0.393,-1.72e-05,-3.79e-05,2.97e-07,2.86e-06,2.2e-06,-0.000356,0.203,0.0109,0.434,0,0,0,0,0,3.62e-05,0.00376,0.00376,0.000781,1.05,1.05,0.0943,0.228,0.228,0.0885,4.12e-07,4.12e-07,1.23e-07,3.95e-06,3.95e-06,3.17e-06,0,0,0,0,0,0,0,0 +2790000,0.979,-0.00762,-0.0147,0.205,0.0256,0.00351,-0.226,0.00965,0.000814,-0.393,-1.72e-05,-3.79e-05,2.97e-07,2.86e-06,2.2e-06,-0.000356,0.203,0.0109,0.434,0,0,0,0,0,3.62e-05,0.00376,0.00376,0.000781,1.05,1.05,0.0943,0.228,0.228,0.0885,4.12e-07,4.12e-07,1.23e-07,3.95e-06,3.95e-06,3.17e-06,0,0,0,0,0,0,0,0 2890000,0.979,-0.00759,-0.0143,0.205,0.0181,0.00184,-0.222,0.00574,0.000506,-0.399,-1.85e-05,-4.16e-05,3.18e-07,1.91e-06,3.08e-06,-0.000398,0.203,0.0109,0.434,0,0,0,0,0,3.48e-05,0.0029,0.0029,0.000761,0.727,0.727,0.0942,0.148,0.148,0.0889,3.47e-07,3.47e-07,1.12e-07,3.95e-06,3.95e-06,3.08e-06,0,0,0,0,0,0,0,0 2990000,0.979,-0.00756,-0.0144,0.205,0.0208,0.00137,-0.207,0.00795,0.000696,-0.392,-1.84e-05,-4.14e-05,3.17e-07,3.11e-07,4.56e-06,-0.000471,0.203,0.0109,0.434,0,0,0,0,0,3.41e-05,0.00319,0.00319,0.000741,0.904,0.904,0.0929,0.211,0.211,0.0875,3.47e-07,3.47e-07,1.02e-07,3.95e-06,3.95e-06,2.98e-06,0,0,0,0,0,0,0,0 3090000,0.979,-0.0075,-0.0141,0.205,0.017,-0.000483,-0.203,0.00489,0.000335,-0.395,-1.94e-05,-4.43e-05,3.34e-07,-9.68e-07,5.59e-06,-0.000516,0.203,0.0109,0.434,0,0,0,0,0,3.29e-05,0.00252,0.00252,0.000722,0.638,0.638,0.0919,0.139,0.139,0.0862,2.94e-07,2.94e-07,9.36e-08,3.95e-06,3.95e-06,2.87e-06,0,0,0,0,0,0,0,0 -3190000,0.979,-0.00749,-0.0143,0.205,0.0201,-0.00147,-0.195,0.00684,0.00019,-0.398,-1.94e-05,-4.42e-05,3.34e-07,-2.01e-06,6.55e-06,-0.000563,0.203,0.0109,0.434,0,0,0,0,0,3.23e-05,0.00277,0.00277,0.000704,0.791,0.791,0.092,0.196,0.196,0.087,2.94e-07,2.94e-07,8.58e-08,3.95e-06,3.95e-06,2.78e-06,0,0,0,0,0,0,0,0 -3290000,0.979,-0.00737,-0.0139,0.205,0.0145,-0.00116,-0.183,0.00435,1.62e-06,-0.394,-2.04e-05,-4.65e-05,3.52e-07,-3.87e-06,8.03e-06,-0.000628,0.203,0.0109,0.434,0,0,0,0,0,3.12e-05,0.00222,0.00222,0.000686,0.567,0.567,0.0909,0.131,0.131,0.086,2.49e-07,2.49e-07,7.87e-08,3.94e-06,3.94e-06,2.66e-06,0,0,0,0,0,0,0,0 +3190000,0.979,-0.00749,-0.0143,0.205,0.0201,-0.00148,-0.195,0.00684,0.00019,-0.398,-1.94e-05,-4.42e-05,3.34e-07,-2.01e-06,6.55e-06,-0.000563,0.203,0.0109,0.434,0,0,0,0,0,3.23e-05,0.00277,0.00277,0.000704,0.791,0.791,0.092,0.196,0.196,0.087,2.94e-07,2.94e-07,8.58e-08,3.95e-06,3.95e-06,2.78e-06,0,0,0,0,0,0,0,0 +3290000,0.979,-0.00737,-0.0139,0.205,0.0145,-0.00116,-0.183,0.00435,1.63e-06,-0.394,-2.04e-05,-4.65e-05,3.52e-07,-3.87e-06,8.03e-06,-0.000628,0.203,0.0109,0.434,0,0,0,0,0,3.12e-05,0.00222,0.00222,0.000686,0.567,0.567,0.0909,0.131,0.131,0.086,2.49e-07,2.49e-07,7.87e-08,3.94e-06,3.94e-06,2.66e-06,0,0,0,0,0,0,0,0 3390000,0.979,-0.00721,-0.014,0.205,0.0157,0.000219,-0.174,0.00588,-6.31e-05,-0.391,-2.04e-05,-4.64e-05,3.52e-07,-5.16e-06,9.2e-06,-0.000686,0.203,0.0109,0.434,0,0,0,0,0,3.05e-05,0.00244,0.00244,0.000669,0.702,0.702,0.0898,0.183,0.183,0.0851,2.49e-07,2.49e-07,7.24e-08,3.94e-06,3.94e-06,2.54e-06,0,0,0,0,0,0,0,0 3490000,0.979,-0.00715,-0.014,0.205,0.0195,0.00301,-0.172,0.00774,9.49e-05,-0.398,-2.04e-05,-4.64e-05,3.51e-07,-5.81e-06,9.79e-06,-0.000716,0.203,0.0109,0.434,0,0,0,0,0,2.99e-05,0.00268,0.00268,0.000653,0.86,0.86,0.0898,0.254,0.254,0.0861,2.49e-07,2.49e-07,6.68e-08,3.94e-06,3.94e-06,2.44e-06,0,0,0,0,0,0,0,0 3590000,0.979,-0.00699,-0.0136,0.205,0.0157,0.00279,-0.167,0.00528,0.00032,-0.399,-2.12e-05,-4.83e-05,3.66e-07,-7.38e-06,1.09e-05,-0.000762,0.203,0.0109,0.434,0,0,0,0,0,2.89e-05,0.00218,0.00218,0.000637,0.632,0.632,0.0884,0.171,0.171,0.0853,2.11e-07,2.11e-07,6.16e-08,3.94e-06,3.94e-06,2.31e-06,0,0,0,0,0,0,0,0 @@ -74,7 +74,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 7190000,0.982,-0.00644,-0.0122,0.188,-0.00814,0.0147,-0.106,-0.00306,0.00616,-0.582,-1.63e-05,-5.79e-05,2.15e-07,-2.4e-05,1.56e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,4.82e-05,0.000314,0.000314,0.00128,0.161,0.161,0.028,0.122,0.122,0.0638,6.62e-09,6.63e-09,8.49e-09,3.86e-06,3.86e-06,2.19e-07,0,0,0,0,0,0,0,0 7290000,0.982,-0.00642,-0.0121,0.188,-0.00769,0.0181,-0.108,-0.00391,0.00776,-0.593,-1.63e-05,-5.79e-05,2.39e-07,-2.4e-05,1.56e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,3.28e-05,0.000315,0.000315,0.000872,0.167,0.167,0.027,0.148,0.148,0.0628,6.62e-09,6.62e-09,8.49e-09,3.86e-06,3.86e-06,2.06e-07,0,0,0,0,0,0,0,0 7390000,0.982,-0.0063,-0.0121,0.188,-0.00979,0.0203,-0.109,-0.00478,0.00973,-0.604,-1.63e-05,-5.79e-05,2.53e-07,-2.4e-05,1.56e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,2.56e-05,0.000316,0.000315,0.000681,0.176,0.176,0.0263,0.177,0.177,0.0628,6.62e-09,6.62e-09,8.48e-09,3.86e-06,3.86e-06,1.96e-07,0,0,0,0,0,0,0,0 -7490000,0.982,-0.00631,-0.0122,0.187,-0.00782,0.0224,-0.109,-0.00563,0.0119,-0.615,-1.63e-05,-5.79e-05,3.44e-07,-2.4e-05,1.56e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,2.05e-05,0.000317,0.000317,0.000545,0.188,0.188,0.0253,0.21,0.21,0.0618,6.61e-09,6.62e-09,8.48e-09,3.86e-06,3.86e-06,1.85e-07,0,0,0,0,0,0,0,0 +7490000,0.982,-0.00631,-0.0122,0.187,-0.00782,0.0224,-0.109,-0.00562,0.0119,-0.615,-1.63e-05,-5.79e-05,3.44e-07,-2.4e-05,1.56e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,2.05e-05,0.000317,0.000317,0.000545,0.188,0.188,0.0253,0.21,0.21,0.0618,6.61e-09,6.62e-09,8.48e-09,3.86e-06,3.86e-06,1.85e-07,0,0,0,0,0,0,0,0 7590000,0.982,-0.00639,-0.0121,0.187,-0.00719,0.0246,-0.11,-0.00638,0.0142,-0.626,-1.63e-05,-5.79e-05,3.53e-07,-2.4e-05,1.56e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,1.72e-05,0.000318,0.000318,0.000455,0.205,0.205,0.0244,0.247,0.247,0.0609,6.61e-09,6.62e-09,8.48e-09,3.86e-06,3.86e-06,1.74e-07,0,0,0,0,0,0,0,0 7690000,0.982,-0.00641,-0.0122,0.187,-0.00789,0.0277,-0.114,-0.00713,0.0168,-0.637,-1.63e-05,-5.79e-05,3.31e-07,-2.4e-05,1.56e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,1.5e-05,0.00032,0.00032,0.000398,0.225,0.225,0.0239,0.289,0.289,0.0608,6.61e-09,6.62e-09,8.47e-09,3.86e-06,3.86e-06,1.66e-07,0,0,0,0,0,0,0,0 7790000,0.982,-0.00629,-0.0122,0.187,-0.00667,0.0293,-0.116,-0.00784,0.0196,-0.648,-1.63e-05,-5.79e-05,2.72e-07,-2.4e-05,1.56e-05,-0.00126,0.204,0.00201,0.435,0,0,0,0,0,1.32e-05,0.000322,0.000322,0.000348,0.249,0.249,0.023,0.335,0.335,0.0599,6.6e-09,6.61e-09,8.46e-09,3.86e-06,3.86e-06,1.57e-07,0,0,0,0,0,0,0,0 @@ -135,10 +135,10 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 13290000,0.982,-0.00714,-0.0115,0.187,0.00323,-0.00287,0.152,0.00116,-0.00421,-0.0287,-1.18e-05,-5.94e-05,-7.37e-07,-8.73e-06,5.62e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.71e-06,0.000199,0.000199,0.000126,0.0641,0.0641,0.0101,0.0555,0.0555,0.0465,3.76e-09,3.76e-09,3.39e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0 13390000,0.982,-0.00708,-0.0117,0.187,0.00247,-0.00133,0.148,0.000779,-0.00324,-0.0311,-1.19e-05,-5.94e-05,-1.02e-06,-9.08e-06,5.62e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.68e-06,0.00019,0.00019,0.000125,0.0533,0.0533,0.00943,0.0476,0.0476,0.0452,3.63e-09,3.63e-09,3.29e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0 13490000,0.982,-0.00706,-0.0116,0.187,0.00294,0.00056,0.145,0.00106,-0.00321,-0.0338,-1.19e-05,-5.94e-05,-7.27e-07,-9.23e-06,5.63e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.66e-06,0.000195,0.000196,0.000125,0.0605,0.0605,0.00904,0.0552,0.0552,0.0445,3.63e-09,3.63e-09,3.19e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0 -13590000,0.982,-0.00707,-0.0117,0.187,0.00731,9.69e-07,0.143,0.00387,-0.00272,-0.0368,-1.18e-05,-5.91e-05,-9.04e-07,-8.93e-06,5.61e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.66e-06,0.000187,0.000187,0.000125,0.0507,0.0507,0.00862,0.0474,0.0474,0.0439,3.49e-09,3.5e-09,3.11e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0 +13590000,0.982,-0.00707,-0.0117,0.187,0.00731,9.89e-07,0.143,0.00387,-0.00272,-0.0368,-1.18e-05,-5.91e-05,-9.04e-07,-8.93e-06,5.61e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.66e-06,0.000187,0.000187,0.000125,0.0507,0.0507,0.00862,0.0474,0.0474,0.0439,3.49e-09,3.5e-09,3.11e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0 13690000,0.982,-0.00702,-0.0116,0.187,0.00731,-0.00122,0.142,0.00458,-0.00278,-0.0336,-1.18e-05,-5.91e-05,-3.85e-07,-9.03e-06,5.62e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.63e-06,0.000193,0.000193,0.000124,0.0574,0.0574,0.00832,0.0549,0.0549,0.0432,3.49e-09,3.5e-09,3.02e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0 13790000,0.982,-0.00697,-0.0118,0.187,0.0141,0.00254,0.138,0.00807,-0.000575,-0.0374,-1.19e-05,-5.87e-05,-5.76e-07,-7.54e-06,5.66e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.6e-06,0.000186,0.000186,0.000123,0.0485,0.0485,0.00794,0.0472,0.0472,0.0421,3.36e-09,3.36e-09,2.93e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0 -13890000,0.982,-0.00688,-0.0117,0.187,0.0152,0.00345,0.138,0.00952,-0.000269,-0.0338,-1.18e-05,-5.87e-05,5.24e-08,-7.66e-06,5.66e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.59e-06,0.000191,0.000191,0.000123,0.0547,0.0547,0.00777,0.0546,0.0546,0.0419,3.36e-09,3.36e-09,2.85e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0 +13890000,0.982,-0.00688,-0.0117,0.187,0.0152,0.00345,0.138,0.00952,-0.000269,-0.0338,-1.18e-05,-5.87e-05,5.23e-08,-7.66e-06,5.66e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.59e-06,0.000191,0.000191,0.000123,0.0547,0.0547,0.00777,0.0546,0.0546,0.0419,3.36e-09,3.36e-09,2.85e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0 13990000,0.982,-0.00694,-0.0114,0.187,0.0147,0.00344,0.133,0.00721,-0.0019,-0.0384,-1.17e-05,-5.91e-05,7.05e-07,-9.88e-06,5.6e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.56e-06,0.000184,0.000184,0.000122,0.0465,0.0465,0.00748,0.0471,0.0471,0.0409,3.22e-09,3.22e-09,2.77e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0 14090000,0.982,-0.00695,-0.0114,0.187,0.0124,-0.000786,0.133,0.00866,-0.00179,-0.0425,-1.17e-05,-5.91e-05,-6.07e-07,-1.02e-05,5.62e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.54e-06,0.00019,0.00019,0.000121,0.0525,0.0525,0.00733,0.0543,0.0543,0.0403,3.22e-09,3.22e-09,2.69e-09,3.46e-06,3.46e-06,5.01e-08,0,0,0,0,0,0,0,0 14190000,0.982,-0.00692,-0.0113,0.187,0.00982,0.000264,0.13,0.0079,-0.00137,-0.0444,-1.18e-05,-5.92e-05,-1.19e-06,-1.08e-05,5.68e-05,-0.00162,0.204,0.00201,0.435,0,0,0,0,0,4.53e-06,0.000184,0.000184,0.000121,0.0449,0.0449,0.00715,0.0469,0.0469,0.0398,3.08e-09,3.08e-09,2.62e-09,3.45e-06,3.45e-06,5e-08,0,0,0,0,0,0,0,0 @@ -206,12 +206,12 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 20390000,0.982,-0.00662,-0.0103,0.187,-0.00963,-0.000481,0.0238,0.00581,-0.000228,-0.264,-1.51e-05,-5.94e-05,7.49e-07,-4.81e-05,0.000135,-0.00135,0.204,0.00201,0.435,0,0,0,0,0,3.01e-06,0.000102,0.000102,8.12e-05,0.0244,0.0244,0.00827,0.0434,0.0434,0.0357,2.14e-10,2.14e-10,5.67e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 20490000,0.982,-0.00661,-0.0102,0.186,-0.0144,-0.00138,0.0226,0.0046,-0.000293,-0.27,-1.51e-05,-5.94e-05,7.17e-07,-4.88e-05,0.000135,-0.00135,0.204,0.00201,0.435,0,0,0,0,0,2.99e-06,0.000103,0.000103,8.06e-05,0.0266,0.0266,0.0083,0.0487,0.0487,0.0357,2.14e-10,2.14e-10,5.55e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 20590000,0.982,-0.00659,-0.0102,0.186,-0.0133,-0.00242,0.0212,0.00585,-0.000249,-0.275,-1.51e-05,-5.93e-05,9.64e-07,-4.7e-05,0.000135,-0.00135,0.204,0.00201,0.435,0,0,0,0,0,2.96e-06,0.0001,0.0001,8e-05,0.0238,0.0238,0.00821,0.0433,0.0433,0.0355,1.97e-10,1.97e-10,5.44e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0 -20690000,0.982,-0.0065,-0.0102,0.186,-0.0151,-0.00113,0.0214,0.00445,-0.000373,-0.278,-1.51e-05,-5.93e-05,7.36e-07,-4.76e-05,0.000135,-0.00134,0.204,0.00201,0.435,0,0,0,0,0,2.95e-06,0.000101,0.000101,7.97e-05,0.0259,0.0259,0.00829,0.0485,0.0485,0.0359,1.97e-10,1.97e-10,5.34e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0 +20690000,0.982,-0.0065,-0.0102,0.186,-0.0151,-0.00113,0.0214,0.00445,-0.000373,-0.278,-1.51e-05,-5.93e-05,7.35e-07,-4.76e-05,0.000135,-0.00134,0.204,0.00201,0.435,0,0,0,0,0,2.95e-06,0.000101,0.000101,7.97e-05,0.0259,0.0259,0.00829,0.0485,0.0485,0.0359,1.97e-10,1.97e-10,5.34e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0 20790000,0.982,-0.00591,-0.0102,0.186,-0.0174,0.00134,0.00537,0.00376,-0.000273,-0.283,-1.51e-05,-5.92e-05,8.06e-07,-4.66e-05,0.000135,-0.00134,0.204,0.00201,0.435,0,0,0,0,0,2.93e-06,9.91e-05,9.9e-05,7.91e-05,0.0232,0.0232,0.0082,0.0431,0.0431,0.0356,1.82e-10,1.82e-10,5.23e-10,2.98e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0 20890000,0.982,0.00321,-0.00615,0.186,-0.0238,0.0134,-0.114,0.00164,0.000509,-0.293,-1.51e-05,-5.92e-05,8.01e-07,-4.69e-05,0.000135,-0.00134,0.204,0.00201,0.435,0,0,0,0,0,2.9e-06,9.97e-05,9.97e-05,7.86e-05,0.0256,0.0256,0.00823,0.0483,0.0483,0.0357,1.82e-10,1.82e-10,5.13e-10,2.98e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0 20990000,0.982,0.00653,-0.00273,0.186,-0.0345,0.0313,-0.254,0.00117,0.00104,-0.311,-1.49e-05,-5.92e-05,7.52e-07,-4.46e-05,0.000132,-0.00134,0.204,0.00201,0.435,0,0,0,0,0,2.88e-06,9.77e-05,9.76e-05,7.8e-05,0.0233,0.0233,0.00814,0.0429,0.0429,0.0354,1.68e-10,1.68e-10,5.03e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0 21090000,0.982,0.00495,-0.00311,0.187,-0.0482,0.0474,-0.373,-0.00297,0.00502,-0.345,-1.49e-05,-5.91e-05,7.35e-07,-4.48e-05,0.000132,-0.00134,0.204,0.00201,0.435,0,0,0,0,0,2.88e-06,9.83e-05,9.82e-05,7.77e-05,0.0256,0.0256,0.00822,0.0481,0.0481,0.0358,1.68e-10,1.68e-10,4.94e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0 -21190000,0.982,0.00206,-0.00479,0.187,-0.0517,0.0513,-0.5,-0.00228,0.00399,-0.384,-1.46e-05,-5.9e-05,7.94e-07,-3.98e-05,0.000122,-0.00135,0.204,0.00201,0.435,0,0,0,0,0,2.87e-06,9.61e-05,9.61e-05,7.72e-05,0.0232,0.0232,0.00813,0.0428,0.0428,0.0356,1.55e-10,1.55e-10,4.84e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0 +21190000,0.982,0.00206,-0.00479,0.187,-0.0517,0.0513,-0.5,-0.00228,0.00399,-0.384,-1.46e-05,-5.9e-05,7.93e-07,-3.98e-05,0.000122,-0.00135,0.204,0.00201,0.435,0,0,0,0,0,2.87e-06,9.61e-05,9.61e-05,7.72e-05,0.0232,0.0232,0.00813,0.0428,0.0428,0.0356,1.55e-10,1.55e-10,4.84e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0 21290000,0.982,-0.000105,-0.00612,0.187,-0.0522,0.0551,-0.631,-0.00748,0.00934,-0.446,-1.46e-05,-5.9e-05,4.96e-07,-4e-05,0.000122,-0.00134,0.204,0.00201,0.435,0,0,0,0,0,2.85e-06,9.67e-05,9.67e-05,7.66e-05,0.0256,0.0256,0.00816,0.048,0.048,0.0356,1.55e-10,1.56e-10,4.75e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0 21390000,0.982,-0.0016,-0.00685,0.187,-0.0473,0.0508,-0.756,-0.00606,0.0115,-0.513,-1.44e-05,-5.88e-05,4.99e-07,-3.43e-05,0.000116,-0.00135,0.204,0.00201,0.435,0,0,0,0,0,2.85e-06,9.45e-05,9.44e-05,7.64e-05,0.0232,0.0232,0.00812,0.0427,0.0427,0.0357,1.44e-10,1.44e-10,4.66e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0 21490000,0.982,-0.0024,-0.00726,0.187,-0.0432,0.0483,-0.893,-0.0107,0.0165,-0.602,-1.44e-05,-5.88e-05,6.21e-07,-3.47e-05,0.000117,-0.00134,0.204,0.00201,0.435,0,0,0,0,0,2.84e-06,9.5e-05,9.49e-05,7.58e-05,0.0255,0.0255,0.00815,0.0479,0.0479,0.0357,1.44e-10,1.44e-10,4.57e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0 @@ -277,7 +277,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 27490000,0.982,-0.00981,-0.0157,0.186,-0.0796,0.0527,0.759,0.0473,-0.0293,-3.86,-1.6e-05,-5.84e-05,1.05e-07,-2.99e-05,4.21e-05,-0.00121,0.204,0.00201,0.435,0,0,0,0,0,2.08e-06,8.2e-05,8.19e-05,5.59e-05,0.0141,0.0141,0.00803,0.0416,0.0416,0.0352,3.94e-11,3.94e-11,1.8e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 27590000,0.982,-0.00968,-0.0146,0.186,-0.0735,0.0551,0.853,0.039,-0.0253,-3.79,-1.6e-05,-5.84e-05,7.04e-08,-3.09e-05,4.24e-05,-0.0012,0.204,0.00201,0.435,0,0,0,0,0,2.07e-06,8.2e-05,8.19e-05,5.57e-05,0.0131,0.0131,0.008,0.0378,0.0378,0.0353,3.85e-11,3.85e-11,1.78e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 27690000,0.983,-0.00846,-0.0116,0.186,-0.0705,0.0518,0.755,0.0318,-0.0199,-3.72,-1.6e-05,-5.84e-05,5.64e-08,-3.05e-05,4.15e-05,-0.00119,0.204,0.00201,0.435,0,0,0,0,0,2.05e-06,8.22e-05,8.21e-05,5.54e-05,0.014,0.014,0.00804,0.0414,0.0414,0.0354,3.86e-11,3.86e-11,1.75e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 -27790000,0.983,-0.00712,-0.0102,0.186,-0.0698,0.0495,0.749,0.0257,-0.0174,-3.65,-1.59e-05,-5.84e-05,5.28e-08,-3.29e-05,4.79e-05,-0.00119,0.204,0.00201,0.435,0,0,0,0,0,2.04e-06,8.23e-05,8.22e-05,5.52e-05,0.013,0.013,0.00797,0.0377,0.0377,0.0351,3.78e-11,3.78e-11,1.73e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 +27790000,0.983,-0.00712,-0.0102,0.186,-0.0698,0.0495,0.749,0.0257,-0.0174,-3.65,-1.59e-05,-5.84e-05,5.27e-08,-3.29e-05,4.79e-05,-0.00119,0.204,0.00201,0.435,0,0,0,0,0,2.04e-06,8.23e-05,8.22e-05,5.52e-05,0.013,0.013,0.00797,0.0377,0.0377,0.0351,3.78e-11,3.78e-11,1.73e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 27890000,0.983,-0.00676,-0.0102,0.186,-0.0767,0.0566,0.788,0.0183,-0.0122,-3.57,-1.59e-05,-5.84e-05,1.48e-08,-3.27e-05,4.73e-05,-0.00119,0.204,0.00201,0.435,0,0,0,0,0,2.04e-06,8.24e-05,8.24e-05,5.5e-05,0.0139,0.0139,0.00806,0.0413,0.0413,0.0355,3.79e-11,3.79e-11,1.71e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 27990000,0.983,-0.00721,-0.0106,0.186,-0.077,0.058,0.775,0.013,-0.0105,-3.5,-1.58e-05,-5.83e-05,-2.78e-08,-3.49e-05,5.14e-05,-0.00119,0.204,0.00201,0.435,0,0,0,0,0,2.03e-06,8.25e-05,8.24e-05,5.47e-05,0.013,0.013,0.00799,0.0376,0.0376,0.0352,3.71e-11,3.71e-11,1.69e-10,2.83e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 28090000,0.983,-0.00747,-0.0106,0.186,-0.0807,0.0587,0.782,0.00512,-0.00461,-3.43,-1.58e-05,-5.83e-05,6.57e-08,-3.49e-05,5.13e-05,-0.00119,0.204,0.00201,0.435,0,0,0,0,0,2.02e-06,8.27e-05,8.26e-05,5.45e-05,0.0139,0.0139,0.00803,0.0412,0.0412,0.0353,3.72e-11,3.72e-11,1.67e-10,2.83e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 @@ -293,7 +293,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 29090000,0.983,-0.00531,-0.0114,0.186,-0.0821,0.0627,0.78,-0.0532,0.0279,-2.7,-1.51e-05,-5.8e-05,1.69e-07,-3.82e-05,5.59e-05,-0.00116,0.204,0.00201,0.435,0,0,0,0,0,1.94e-06,8.37e-05,8.37e-05,5.23e-05,0.0137,0.0137,0.00802,0.0408,0.0408,0.0353,3.41e-11,3.41e-11,1.48e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 29190000,0.983,-0.00527,-0.0116,0.186,-0.0784,0.0612,0.775,-0.0509,0.0271,-2.63,-1.5e-05,-5.79e-05,2.32e-07,-3.81e-05,5.46e-05,-0.00115,0.204,0.00201,0.435,0,0,0,0,0,1.94e-06,8.37e-05,8.36e-05,5.21e-05,0.0127,0.0127,0.00799,0.0372,0.0372,0.0354,3.35e-11,3.35e-11,1.46e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 29290000,0.983,-0.00553,-0.0116,0.186,-0.0805,0.0673,0.778,-0.0588,0.0336,-2.55,-1.5e-05,-5.79e-05,2.49e-07,-3.79e-05,5.42e-05,-0.00115,0.204,0.00201,0.435,0,0,0,0,0,1.93e-06,8.39e-05,8.38e-05,5.19e-05,0.0136,0.0136,0.00803,0.0407,0.0407,0.0354,3.36e-11,3.36e-11,1.44e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -29390000,0.983,-0.00598,-0.0111,0.186,-0.0759,0.0656,0.78,-0.0571,0.0344,-2.48,-1.49e-05,-5.79e-05,2.89e-07,-3.79e-05,5.31e-05,-0.00115,0.204,0.00201,0.435,0,0,0,0,0,1.92e-06,8.38e-05,8.37e-05,5.16e-05,0.0127,0.0127,0.00796,0.0372,0.0372,0.0352,3.3e-11,3.3e-11,1.43e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +29390000,0.983,-0.00598,-0.0111,0.186,-0.0759,0.0656,0.78,-0.0571,0.0344,-2.48,-1.49e-05,-5.79e-05,2.88e-07,-3.79e-05,5.31e-05,-0.00115,0.204,0.00201,0.435,0,0,0,0,0,1.92e-06,8.38e-05,8.37e-05,5.16e-05,0.0127,0.0127,0.00796,0.0372,0.0372,0.0352,3.3e-11,3.3e-11,1.43e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 29490000,0.983,-0.00598,-0.0109,0.186,-0.0788,0.0664,0.78,-0.0648,0.0411,-2.4,-1.49e-05,-5.79e-05,3.97e-07,-3.75e-05,5.25e-05,-0.00115,0.204,0.00201,0.435,0,0,0,0,0,1.92e-06,8.4e-05,8.39e-05,5.15e-05,0.0136,0.0136,0.00805,0.0406,0.0406,0.0355,3.31e-11,3.31e-11,1.41e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 29590000,0.983,-0.00589,-0.0109,0.186,-0.0743,0.0642,0.782,-0.0622,0.0401,-2.33,-1.47e-05,-5.78e-05,5.01e-07,-3.7e-05,5.08e-05,-0.00115,0.204,0.00201,0.435,0,0,0,0,0,1.91e-06,8.39e-05,8.38e-05,5.13e-05,0.0127,0.0127,0.00798,0.0371,0.0371,0.0353,3.25e-11,3.25e-11,1.4e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 29690000,0.983,-0.00593,-0.0107,0.185,-0.0786,0.063,0.777,-0.0698,0.0465,-2.25,-1.47e-05,-5.78e-05,5.93e-07,-3.64e-05,4.96e-05,-0.00114,0.204,0.00201,0.435,0,0,0,0,0,1.9e-06,8.4e-05,8.4e-05,5.1e-05,0.0136,0.0136,0.00802,0.0406,0.0406,0.0353,3.26e-11,3.26e-11,1.38e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 diff --git a/src/modules/ekf2/test/test_EKF_fusionLogic.cpp b/src/modules/ekf2/test/test_EKF_fusionLogic.cpp index d686f140f3..c9b503331d 100644 --- a/src/modules/ekf2/test/test_EKF_fusionLogic.cpp +++ b/src/modules/ekf2/test/test_EKF_fusionLogic.cpp @@ -157,7 +157,7 @@ TEST_F(EkfFusionLogicTest, rejectGpsSignalJump) EXPECT_TRUE(matrix::isEqual(accel_bias_new, accel_bias_old, 0.01f)); // BUT THEN: GPS fusion should reset after a while - // (it takes some time beacuse vel fusion is still good) + // (it takes some time because vel fusion is still good) _sensor_simulator.runSeconds(14); pos_new = _ekf->getPosition(); vel_new = _ekf->getVelocity();