diff --git a/msg/EstimatorStates.msg b/msg/EstimatorStates.msg index f4e3f0f26101..787a005f8797 100644 --- a/msg/EstimatorStates.msg +++ b/msg/EstimatorStates.msg @@ -4,4 +4,4 @@ uint64 timestamp_sample # the timestamp of the raw data (microseconds) float32[24] states # Internal filter states uint8 n_states # Number of states effectively used -float32[24] covariances # Diagonal Elements of Covariance Matrix +float32[23] covariances # Diagonal Elements of Covariance Matrix diff --git a/src/lib/matrix/matrix/Vector.hpp b/src/lib/matrix/matrix/Vector.hpp index 7890192b22fd..dc80e28d2c8a 100644 --- a/src/lib/matrix/matrix/Vector.hpp +++ b/src/lib/matrix/matrix/Vector.hpp @@ -153,6 +153,11 @@ class Vector : public Matrix { (*this).transpose().print(); } + + static size_t size() + { + return M; + } }; template diff --git a/src/modules/ekf2/EKF/control.cpp b/src/modules/ekf2/EKF/control.cpp index 5c7aa5790b62..037ffe86b248 100644 --- a/src/modules/ekf2/EKF/control.cpp +++ b/src/modules/ekf2/EKF/control.cpp @@ -68,7 +68,7 @@ void Ekf::controlFusionModes(const imuSample &imu_delayed) // monitor the tilt alignment if (!_control_status.flags.tilt_align) { // whilst we are aligning the tilt, monitor the variances - const Vector3f angle_err_var_vec = calcRotVecVariances(); + const Vector3f angle_err_var_vec = getQuaternionVariance(); // Once the tilt variances have reduced to equivalent of 3deg uncertainty // and declare the tilt alignment complete diff --git a/src/modules/ekf2/EKF/covariance.cpp b/src/modules/ekf2/EKF/covariance.cpp index 28c5815f1819..6983754c5f7a 100644 --- a/src/modules/ekf2/EKF/covariance.cpp +++ b/src/modules/ekf2/EKF/covariance.cpp @@ -43,7 +43,6 @@ #include "ekf.h" #include -#include #include #include @@ -368,10 +367,8 @@ void Ekf::resetQuatCov(const float yaw_noise) void Ekf::resetQuatCov(const Vector3f &rot_var_ned) { - matrix::SquareMatrix q_cov; - sym::RotVarNedToLowerTriangularQuatCov(_state.vector(), rot_var_ned, &q_cov); - q_cov.copyLowerToUpperTriangle(); - resetStateCovariance(q_cov); + matrix::SquareMatrix q_cov_ned = diag(rot_var_ned); + resetStateCovariance(_R_to_earth.T() * q_cov_ned * _R_to_earth); } #if defined(CONFIG_EKF2_MAGNETOMETER) diff --git a/src/modules/ekf2/EKF/drag_fusion.cpp b/src/modules/ekf2/EKF/drag_fusion.cpp index ca858cd06b68..a9273a597b60 100644 --- a/src/modules/ekf2/EKF/drag_fusion.cpp +++ b/src/modules/ekf2/EKF/drag_fusion.cpp @@ -84,7 +84,7 @@ void Ekf::fuseDrag(const dragSample &drag_sample) _state.vel(2)); const Vector3f rel_wind_body = _state.quat_nominal.rotateVectorInverse(rel_wind_earth); const float rel_wind_speed = rel_wind_body.norm(); - const VectorState state_vector_prev = _state.vector(); + const auto state_vector_prev = _state.vector(); Vector2f bcoef_inv{0.f, 0.f}; diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 4311417d3600..768b24d438fd 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -84,8 +84,6 @@ class Ekf final : public EstimatorInterface // should be called every time new data is pushed into the filter bool update(); - static uint8_t getNumberOfStates() { return State::size; } - const StateSample &state() const { return _state; } #if defined(CONFIG_EKF2_BAROMETER) @@ -233,9 +231,6 @@ class Ekf final : public EstimatorInterface const auto &aid_src_gravity() const { return _aid_src_gravity; } #endif // CONFIG_EKF2_GRAVITY_FUSION - // get the state vector at the delayed time horizon - const matrix::Vector &getStateAtFusionHorizonAsVector() const { return _state.vector(); } - #if defined(CONFIG_EKF2_WIND) // get the wind velocity in m/s const Vector2f &getWindVelocity() const { return _state.wind_vel; }; @@ -408,8 +403,6 @@ class Ekf final : public EstimatorInterface // return a bitmask integer that describes which state estimates can be used for flight control void get_ekf_soln_status(uint16_t *status) const; - // rotate quaternion covariances into variances for an equivalent rotation vector - Vector3f calcRotVecVariances() const; float getYawVar() const; uint8_t getHeightSensorRef() const { return _height_sensor_ref; } diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index e75d9c01cbbd..e6a56655a4b0 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -40,8 +40,6 @@ */ #include "ekf.h" -#include -#include #include #include @@ -758,7 +756,8 @@ void Ekf::get_ekf_soln_status(uint16_t *status) const void Ekf::fuse(const VectorState &K, float innovation) { - _state.quat_nominal -= K.slice(State::quat_nominal.idx, 0) * innovation; + Quatf delta_quat(matrix::AxisAnglef(K.slice(State::quat_nominal.idx, 0) * (-1.f * innovation))); + _state.quat_nominal *= delta_quat; _state.quat_nominal.normalize(); _R_to_earth = Dcmf(_state.quat_nominal); @@ -851,21 +850,11 @@ void Ekf::updateVerticalDeadReckoningStatus() } } -// calculate the variances for the rotation vector equivalent -Vector3f Ekf::calcRotVecVariances() const -{ - Vector3f rot_var; - sym::QuatVarToRotVar(_state.vector(), P, FLT_EPSILON, &rot_var); - return rot_var; -} - float Ekf::getYawVar() const { - VectorState H_YAW; - float yaw_var = 0.f; - computeYawInnovVarAndH(0.f, yaw_var, H_YAW); - - return yaw_var; + const matrix::SquareMatrix3f rot_cov = diag(getQuaternionVariance()); + const auto rot_var_ned = matrix::SquareMatrix(_R_to_earth * rot_cov * _R_to_earth.T()).diag(); + return rot_var_ned(2); } #if defined(CONFIG_EKF2_BAROMETER) @@ -899,7 +888,7 @@ void Ekf::resetQuatStateYaw(float yaw, float yaw_variance) const Quatf quat_before_reset = _state.quat_nominal; // save a copy of covariance in NED frame to restore it after the quat reset - const matrix::SquareMatrix3f rot_cov = diag(calcRotVecVariances()); + const matrix::SquareMatrix3f rot_cov = diag(getQuaternionVariance()); Vector3f rot_var_ned_before_reset = matrix::SquareMatrix3f(_R_to_earth * rot_cov * _R_to_earth.T()).diag(); // update the yaw angle variance diff --git a/src/modules/ekf2/EKF/mag_fusion.cpp b/src/modules/ekf2/EKF/mag_fusion.cpp index 03898b36d038..1dc2f31c3bf8 100644 --- a/src/modules/ekf2/EKF/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/mag_fusion.cpp @@ -62,7 +62,7 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo // Observation jacobian and Kalman gain vectors VectorState H; - const VectorState state_vector = _state.vector(); + const auto state_vector = _state.vector(); sym::ComputeMagInnovInnovVarAndHx(state_vector, P, mag, R_MAG, FLT_EPSILON, &mag_innov, &innov_var, &H); // do not use the synthesized measurement for the magnetomter Z component for 3D fusion diff --git a/src/modules/ekf2/EKF/optflow_fusion.cpp b/src/modules/ekf2/EKF/optflow_fusion.cpp index bcef15721ecf..ef0810b8653f 100644 --- a/src/modules/ekf2/EKF/optflow_fusion.cpp +++ b/src/modules/ekf2/EKF/optflow_fusion.cpp @@ -94,7 +94,7 @@ void Ekf::fuseOptFlow() // a positive offset in earth frame leads to a smaller height above the ground. float range = predictFlowRange(); - const VectorState state_vector = _state.vector(); + const auto state_vector = _state.vector(); Vector2f innov_var; VectorState H; diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py b/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py index 4ab40828b870..67e74569bc37 100755 --- a/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py +++ b/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py @@ -55,7 +55,7 @@ # The state vector is organized in an ordered dictionary State = Values( - quat_nominal = sf.V4(), + quat_nominal = sf.Rot3(), vel = sf.V3(), pos = sf.V3(), gyro_bias = sf.V3(), @@ -99,9 +99,11 @@ class VTangent(sf.Matrix): class MTangent(sf.Matrix): SHAPE = (State.tangent_dim(), State.tangent_dim()) -def state_to_rot3(state: Values): - q = sf.Quaternion(sf.V3(state["quat_nominal"][1], state["quat_nominal"][2], state["quat_nominal"][3]), state["quat_nominal"][0]) - return sf.Rot3(q) +def vstate_to_state(v: VState): + state = State.from_storage(v) + q_px4 = state["quat_nominal"].to_storage() + state["quat_nominal"] = sf.Rot3(sf.Quaternion(xyz=sf.V3(q_px4[1], q_px4[2], q_px4[3]), w=q_px4[0])) + return state def predict_covariance( state: VState, @@ -114,33 +116,80 @@ def predict_covariance( d_ang_var: sf.Scalar ) -> MTangent: - state = State.from_storage(state) + state = vstate_to_state(state) g = sf.Symbol("g") # does not appear in the jacobians - d_vel_b = state["accel_bias"] * d_vel_dt - d_vel_true = d_vel - d_vel_b - - d_ang_b = state["gyro_bias"] * d_ang_dt - d_ang_true = d_ang - d_ang_b - - q = sf.Quaternion(sf.V3(state["quat_nominal"][1], state["quat_nominal"][2], state["quat_nominal"][3]), state["quat_nominal"][0]) - R_to_earth = state_to_rot3(state) - v = state["vel"] - p = state["pos"] - - q_new = q * sf.Quaternion(sf.V3(0.5 * d_ang_true[0], 0.5 * d_ang_true[1], 0.5 * d_ang_true[2]), 1) - v_new = v + R_to_earth * d_vel_true + sf.V3(0, 0, g) * d_vel_dt - p_new = p + v * d_vel_dt - - # Predicted state vector at time t + dt - state_new = state.copy() - state_new["quat_nominal"] = sf.V4(q_new.w, q_new.x, q_new.y, q_new.z), # convert to Hamiltonian form - state_new["vel"] = v_new, - state_new["pos"] = p_new, + state_error = Values( + theta = sf.V3.symbolic("delta_theta"), + vel = sf.V3.symbolic("delta_v"), + pos = sf.V3.symbolic("delta_p"), + gyro_bias = sf.V3.symbolic("delta_w_b"), + accel_bias = sf.V3.symbolic("delta_a_b"), + mag_I = sf.V3.symbolic("mag_I"), + mag_B = sf.V3.symbolic("mag_B"), + wind_vel = sf.V2.symbolic("wind_vel") + ) + + if args.disable_mag: + del state_error["mag_I"] + del state_error["mag_B"] + + if args.disable_wind: + del state_error["wind_vel"] + + # True state kinematics + state_t = Values() + + for key in state.keys(): + if key == "quat_nominal": + # Create true quaternion using small angle approximation of the error rotation + state_t["quat_nominal"] = state["quat_nominal"] * sf.Rot3(sf.Quaternion(xyz=(0.5 * state_error["theta"]), w=1)) + else: + state_t[key] = state[key] + state_error[key] + + noise = Values( + d_vel = sf.V3.symbolic("a_n"), + d_ang = sf.V3.symbolic("w_n"), + ) + + input_t = Values( + d_vel = d_vel - state_t["accel_bias"] * d_vel_dt - noise["d_vel"], + d_ang = d_ang - state_t["gyro_bias"] * d_ang_dt - noise["d_ang"] + ) + + R_t = state_t["quat_nominal"] + state_t_pred = state_t.copy() + state_t_pred["quat_nominal"] = state_t["quat_nominal"] * sf.Rot3(sf.Quaternion(xyz=(0.5 * input_t["d_ang"]), w=1)) + state_t_pred["vel"] = state_t["vel"] + R_t * input_t["d_vel"] + sf.V3(0, 0, g) * d_vel_dt + state_t_pred["pos"] = state_t["pos"] + state_t["vel"] * d_vel_dt + + # Nominal state kinematics + input = Values( + d_vel = d_vel - state["accel_bias"] * d_vel_dt, + d_ang = d_ang - state["gyro_bias"] * d_ang_dt + ) + + R = state["quat_nominal"] + state_pred = state.copy() + state_pred["quat_nominal"] = state["quat_nominal"] * sf.Rot3(sf.Quaternion(xyz=(0.5 * input["d_ang"]), w=1)) + state_pred["vel"] = state["vel"] + R * input["d_vel"] + sf.V3(0, 0, g) * d_vel_dt + state_pred["pos"] = state["pos"] + state["vel"] * d_vel_dt + + # Error state kinematics + state_error_pred = Values() + for key in state_error.keys(): + if key == "theta": + delta_q = sf.Quaternion.from_storage(state_pred["quat_nominal"].to_storage()).conj() * sf.Quaternion.from_storage(state_t_pred["quat_nominal"].to_storage()) + state_error_pred["theta"] = 2 * sf.V3(delta_q.x, delta_q.y, delta_q.z) # Use small angle approximation to obtain a simpler jacobian + else: + state_error_pred[key] = state_t_pred[key] - state_pred[key] + + zero_state_error = {state_error[key]: state_error[key].zero() for key in state_error.keys()} + zero_noise = {noise[key]: noise[key].zero() for key in noise.keys()} # State propagation jacobian - A = VState(state_new.to_storage()).jacobian(state, tangent_space = False) - G = VState(state_new.to_storage()).jacobian(sf.V6.block_matrix([[d_vel], [d_ang]]), tangent_space = False) + A = VTangent(state_error_pred.to_storage()).jacobian(state_error).subs(zero_state_error).subs(zero_noise) + G = VTangent(state_error_pred.to_storage()).jacobian(noise).subs(zero_state_error).subs(zero_noise) # Covariance propagation var_u = sf.Matrix.diag([d_vel_var[0], d_vel_var[1], d_vel_var[2], d_ang_var, d_ang_var, d_ang_var]) @@ -149,8 +198,8 @@ def predict_covariance( # Generate the equations for the upper triangular matrix and the diagonal only # Since the matrix is symmetric, the lower triangle does not need to be derived # and can simply be copied in the implementation - for index in range(state.storage_dim()): - for j in range(state.storage_dim()): + for index in range(state.tangent_dim()): + for j in range(state.tangent_dim()): if index > j: P_new[index,j] = 0 @@ -164,14 +213,14 @@ def compute_airspeed_innov_and_innov_var( epsilon: sf.Scalar ) -> (sf.Scalar, sf.Scalar): - state = State.from_storage(state) + state = vstate_to_state(state) wind = sf.V3(state["wind_vel"][0], state["wind_vel"][1], 0.0) vel_rel = state["vel"] - wind airspeed_pred = vel_rel.norm(epsilon=epsilon) innov = airspeed_pred - airspeed - H = sf.V1(airspeed_pred).jacobian(state, tangent_space=False) + H = sf.V1(airspeed_pred).jacobian(state) innov_var = (H * P * H.T + R)[0,0] return (innov, innov_var) @@ -183,11 +232,11 @@ def compute_airspeed_h_and_k( epsilon: sf.Scalar ) -> (VTangent, VTangent): - state = State.from_storage(state) + state = vstate_to_state(state) wind = sf.V3(state["wind_vel"][0], state["wind_vel"][1], 0.0) vel_rel = state["vel"] - wind airspeed_pred = vel_rel.norm(epsilon=epsilon) - H = sf.V1(airspeed_pred).jacobian(state, tangent_space=False) + H = sf.V1(airspeed_pred).jacobian(state) K = P * H.T / sf.Max(innov_var, epsilon) @@ -229,7 +278,7 @@ def predict_sideslip( wind = sf.V3(state["wind_vel"][0], state["wind_vel"][1], 0.0) vel_rel = state["vel"] - wind - relative_wind_body = state_to_rot3(state).inverse() * vel_rel + relative_wind_body = state["quat_nominal"].inverse() * vel_rel # Small angle approximation of side slip model # Protect division by zero using epsilon @@ -244,12 +293,12 @@ def compute_sideslip_innov_and_innov_var( epsilon: sf.Scalar ) -> (sf.Scalar, sf.Scalar, sf.Scalar): - state = State.from_storage(state) + state = vstate_to_state(state) sideslip_pred = predict_sideslip(state, epsilon); innov = sideslip_pred - 0.0 - H = sf.V1(sideslip_pred).jacobian(state, tangent_space=False) + H = sf.V1(sideslip_pred).jacobian(state) innov_var = (H * P * H.T + R)[0,0] return (innov, innov_var) @@ -261,10 +310,10 @@ def compute_sideslip_h_and_k( epsilon: sf.Scalar ) -> (VTangent, VTangent): - state = State.from_storage(state) + state = vstate_to_state(state) sideslip_pred = predict_sideslip(state, epsilon); - H = sf.V1(sideslip_pred).jacobian(state, tangent_space=False) + H = sf.V1(sideslip_pred).jacobian(state) K = P * H.T / sf.Max(innov_var, epsilon) @@ -274,7 +323,7 @@ def predict_mag_body(state) -> sf.V3: mag_field_earth = state["mag_I"] mag_bias_body = state["mag_B"] - mag_body = state_to_rot3(state).inverse() * mag_field_earth + mag_bias_body + mag_body = state["quat_nominal"].inverse() * mag_field_earth + mag_bias_body return mag_body def compute_mag_innov_innov_var_and_hx( @@ -285,17 +334,17 @@ def compute_mag_innov_innov_var_and_hx( epsilon: sf.Scalar ) -> (sf.V3, sf.V3, VTangent): - state = State.from_storage(state) + state = vstate_to_state(state) meas_pred = predict_mag_body(state); innov = meas_pred - meas innov_var = sf.V3() - Hx = sf.V1(meas_pred[0]).jacobian(state, tangent_space=False) + Hx = sf.V1(meas_pred[0]).jacobian(state) innov_var[0] = (Hx * P * Hx.T + R)[0,0] - Hy = sf.V1(meas_pred[1]).jacobian(state, tangent_space=False) + Hy = sf.V1(meas_pred[1]).jacobian(state) innov_var[1] = (Hy * P * Hy.T + R)[0,0] - Hz = sf.V1(meas_pred[2]).jacobian(state, tangent_space=False) + Hz = sf.V1(meas_pred[2]).jacobian(state) innov_var[2] = (Hz * P * Hz.T + R)[0,0] return (innov, innov_var, Hx.T) @@ -307,10 +356,10 @@ def compute_mag_y_innov_var_and_h( epsilon: sf.Scalar ) -> (sf.Scalar, VTangent): - state = State.from_storage(state) + state = vstate_to_state(state) meas_pred = predict_mag_body(state); - H = sf.V1(meas_pred[1]).jacobian(state, tangent_space=False) + H = sf.V1(meas_pred[1]).jacobian(state) innov_var = (H * P * H.T + R)[0,0] return (innov_var, H.T) @@ -322,10 +371,10 @@ def compute_mag_z_innov_var_and_h( epsilon: sf.Scalar ) -> (sf.Scalar, VTangent): - state = State.from_storage(state) + state = vstate_to_state(state) meas_pred = predict_mag_body(state); - H = sf.V1(meas_pred[2]).jacobian(state, tangent_space=False) + H = sf.V1(meas_pred[2]).jacobian(state) innov_var = (H * P * H.T + R)[0,0] return (innov_var, H.T) @@ -337,12 +386,12 @@ def compute_yaw_321_innov_var_and_h( epsilon: sf.Scalar ) -> (sf.Scalar, VTangent): - state = State.from_storage(state) - R_to_earth = state_to_rot3(state).to_rotation_matrix() + state = vstate_to_state(state) + R_to_earth = state["quat_nominal"].to_rotation_matrix() # Fix the singularity at pi/2 by inserting epsilon meas_pred = sf.atan2(R_to_earth[1,0], R_to_earth[0,0], epsilon=epsilon) - H = sf.V1(meas_pred).jacobian(state, tangent_space=False) + H = sf.V1(meas_pred).jacobian(state) innov_var = (H * P * H.T + R)[0,0] return (innov_var, H.T) @@ -354,12 +403,12 @@ def compute_yaw_321_innov_var_and_h_alternate( epsilon: sf.Scalar ) -> (sf.Scalar, VTangent): - state = State.from_storage(state) - R_to_earth = state_to_rot3(state).to_rotation_matrix() + state = vstate_to_state(state) + R_to_earth = state["quat_nominal"].to_rotation_matrix() # Alternate form that has a singularity at yaw 0 instead of pi/2 meas_pred = sf.pi/2 - sf.atan2(R_to_earth[0,0], R_to_earth[1,0], epsilon=epsilon) - H = sf.V1(meas_pred).jacobian(state, tangent_space=False) + H = sf.V1(meas_pred).jacobian(state) innov_var = (H * P * H.T + R)[0,0] return (innov_var, H.T) @@ -371,12 +420,12 @@ def compute_yaw_312_innov_var_and_h( epsilon: sf.Scalar ) -> (sf.Scalar, VTangent): - state = State.from_storage(state) - R_to_earth = state_to_rot3(state).to_rotation_matrix() + state = vstate_to_state(state) + R_to_earth = state["quat_nominal"].to_rotation_matrix() # Alternate form to be used when close to pitch +-pi/2 meas_pred = sf.atan2(-R_to_earth[0,1], R_to_earth[1,1], epsilon=epsilon) - H = sf.V1(meas_pred).jacobian(state, tangent_space=False) + H = sf.V1(meas_pred).jacobian(state) innov_var = (H * P * H.T + R)[0,0] return (innov_var, H.T) @@ -388,12 +437,12 @@ def compute_yaw_312_innov_var_and_h_alternate( epsilon: sf.Scalar ) -> (sf.Scalar, VTangent): - state = State.from_storage(state) - R_to_earth = state_to_rot3(state).to_rotation_matrix() + state = vstate_to_state(state) + R_to_earth = state["quat_nominal"].to_rotation_matrix() # Alternate form to be used when close to pitch +-pi/2 meas_pred = sf.pi/2 - sf.atan2(-R_to_earth[1,1], R_to_earth[0,1], epsilon=epsilon) - H = sf.V1(meas_pred).jacobian(state, tangent_space=False) + H = sf.V1(meas_pred).jacobian(state) innov_var = (H * P * H.T + R)[0,0] return (innov_var, H.T) @@ -405,16 +454,16 @@ def compute_mag_declination_pred_innov_var_and_h( epsilon: sf.Scalar ) -> (sf.Scalar, sf.Scalar, VTangent): - state = State.from_storage(state) + state = vstate_to_state(state) meas_pred = sf.atan2(state["mag_I"][1], state["mag_I"][0], epsilon=epsilon) - H = sf.V1(meas_pred).jacobian(state, tangent_space=False) + H = sf.V1(meas_pred).jacobian(state) innov_var = (H * P * H.T + R)[0,0] return (meas_pred, innov_var, H.T) def predict_opt_flow(state, distance, epsilon): - R_to_body = state_to_rot3(state).inverse() + R_to_body = state["quat_nominal"].inverse() # Calculate earth relative velocity in a non-rotating sensor frame rel_vel_sensor = R_to_body * state["vel"] @@ -436,13 +485,13 @@ def compute_flow_xy_innov_var_and_hx( R: sf.Scalar, epsilon: sf.Scalar ) -> (sf.V2, VTangent): - state = State.from_storage(state) + state = vstate_to_state(state) meas_pred = predict_opt_flow(state, distance, epsilon); innov_var = sf.V2() - Hx = sf.V1(meas_pred[0]).jacobian(state, tangent_space=False) + Hx = sf.V1(meas_pred[0]).jacobian(state) innov_var[0] = (Hx * P * Hx.T + R)[0,0] - Hy = sf.V1(meas_pred[1]).jacobian(state, tangent_space=False) + Hy = sf.V1(meas_pred[1]).jacobian(state) innov_var[1] = (Hy * P * Hy.T + R)[0,0] return (innov_var, Hx.T) @@ -454,10 +503,10 @@ def compute_flow_y_innov_var_and_h( R: sf.Scalar, epsilon: sf.Scalar ) -> (sf.Scalar, VTangent): - state = State.from_storage(state) + state = vstate_to_state(state) meas_pred = predict_opt_flow(state, distance, epsilon); - Hy = sf.V1(meas_pred[1]).jacobian(state, tangent_space=False) + Hy = sf.V1(meas_pred[1]).jacobian(state) innov_var = (Hy * P * Hy.T + R)[0,0] return (innov_var, Hy.T) @@ -470,8 +519,8 @@ def compute_gnss_yaw_pred_innov_var_and_h( epsilon: sf.Scalar ) -> (sf.Scalar, sf.Scalar, VTangent): - state = State.from_storage(state) - R_to_earth = state_to_rot3(state) + state = vstate_to_state(state) + R_to_earth = state["quat_nominal"] # define antenna vector in body frame ant_vec_bf = sf.V3(sf.cos(antenna_yaw_offset), sf.sin(antenna_yaw_offset), 0) @@ -482,7 +531,7 @@ def compute_gnss_yaw_pred_innov_var_and_h( # Calculate the yaw angle from the projection meas_pred = sf.atan2(ant_vec_ef[1], ant_vec_ef[0], epsilon=epsilon) - H = sf.V1(meas_pred).jacobian(state, tangent_space=False) + H = sf.V1(meas_pred).jacobian(state) innov_var = (H * P * H.T + R)[0,0] return (meas_pred, innov_var, H.T) @@ -494,7 +543,7 @@ def predict_drag( cm: sf.Scalar, epsilon: sf.Scalar ) -> (sf.Scalar): - R_to_body = state_to_rot3(state).inverse() + R_to_body = state["quat_nominal"].inverse() wind = sf.V3(state["wind_vel"][0], state["wind_vel"][1], 0.0) vel_rel = state["vel"] - wind @@ -517,9 +566,9 @@ def compute_drag_x_innov_var_and_k( epsilon: sf.Scalar ) -> (sf.Scalar, VTangent): - state = State.from_storage(state) + state = vstate_to_state(state) meas_pred = predict_drag(state, rho, cd, cm, epsilon) - Hx = sf.V1(meas_pred[0]).jacobian(state, tangent_space=False) + Hx = sf.V1(meas_pred[0]).jacobian(state) innov_var = (Hx * P * Hx.T + R)[0,0] Ktotal = P * Hx.T / sf.Max(innov_var, epsilon) K = VTangent() @@ -537,9 +586,9 @@ def compute_drag_y_innov_var_and_k( epsilon: sf.Scalar ) -> (sf.Scalar, VTangent): - state = State.from_storage(state) + state = vstate_to_state(state) meas_pred = predict_drag(state, rho, cd, cm, epsilon) - Hy = sf.V1(meas_pred[1]).jacobian(state, tangent_space=False) + Hy = sf.V1(meas_pred[1]).jacobian(state) innov_var = (Hy * P * Hy.T + R)[0,0] Ktotal = P * Hy.T / sf.Max(innov_var, epsilon) K = VTangent() @@ -555,9 +604,9 @@ def compute_gravity_innov_var_and_k_and_h( epsilon: sf.Scalar ) -> (sf.V3, sf.V3, VTangent, VTangent, VTangent): - state = State.from_storage(state) + state = vstate_to_state(state) # get transform from earth to body frame - R_to_body = state_to_rot3(state).inverse() + R_to_body = state["quat_nominal"].inverse() # the innovation is the error between measured acceleration # and predicted (body frame), assuming no body acceleration @@ -571,46 +620,12 @@ def compute_gravity_innov_var_and_k_and_h( # calculate observation jacobian (H), kalman gain (K), and innovation variance (S) # for each axis for i in range(3): - H = sf.V1(meas_pred[i]).jacobian(state, tangent_space=False) + H = sf.V1(meas_pred[i]).jacobian(state) innov_var[i] = (H * P * H.T + R)[0,0] K[i] = P * H.T / innov_var[i] return (innov, innov_var, K[0], K[1], K[2]) -def quat_var_to_rot_var( - state: VState, - P: MTangent, - epsilon: sf.Scalar -) -> sf.V3: - state = State.from_storage(state) - J = sf.V3(state_to_rot3(state).to_tangent(epsilon=epsilon)).jacobian(state, tangent_space=False) - rot_cov = J * P * J.T - return sf.V3(rot_cov[0, 0], rot_cov[1, 1], rot_cov[2, 2]) - -def rot_var_ned_to_lower_triangular_quat_cov( - state: VState, - rot_var_ned: sf.V3 -) -> sf.M44: - # This function converts an attitude variance defined by a 3D vector in NED frame - # into a 4x4 covariance matrix representing the uncertainty on each of the 4 quaternion parameters - # Note: the resulting quaternion uncertainty is defined as a perturbation - # at the tip of the quaternion (i.e.:body-frame uncertainty) - state = State.from_storage(state) - q = state["quat_nominal"] - attitude = state_to_rot3(state) - J = q.jacobian(attitude) - - # Convert uncertainties from NED to body frame - rot_cov_ned = sf.M33.diag(rot_var_ned) - adjoint = attitude.to_rotation_matrix() # the adjoint of SO(3) is simply the rotation matrix itself - rot_cov_body = adjoint.T * rot_cov_ned * adjoint - - # Convert yaw (body) to quaternion parameter uncertainty - q_var = J * rot_cov_body * J.T - - # Generate lower trangle only and copy it to the upper part in implementation (produces less code) - return q_var.lower_triangle() - print("Derive EKF2 equations...") generate_px4_function(predict_covariance, output_names=None) @@ -638,7 +653,4 @@ def rot_var_ned_to_lower_triangular_quat_cov( generate_px4_function(compute_gnss_yaw_pred_innov_var_and_h, output_names=["meas_pred", "innov_var", "H"]) generate_px4_function(compute_gravity_innov_var_and_k_and_h, output_names=["innov", "innov_var", "Kx", "Ky", "Kz"]) -generate_px4_function(quat_var_to_rot_var, output_names=["rot_var"]) -generate_px4_function(rot_var_ned_to_lower_triangular_quat_cov, output_names=["q_cov_lower_triangle"]) - generate_px4_state(State, tangent_idx) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/derivation_utils.py b/src/modules/ekf2/EKF/python/ekf_derivation/derivation_utils.py index bd91c3ba614c..b08ade69a47c 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/derivation_utils.py +++ b/src/modules/ekf2/EKF/python/ekf_derivation/derivation_utils.py @@ -104,7 +104,7 @@ def TypeFromLength(len): raise NotImplementedError for key, val in state.items(): - out += f"\t{TypeFromLength(len(val))} {key}{{}};\n" + out += f"\t{TypeFromLength(val.storage_dim())} {key}{{}};\n" state_size = state.storage_dim() out += f"\n\tmatrix::Vector<{T}, {state_size}> Data() const {{\n" \ diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_airspeed_h_and_k.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_airspeed_h_and_k.h index 661c1f16eab8..cc2c18cd6394 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_airspeed_h_and_k.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_airspeed_h_and_k.h @@ -17,20 +17,20 @@ namespace sym { * * Args: * state: Matrix24_1 - * P: Matrix24_24 + * P: Matrix23_23 * innov_var: Scalar * epsilon: Scalar * * Outputs: - * H: Matrix24_1 - * K: Matrix24_1 + * H: Matrix23_1 + * K: Matrix23_1 */ template void ComputeAirspeedHAndK(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar innov_var, - const Scalar epsilon, matrix::Matrix* const H = nullptr, - matrix::Matrix* const K = nullptr) { - // Total ops: 256 + const matrix::Matrix& P, const Scalar innov_var, + const Scalar epsilon, matrix::Matrix* const H = nullptr, + matrix::Matrix* const K = nullptr) { + // Total ops: 246 // Input arrays @@ -47,68 +47,66 @@ void ComputeAirspeedHAndK(const matrix::Matrix& state, // Output terms (2) if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); - _h(4, 0) = _tmp3; - _h(5, 0) = _tmp4; - _h(6, 0) = _tmp5; - _h(22, 0) = -_tmp3; - _h(23, 0) = -_tmp4; + _h(3, 0) = _tmp3; + _h(4, 0) = _tmp4; + _h(5, 0) = _tmp5; + _h(21, 0) = -_tmp3; + _h(22, 0) = -_tmp4; } if (K != nullptr) { - matrix::Matrix& _k = (*K); + matrix::Matrix& _k = (*K); - _k(0, 0) = _tmp6 * (-P(0, 22) * _tmp3 - P(0, 23) * _tmp4 + P(0, 4) * _tmp3 + P(0, 5) * _tmp4 + - P(0, 6) * _tmp5); - _k(1, 0) = _tmp6 * (-P(1, 22) * _tmp3 - P(1, 23) * _tmp4 + P(1, 4) * _tmp3 + P(1, 5) * _tmp4 + - P(1, 6) * _tmp5); - _k(2, 0) = _tmp6 * (-P(2, 22) * _tmp3 - P(2, 23) * _tmp4 + P(2, 4) * _tmp3 + P(2, 5) * _tmp4 + - P(2, 6) * _tmp5); - _k(3, 0) = _tmp6 * (-P(3, 22) * _tmp3 - P(3, 23) * _tmp4 + P(3, 4) * _tmp3 + P(3, 5) * _tmp4 + - P(3, 6) * _tmp5); - _k(4, 0) = _tmp6 * (-P(4, 22) * _tmp3 - P(4, 23) * _tmp4 + P(4, 4) * _tmp3 + P(4, 5) * _tmp4 + - P(4, 6) * _tmp5); - _k(5, 0) = _tmp6 * (-P(5, 22) * _tmp3 - P(5, 23) * _tmp4 + P(5, 4) * _tmp3 + P(5, 5) * _tmp4 + - P(5, 6) * _tmp5); - _k(6, 0) = _tmp6 * (-P(6, 22) * _tmp3 - P(6, 23) * _tmp4 + P(6, 4) * _tmp3 + P(6, 5) * _tmp4 + - P(6, 6) * _tmp5); - _k(7, 0) = _tmp6 * (-P(7, 22) * _tmp3 - P(7, 23) * _tmp4 + P(7, 4) * _tmp3 + P(7, 5) * _tmp4 + - P(7, 6) * _tmp5); - _k(8, 0) = _tmp6 * (-P(8, 22) * _tmp3 - P(8, 23) * _tmp4 + P(8, 4) * _tmp3 + P(8, 5) * _tmp4 + - P(8, 6) * _tmp5); - _k(9, 0) = _tmp6 * (-P(9, 22) * _tmp3 - P(9, 23) * _tmp4 + P(9, 4) * _tmp3 + P(9, 5) * _tmp4 + - P(9, 6) * _tmp5); - _k(10, 0) = _tmp6 * (-P(10, 22) * _tmp3 - P(10, 23) * _tmp4 + P(10, 4) * _tmp3 + - P(10, 5) * _tmp4 + P(10, 6) * _tmp5); - _k(11, 0) = _tmp6 * (-P(11, 22) * _tmp3 - P(11, 23) * _tmp4 + P(11, 4) * _tmp3 + - P(11, 5) * _tmp4 + P(11, 6) * _tmp5); - _k(12, 0) = _tmp6 * (-P(12, 22) * _tmp3 - P(12, 23) * _tmp4 + P(12, 4) * _tmp3 + - P(12, 5) * _tmp4 + P(12, 6) * _tmp5); - _k(13, 0) = _tmp6 * (-P(13, 22) * _tmp3 - P(13, 23) * _tmp4 + P(13, 4) * _tmp3 + - P(13, 5) * _tmp4 + P(13, 6) * _tmp5); - _k(14, 0) = _tmp6 * (-P(14, 22) * _tmp3 - P(14, 23) * _tmp4 + P(14, 4) * _tmp3 + - P(14, 5) * _tmp4 + P(14, 6) * _tmp5); - _k(15, 0) = _tmp6 * (-P(15, 22) * _tmp3 - P(15, 23) * _tmp4 + P(15, 4) * _tmp3 + - P(15, 5) * _tmp4 + P(15, 6) * _tmp5); - _k(16, 0) = _tmp6 * (-P(16, 22) * _tmp3 - P(16, 23) * _tmp4 + P(16, 4) * _tmp3 + - P(16, 5) * _tmp4 + P(16, 6) * _tmp5); - _k(17, 0) = _tmp6 * (-P(17, 22) * _tmp3 - P(17, 23) * _tmp4 + P(17, 4) * _tmp3 + - P(17, 5) * _tmp4 + P(17, 6) * _tmp5); - _k(18, 0) = _tmp6 * (-P(18, 22) * _tmp3 - P(18, 23) * _tmp4 + P(18, 4) * _tmp3 + - P(18, 5) * _tmp4 + P(18, 6) * _tmp5); - _k(19, 0) = _tmp6 * (-P(19, 22) * _tmp3 - P(19, 23) * _tmp4 + P(19, 4) * _tmp3 + - P(19, 5) * _tmp4 + P(19, 6) * _tmp5); - _k(20, 0) = _tmp6 * (-P(20, 22) * _tmp3 - P(20, 23) * _tmp4 + P(20, 4) * _tmp3 + - P(20, 5) * _tmp4 + P(20, 6) * _tmp5); - _k(21, 0) = _tmp6 * (-P(21, 22) * _tmp3 - P(21, 23) * _tmp4 + P(21, 4) * _tmp3 + - P(21, 5) * _tmp4 + P(21, 6) * _tmp5); - _k(22, 0) = _tmp6 * (-P(22, 22) * _tmp3 - P(22, 23) * _tmp4 + P(22, 4) * _tmp3 + - P(22, 5) * _tmp4 + P(22, 6) * _tmp5); - _k(23, 0) = _tmp6 * (-P(23, 22) * _tmp3 - P(23, 23) * _tmp4 + P(23, 4) * _tmp3 + - P(23, 5) * _tmp4 + P(23, 6) * _tmp5); + _k(0, 0) = _tmp6 * (-P(0, 21) * _tmp3 - P(0, 22) * _tmp4 + P(0, 3) * _tmp3 + P(0, 4) * _tmp4 + + P(0, 5) * _tmp5); + _k(1, 0) = _tmp6 * (-P(1, 21) * _tmp3 - P(1, 22) * _tmp4 + P(1, 3) * _tmp3 + P(1, 4) * _tmp4 + + P(1, 5) * _tmp5); + _k(2, 0) = _tmp6 * (-P(2, 21) * _tmp3 - P(2, 22) * _tmp4 + P(2, 3) * _tmp3 + P(2, 4) * _tmp4 + + P(2, 5) * _tmp5); + _k(3, 0) = _tmp6 * (-P(3, 21) * _tmp3 - P(3, 22) * _tmp4 + P(3, 3) * _tmp3 + P(3, 4) * _tmp4 + + P(3, 5) * _tmp5); + _k(4, 0) = _tmp6 * (-P(4, 21) * _tmp3 - P(4, 22) * _tmp4 + P(4, 3) * _tmp3 + P(4, 4) * _tmp4 + + P(4, 5) * _tmp5); + _k(5, 0) = _tmp6 * (-P(5, 21) * _tmp3 - P(5, 22) * _tmp4 + P(5, 3) * _tmp3 + P(5, 4) * _tmp4 + + P(5, 5) * _tmp5); + _k(6, 0) = _tmp6 * (-P(6, 21) * _tmp3 - P(6, 22) * _tmp4 + P(6, 3) * _tmp3 + P(6, 4) * _tmp4 + + P(6, 5) * _tmp5); + _k(7, 0) = _tmp6 * (-P(7, 21) * _tmp3 - P(7, 22) * _tmp4 + P(7, 3) * _tmp3 + P(7, 4) * _tmp4 + + P(7, 5) * _tmp5); + _k(8, 0) = _tmp6 * (-P(8, 21) * _tmp3 - P(8, 22) * _tmp4 + P(8, 3) * _tmp3 + P(8, 4) * _tmp4 + + P(8, 5) * _tmp5); + _k(9, 0) = _tmp6 * (-P(9, 21) * _tmp3 - P(9, 22) * _tmp4 + P(9, 3) * _tmp3 + P(9, 4) * _tmp4 + + P(9, 5) * _tmp5); + _k(10, 0) = _tmp6 * (-P(10, 21) * _tmp3 - P(10, 22) * _tmp4 + P(10, 3) * _tmp3 + + P(10, 4) * _tmp4 + P(10, 5) * _tmp5); + _k(11, 0) = _tmp6 * (-P(11, 21) * _tmp3 - P(11, 22) * _tmp4 + P(11, 3) * _tmp3 + + P(11, 4) * _tmp4 + P(11, 5) * _tmp5); + _k(12, 0) = _tmp6 * (-P(12, 21) * _tmp3 - P(12, 22) * _tmp4 + P(12, 3) * _tmp3 + + P(12, 4) * _tmp4 + P(12, 5) * _tmp5); + _k(13, 0) = _tmp6 * (-P(13, 21) * _tmp3 - P(13, 22) * _tmp4 + P(13, 3) * _tmp3 + + P(13, 4) * _tmp4 + P(13, 5) * _tmp5); + _k(14, 0) = _tmp6 * (-P(14, 21) * _tmp3 - P(14, 22) * _tmp4 + P(14, 3) * _tmp3 + + P(14, 4) * _tmp4 + P(14, 5) * _tmp5); + _k(15, 0) = _tmp6 * (-P(15, 21) * _tmp3 - P(15, 22) * _tmp4 + P(15, 3) * _tmp3 + + P(15, 4) * _tmp4 + P(15, 5) * _tmp5); + _k(16, 0) = _tmp6 * (-P(16, 21) * _tmp3 - P(16, 22) * _tmp4 + P(16, 3) * _tmp3 + + P(16, 4) * _tmp4 + P(16, 5) * _tmp5); + _k(17, 0) = _tmp6 * (-P(17, 21) * _tmp3 - P(17, 22) * _tmp4 + P(17, 3) * _tmp3 + + P(17, 4) * _tmp4 + P(17, 5) * _tmp5); + _k(18, 0) = _tmp6 * (-P(18, 21) * _tmp3 - P(18, 22) * _tmp4 + P(18, 3) * _tmp3 + + P(18, 4) * _tmp4 + P(18, 5) * _tmp5); + _k(19, 0) = _tmp6 * (-P(19, 21) * _tmp3 - P(19, 22) * _tmp4 + P(19, 3) * _tmp3 + + P(19, 4) * _tmp4 + P(19, 5) * _tmp5); + _k(20, 0) = _tmp6 * (-P(20, 21) * _tmp3 - P(20, 22) * _tmp4 + P(20, 3) * _tmp3 + + P(20, 4) * _tmp4 + P(20, 5) * _tmp5); + _k(21, 0) = _tmp6 * (-P(21, 21) * _tmp3 - P(21, 22) * _tmp4 + P(21, 3) * _tmp3 + + P(21, 4) * _tmp4 + P(21, 5) * _tmp5); + _k(22, 0) = _tmp6 * (-P(22, 21) * _tmp3 - P(22, 22) * _tmp4 + P(22, 3) * _tmp3 + + P(22, 4) * _tmp4 + P(22, 5) * _tmp5); } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_airspeed_innov_and_innov_var.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_airspeed_innov_and_innov_var.h index 02546feaddaa..34c059b56208 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_airspeed_innov_and_innov_var.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_airspeed_innov_and_innov_var.h @@ -17,7 +17,7 @@ namespace sym { * * Args: * state: Matrix24_1 - * P: Matrix24_24 + * P: Matrix23_23 * airspeed: Scalar * R: Scalar * epsilon: Scalar @@ -28,7 +28,7 @@ namespace sym { */ template void ComputeAirspeedInnovAndInnovVar(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar airspeed, + const matrix::Matrix& P, const Scalar airspeed, const Scalar R, const Scalar epsilon, Scalar* const innov = nullptr, Scalar* const innov_var = nullptr) { @@ -57,16 +57,16 @@ void ComputeAirspeedInnovAndInnovVar(const matrix::Matrix& state, Scalar& _innov_var = (*innov_var); _innov_var = R + - _tmp4 * (-P(22, 6) * _tmp5 - P(23, 6) * _tmp6 + P(4, 6) * _tmp5 + P(5, 6) * _tmp6 + - P(6, 6) * _tmp4) - - _tmp5 * (-P(22, 22) * _tmp5 - P(23, 22) * _tmp6 + P(4, 22) * _tmp5 + - P(5, 22) * _tmp6 + P(6, 22) * _tmp4) + - _tmp5 * (-P(22, 4) * _tmp5 - P(23, 4) * _tmp6 + P(4, 4) * _tmp5 + P(5, 4) * _tmp6 + - P(6, 4) * _tmp4) - - _tmp6 * (-P(22, 23) * _tmp5 - P(23, 23) * _tmp6 + P(4, 23) * _tmp5 + - P(5, 23) * _tmp6 + P(6, 23) * _tmp4) + - _tmp6 * (-P(22, 5) * _tmp5 - P(23, 5) * _tmp6 + P(4, 5) * _tmp5 + P(5, 5) * _tmp6 + - P(6, 5) * _tmp4); + _tmp4 * (-P(21, 5) * _tmp5 - P(22, 5) * _tmp6 + P(3, 5) * _tmp5 + P(4, 5) * _tmp6 + + P(5, 5) * _tmp4) - + _tmp5 * (-P(21, 21) * _tmp5 - P(22, 21) * _tmp6 + P(3, 21) * _tmp5 + + P(4, 21) * _tmp6 + P(5, 21) * _tmp4) + + _tmp5 * (-P(21, 3) * _tmp5 - P(22, 3) * _tmp6 + P(3, 3) * _tmp5 + P(4, 3) * _tmp6 + + P(5, 3) * _tmp4) - + _tmp6 * (-P(21, 22) * _tmp5 - P(22, 22) * _tmp6 + P(3, 22) * _tmp5 + + P(4, 22) * _tmp6 + P(5, 22) * _tmp4) + + _tmp6 * (-P(21, 4) * _tmp5 - P(22, 4) * _tmp6 + P(3, 4) * _tmp5 + P(4, 4) * _tmp6 + + P(5, 4) * _tmp4); } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_x_innov_var_and_k.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_x_innov_var_and_k.h index 8d1296a91bb3..12c10a917f52 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_x_innov_var_and_k.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_x_innov_var_and_k.h @@ -17,7 +17,7 @@ namespace sym { * * Args: * state: Matrix24_1 - * P: Matrix24_24 + * P: Matrix23_23 * rho: Scalar * cd: Scalar * cm: Scalar @@ -26,134 +26,123 @@ namespace sym { * * Outputs: * innov_var: Scalar - * K: Matrix24_1 + * K: Matrix23_1 */ template void ComputeDragXInnovVarAndK(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar rho, + const matrix::Matrix& P, const Scalar rho, const Scalar cd, const Scalar cm, const Scalar R, const Scalar epsilon, Scalar* const innov_var = nullptr, - matrix::Matrix* const K = nullptr) { - // Total ops: 398 + matrix::Matrix* const K = nullptr) { + // Total ops: 348 // Input arrays // Intermediate terms (77) - const Scalar _tmp0 = -state(22, 0) + state(4, 0); - const Scalar _tmp1 = 4 * _tmp0; - const Scalar _tmp2 = -state(23, 0) + state(5, 0); - const Scalar _tmp3 = 2 * state(0, 0); - const Scalar _tmp4 = _tmp2 * _tmp3; - const Scalar _tmp5 = 2 * state(6, 0); - const Scalar _tmp6 = _tmp5 * state(1, 0); - const Scalar _tmp7 = -_tmp1 * state(3, 0) + _tmp4 + _tmp6; - const Scalar _tmp8 = 2 * state(2, 0); - const Scalar _tmp9 = _tmp2 * _tmp8; - const Scalar _tmp10 = 2 * state(1, 0); - const Scalar _tmp11 = _tmp0 * _tmp10; - const Scalar _tmp12 = _tmp8 * state(3, 0); - const Scalar _tmp13 = _tmp3 * state(1, 0); - const Scalar _tmp14 = _tmp12 - _tmp13; - const Scalar _tmp15 = _tmp8 * state(0, 0); - const Scalar _tmp16 = _tmp10 * state(3, 0); - const Scalar _tmp17 = _tmp15 + _tmp16; - const Scalar _tmp18 = -2 * std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp19 = 1 - 2 * std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp20 = _tmp18 + _tmp19; - const Scalar _tmp21 = _tmp0 * _tmp17 + _tmp14 * _tmp2 + _tmp20 * state(6, 0); - const Scalar _tmp22 = 2 * _tmp21; - const Scalar _tmp23 = _tmp0 * _tmp3; - const Scalar _tmp24 = 4 * _tmp2; - const Scalar _tmp25 = _tmp8 * state(6, 0); - const Scalar _tmp26 = -2 * std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp27 = _tmp19 + _tmp26; - const Scalar _tmp28 = _tmp3 * state(3, 0); - const Scalar _tmp29 = _tmp8 * state(1, 0); - const Scalar _tmp30 = -_tmp28 + _tmp29; - const Scalar _tmp31 = _tmp12 + _tmp13; - const Scalar _tmp32 = _tmp0 * _tmp30 + _tmp2 * _tmp27 + _tmp31 * state(6, 0); - const Scalar _tmp33 = 2 * _tmp32; - const Scalar _tmp34 = _tmp18 + _tmp26 + 1; - const Scalar _tmp35 = _tmp28 + _tmp29; - const Scalar _tmp36 = -_tmp15 + _tmp16; - const Scalar _tmp37 = _tmp0 * _tmp34 + _tmp2 * _tmp35 + _tmp36 * state(6, 0); - const Scalar _tmp38 = 2 * _tmp37; - const Scalar _tmp39 = std::sqrt(Scalar(std::pow(_tmp21, Scalar(2)) + std::pow(_tmp32, Scalar(2)) + - std::pow(_tmp37, Scalar(2)) + epsilon)); - const Scalar _tmp40 = cd * rho; - const Scalar _tmp41 = Scalar(0.25) * _tmp37 * _tmp40 / _tmp39; - const Scalar _tmp42 = Scalar(0.5) * _tmp39 * _tmp40; - const Scalar _tmp43 = - -_tmp41 * (_tmp22 * (_tmp11 + _tmp9) + _tmp33 * (-_tmp23 - _tmp24 * state(3, 0) + _tmp25) + - _tmp38 * _tmp7) - - _tmp42 * _tmp7 - _tmp7 * cm; - const Scalar _tmp44 = _tmp35 * cm; - const Scalar _tmp45 = _tmp35 * _tmp38; - const Scalar _tmp46 = _tmp14 * _tmp22; - const Scalar _tmp47 = _tmp27 * _tmp33; - const Scalar _tmp48 = _tmp35 * _tmp42; - const Scalar _tmp49 = -_tmp41 * (-_tmp45 - _tmp46 - _tmp47) + _tmp44 + _tmp48; - const Scalar _tmp50 = -_tmp41 * (_tmp45 + _tmp46 + _tmp47) - _tmp44 - _tmp48; - const Scalar _tmp51 = _tmp5 * state(3, 0); - const Scalar _tmp52 = _tmp51 + _tmp9; - const Scalar _tmp53 = 2 * state(3, 0); - const Scalar _tmp54 = _tmp0 * _tmp53; - const Scalar _tmp55 = 4 * state(6, 0); - const Scalar _tmp56 = _tmp0 * _tmp8; - const Scalar _tmp57 = _tmp3 * state(6, 0); - const Scalar _tmp58 = - -_tmp41 * (_tmp22 * (-_tmp4 + _tmp54 - _tmp55 * state(1, 0)) + - _tmp33 * (-_tmp24 * state(1, 0) + _tmp56 + _tmp57) + _tmp38 * _tmp52) - - _tmp42 * _tmp52 - _tmp52 * cm; - const Scalar _tmp59 = _tmp10 * _tmp2; - const Scalar _tmp60 = -_tmp1 * state(2, 0) - _tmp57 + _tmp59; - const Scalar _tmp61 = _tmp2 * _tmp53; - const Scalar _tmp62 = -_tmp41 * (_tmp22 * (_tmp23 - _tmp55 * state(2, 0) + _tmp61) + - _tmp33 * (_tmp11 + _tmp51) + _tmp38 * _tmp60) - - _tmp42 * _tmp60 - _tmp60 * cm; - const Scalar _tmp63 = _tmp34 * cm; - const Scalar _tmp64 = _tmp34 * _tmp38; - const Scalar _tmp65 = _tmp17 * _tmp22; - const Scalar _tmp66 = _tmp30 * _tmp33; - const Scalar _tmp67 = _tmp34 * _tmp42; - const Scalar _tmp68 = -_tmp41 * (-_tmp64 - _tmp65 - _tmp66) + _tmp63 + _tmp67; - const Scalar _tmp69 = -_tmp25 + _tmp61; + const Scalar _tmp0 = 2 * state(0, 0); + const Scalar _tmp1 = _tmp0 * state(3, 0); + const Scalar _tmp2 = 2 * state(2, 0); + const Scalar _tmp3 = _tmp2 * state(1, 0); + const Scalar _tmp4 = _tmp1 + _tmp3; + const Scalar _tmp5 = _tmp4 * cm; + const Scalar _tmp6 = std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp7 = -2 * _tmp6; + const Scalar _tmp8 = std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp9 = -2 * _tmp8; + const Scalar _tmp10 = _tmp7 + _tmp9 + 1; + const Scalar _tmp11 = -state(22, 0) + state(4, 0); + const Scalar _tmp12 = -state(23, 0) + state(5, 0); + const Scalar _tmp13 = _tmp2 * state(0, 0); + const Scalar _tmp14 = -_tmp13; + const Scalar _tmp15 = 2 * state(1, 0) * state(3, 0); + const Scalar _tmp16 = _tmp14 + _tmp15; + const Scalar _tmp17 = _tmp12 * _tmp4 + _tmp16 * state(6, 0); + const Scalar _tmp18 = _tmp10 * _tmp11 + _tmp17; + const Scalar _tmp19 = 2 * _tmp18; + const Scalar _tmp20 = _tmp19 * _tmp4; + const Scalar _tmp21 = _tmp2 * state(3, 0); + const Scalar _tmp22 = _tmp0 * state(1, 0); + const Scalar _tmp23 = -_tmp22; + const Scalar _tmp24 = _tmp21 + _tmp23; + const Scalar _tmp25 = std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp26 = 1 - 2 * _tmp25; + const Scalar _tmp27 = _tmp26 + _tmp9; + const Scalar _tmp28 = _tmp13 + _tmp15; + const Scalar _tmp29 = _tmp11 * _tmp28 + _tmp12 * _tmp24; + const Scalar _tmp30 = _tmp27 * state(6, 0) + _tmp29; + const Scalar _tmp31 = 2 * _tmp30; + const Scalar _tmp32 = _tmp24 * _tmp31; + const Scalar _tmp33 = _tmp26 + _tmp7; + const Scalar _tmp34 = -_tmp1; + const Scalar _tmp35 = _tmp3 + _tmp34; + const Scalar _tmp36 = _tmp21 + _tmp22; + const Scalar _tmp37 = _tmp11 * _tmp35 + _tmp36 * state(6, 0); + const Scalar _tmp38 = _tmp12 * _tmp33 + _tmp37; + const Scalar _tmp39 = 2 * _tmp38; + const Scalar _tmp40 = _tmp33 * _tmp39; + const Scalar _tmp41 = std::sqrt(Scalar(std::pow(_tmp18, Scalar(2)) + std::pow(_tmp30, Scalar(2)) + + std::pow(_tmp38, Scalar(2)) + epsilon)); + const Scalar _tmp42 = cd * rho; + const Scalar _tmp43 = Scalar(0.25) * _tmp18 * _tmp42 / _tmp41; + const Scalar _tmp44 = Scalar(0.5) * _tmp41 * _tmp42; + const Scalar _tmp45 = _tmp4 * _tmp44; + const Scalar _tmp46 = -_tmp43 * (_tmp20 + _tmp32 + _tmp40) - _tmp45 - _tmp5; + const Scalar _tmp47 = -_tmp25; + const Scalar _tmp48 = _tmp47 + _tmp6; + const Scalar _tmp49 = std::pow(state(0, 0), Scalar(2)); + const Scalar _tmp50 = -_tmp49; + const Scalar _tmp51 = _tmp50 + _tmp8; + const Scalar _tmp52 = -_tmp3; + const Scalar _tmp53 = -_tmp15; + const Scalar _tmp54 = -_tmp6; + const Scalar _tmp55 = _tmp12 * (_tmp47 + _tmp49 + _tmp54 + _tmp8) + _tmp37; + const Scalar _tmp56 = -_tmp43 * (_tmp19 * _tmp55 + _tmp39 * (_tmp11 * (_tmp48 + _tmp51) + + _tmp12 * (_tmp34 + _tmp52) + + state(6, 0) * (_tmp13 + _tmp53))) - + _tmp44 * _tmp55 - _tmp55 * cm; + const Scalar _tmp57 = -_tmp43 * (-_tmp20 - _tmp32 - _tmp40) + _tmp45 + _tmp5; + const Scalar _tmp58 = _tmp10 * cm; + const Scalar _tmp59 = _tmp10 * _tmp19; + const Scalar _tmp60 = _tmp28 * _tmp31; + const Scalar _tmp61 = _tmp35 * _tmp39; + const Scalar _tmp62 = _tmp10 * _tmp44; + const Scalar _tmp63 = -_tmp43 * (-_tmp59 - _tmp60 - _tmp61) + _tmp58 + _tmp62; + const Scalar _tmp64 = -_tmp8; + const Scalar _tmp65 = -_tmp21; + const Scalar _tmp66 = _tmp49 + _tmp64; + const Scalar _tmp67 = + _tmp43 * (_tmp31 * (_tmp11 * (_tmp1 + _tmp52) + _tmp12 * (_tmp25 + _tmp50 + _tmp6 + _tmp64) + + state(6, 0) * (_tmp23 + _tmp65)) + + _tmp39 * (_tmp29 + state(6, 0) * (_tmp48 + _tmp66))); + const Scalar _tmp68 = _tmp25 + _tmp54; + const Scalar _tmp69 = + _tmp11 * (_tmp14 + _tmp53) + _tmp12 * (_tmp22 + _tmp65) + state(6, 0) * (_tmp51 + _tmp68); const Scalar _tmp70 = - -_tmp41 * (_tmp22 * (_tmp56 - _tmp59) + _tmp33 * (-_tmp54 + _tmp6) + _tmp38 * _tmp69) - - _tmp42 * _tmp69 - _tmp69 * cm; - const Scalar _tmp71 = -_tmp41 * (_tmp64 + _tmp65 + _tmp66) - _tmp63 - _tmp67; - const Scalar _tmp72 = -_tmp36 * _tmp42 - _tmp36 * cm - - _tmp41 * (_tmp20 * _tmp22 + _tmp31 * _tmp33 + _tmp36 * _tmp38); - const Scalar _tmp73 = P(23, 23) * _tmp49; - const Scalar _tmp74 = P(22, 22) * _tmp68; - const Scalar _tmp75 = R + - _tmp43 * (P(0, 3) * _tmp70 + P(1, 3) * _tmp58 + P(2, 3) * _tmp62 + - P(22, 3) * _tmp68 + P(23, 3) * _tmp49 + P(3, 3) * _tmp43 + - P(4, 3) * _tmp71 + P(5, 3) * _tmp50 + P(6, 3) * _tmp72) + - _tmp49 * (P(0, 23) * _tmp70 + P(1, 23) * _tmp58 + P(2, 23) * _tmp62 + - P(22, 23) * _tmp68 + P(3, 23) * _tmp43 + P(4, 23) * _tmp71 + - P(5, 23) * _tmp50 + P(6, 23) * _tmp72 + _tmp73) + - _tmp50 * (P(0, 5) * _tmp70 + P(1, 5) * _tmp58 + P(2, 5) * _tmp62 + - P(22, 5) * _tmp68 + P(23, 5) * _tmp49 + P(3, 5) * _tmp43 + - P(4, 5) * _tmp71 + P(5, 5) * _tmp50 + P(6, 5) * _tmp72) + - _tmp58 * (P(0, 1) * _tmp70 + P(1, 1) * _tmp58 + P(2, 1) * _tmp62 + - P(22, 1) * _tmp68 + P(23, 1) * _tmp49 + P(3, 1) * _tmp43 + - P(4, 1) * _tmp71 + P(5, 1) * _tmp50 + P(6, 1) * _tmp72) + - _tmp62 * (P(0, 2) * _tmp70 + P(1, 2) * _tmp58 + P(2, 2) * _tmp62 + - P(22, 2) * _tmp68 + P(23, 2) * _tmp49 + P(3, 2) * _tmp43 + - P(4, 2) * _tmp71 + P(5, 2) * _tmp50 + P(6, 2) * _tmp72) + - _tmp68 * (P(0, 22) * _tmp70 + P(1, 22) * _tmp58 + P(2, 22) * _tmp62 + - P(23, 22) * _tmp49 + P(3, 22) * _tmp43 + P(4, 22) * _tmp71 + - P(5, 22) * _tmp50 + P(6, 22) * _tmp72 + _tmp74) + - _tmp70 * (P(0, 0) * _tmp70 + P(1, 0) * _tmp58 + P(2, 0) * _tmp62 + - P(22, 0) * _tmp68 + P(23, 0) * _tmp49 + P(3, 0) * _tmp43 + - P(4, 0) * _tmp71 + P(5, 0) * _tmp50 + P(6, 0) * _tmp72) + - _tmp71 * (P(0, 4) * _tmp70 + P(1, 4) * _tmp58 + P(2, 4) * _tmp62 + - P(22, 4) * _tmp68 + P(23, 4) * _tmp49 + P(3, 4) * _tmp43 + - P(4, 4) * _tmp71 + P(5, 4) * _tmp50 + P(6, 4) * _tmp72) + - _tmp72 * (P(0, 6) * _tmp70 + P(1, 6) * _tmp58 + P(2, 6) * _tmp62 + - P(22, 6) * _tmp68 + P(23, 6) * _tmp49 + P(3, 6) * _tmp43 + - P(4, 6) * _tmp71 + P(5, 6) * _tmp50 + P(6, 6) * _tmp72); + -_tmp43 * (_tmp19 * _tmp69 + _tmp31 * (_tmp11 * (_tmp66 + _tmp68) + _tmp17)) - + _tmp44 * _tmp69 - _tmp69 * cm; + const Scalar _tmp71 = -_tmp43 * (_tmp59 + _tmp60 + _tmp61) - _tmp58 - _tmp62; + const Scalar _tmp72 = -_tmp16 * _tmp44 - _tmp16 * cm - + _tmp43 * (_tmp16 * _tmp19 + _tmp27 * _tmp31 + _tmp36 * _tmp39); + const Scalar _tmp73 = P(21, 21) * _tmp63; + const Scalar _tmp74 = P(22, 22) * _tmp57; + const Scalar _tmp75 = + R + + _tmp46 * (-P(0, 4) * _tmp67 + P(1, 4) * _tmp70 + P(2, 4) * _tmp56 + P(21, 4) * _tmp63 + + P(22, 4) * _tmp57 + P(3, 4) * _tmp71 + P(4, 4) * _tmp46 + P(5, 4) * _tmp72) + + _tmp56 * (-P(0, 2) * _tmp67 + P(1, 2) * _tmp70 + P(2, 2) * _tmp56 + P(21, 2) * _tmp63 + + P(22, 2) * _tmp57 + P(3, 2) * _tmp71 + P(4, 2) * _tmp46 + P(5, 2) * _tmp72) + + _tmp57 * (-P(0, 22) * _tmp67 + P(1, 22) * _tmp70 + P(2, 22) * _tmp56 + P(21, 22) * _tmp63 + + P(3, 22) * _tmp71 + P(4, 22) * _tmp46 + P(5, 22) * _tmp72 + _tmp74) + + _tmp63 * (-P(0, 21) * _tmp67 + P(1, 21) * _tmp70 + P(2, 21) * _tmp56 + P(22, 21) * _tmp57 + + P(3, 21) * _tmp71 + P(4, 21) * _tmp46 + P(5, 21) * _tmp72 + _tmp73) - + _tmp67 * (-P(0, 0) * _tmp67 + P(1, 0) * _tmp70 + P(2, 0) * _tmp56 + P(21, 0) * _tmp63 + + P(22, 0) * _tmp57 + P(3, 0) * _tmp71 + P(4, 0) * _tmp46 + P(5, 0) * _tmp72) + + _tmp70 * (-P(0, 1) * _tmp67 + P(1, 1) * _tmp70 + P(2, 1) * _tmp56 + P(21, 1) * _tmp63 + + P(22, 1) * _tmp57 + P(3, 1) * _tmp71 + P(4, 1) * _tmp46 + P(5, 1) * _tmp72) + + _tmp71 * (-P(0, 3) * _tmp67 + P(1, 3) * _tmp70 + P(2, 3) * _tmp56 + P(21, 3) * _tmp63 + + P(22, 3) * _tmp57 + P(3, 3) * _tmp71 + P(4, 3) * _tmp46 + P(5, 3) * _tmp72) + + _tmp72 * (-P(0, 5) * _tmp67 + P(1, 5) * _tmp70 + P(2, 5) * _tmp56 + P(21, 5) * _tmp63 + + P(22, 5) * _tmp57 + P(3, 5) * _tmp71 + P(4, 5) * _tmp46 + P(5, 5) * _tmp72); const Scalar _tmp76 = Scalar(1.0) / (math::max(_tmp75, epsilon)); // Output terms (2) @@ -164,16 +153,16 @@ void ComputeDragXInnovVarAndK(const matrix::Matrix& state, } if (K != nullptr) { - matrix::Matrix& _k = (*K); + matrix::Matrix& _k = (*K); _k.setZero(); - _k(22, 0) = _tmp76 * (P(22, 0) * _tmp70 + P(22, 1) * _tmp58 + P(22, 2) * _tmp62 + - P(22, 23) * _tmp49 + P(22, 3) * _tmp43 + P(22, 4) * _tmp71 + - P(22, 5) * _tmp50 + P(22, 6) * _tmp72 + _tmp74); - _k(23, 0) = _tmp76 * (P(23, 0) * _tmp70 + P(23, 1) * _tmp58 + P(23, 2) * _tmp62 + - P(23, 22) * _tmp68 + P(23, 3) * _tmp43 + P(23, 4) * _tmp71 + - P(23, 5) * _tmp50 + P(23, 6) * _tmp72 + _tmp73); + _k(21, 0) = + _tmp76 * (-P(21, 0) * _tmp67 + P(21, 1) * _tmp70 + P(21, 2) * _tmp56 + P(21, 22) * _tmp57 + + P(21, 3) * _tmp71 + P(21, 4) * _tmp46 + P(21, 5) * _tmp72 + _tmp73); + _k(22, 0) = + _tmp76 * (-P(22, 0) * _tmp67 + P(22, 1) * _tmp70 + P(22, 2) * _tmp56 + P(22, 21) * _tmp63 + + P(22, 3) * _tmp71 + P(22, 4) * _tmp46 + P(22, 5) * _tmp72 + _tmp74); } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_y_innov_var_and_k.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_y_innov_var_and_k.h index cb817b669916..43a129cd2606 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_y_innov_var_and_k.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_drag_y_innov_var_and_k.h @@ -17,7 +17,7 @@ namespace sym { * * Args: * state: Matrix24_1 - * P: Matrix24_24 + * P: Matrix23_23 * rho: Scalar * cd: Scalar * cm: Scalar @@ -26,157 +26,145 @@ namespace sym { * * Outputs: * innov_var: Scalar - * K: Matrix24_1 + * K: Matrix23_1 */ template void ComputeDragYInnovVarAndK(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar rho, + const matrix::Matrix& P, const Scalar rho, const Scalar cd, const Scalar cm, const Scalar R, const Scalar epsilon, Scalar* const innov_var = nullptr, - matrix::Matrix* const K = nullptr) { - // Total ops: 397 + matrix::Matrix* const K = nullptr) { + // Total ops: 348 // Input arrays - // Intermediate terms (76) - const Scalar _tmp0 = 2 * state(0, 0); - const Scalar _tmp1 = _tmp0 * state(3, 0); - const Scalar _tmp2 = 2 * state(1, 0); - const Scalar _tmp3 = _tmp2 * state(2, 0); - const Scalar _tmp4 = -_tmp1 + _tmp3; - const Scalar _tmp5 = _tmp4 * cm; - const Scalar _tmp6 = -2 * std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp7 = -2 * std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp8 = _tmp6 + _tmp7 + 1; + // Intermediate terms (77) + const Scalar _tmp0 = 2 * state(2, 0) * state(3, 0); + const Scalar _tmp1 = 2 * state(1, 0); + const Scalar _tmp2 = _tmp1 * state(0, 0); + const Scalar _tmp3 = _tmp0 + _tmp2; + const Scalar _tmp4 = std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp5 = -2 * _tmp4; + const Scalar _tmp6 = std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp7 = -2 * _tmp6; + const Scalar _tmp8 = _tmp5 + _tmp7 + 1; const Scalar _tmp9 = -state(22, 0) + state(4, 0); - const Scalar _tmp10 = _tmp1 + _tmp3; - const Scalar _tmp11 = -state(23, 0) + state(5, 0); - const Scalar _tmp12 = _tmp0 * state(2, 0); - const Scalar _tmp13 = _tmp2 * state(3, 0); - const Scalar _tmp14 = -_tmp12 + _tmp13; - const Scalar _tmp15 = _tmp10 * _tmp11 + _tmp14 * state(6, 0) + _tmp8 * _tmp9; - const Scalar _tmp16 = 2 * state(2, 0); - const Scalar _tmp17 = _tmp16 * state(3, 0); - const Scalar _tmp18 = _tmp2 * state(0, 0); - const Scalar _tmp19 = _tmp17 - _tmp18; - const Scalar _tmp20 = _tmp12 + _tmp13; - const Scalar _tmp21 = 1 - 2 * std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp22 = _tmp21 + _tmp7; - const Scalar _tmp23 = _tmp11 * _tmp19 + _tmp20 * _tmp9 + _tmp22 * state(6, 0); - const Scalar _tmp24 = _tmp21 + _tmp6; - const Scalar _tmp25 = _tmp17 + _tmp18; - const Scalar _tmp26 = _tmp11 * _tmp24 + _tmp25 * state(6, 0) + _tmp4 * _tmp9; - const Scalar _tmp27 = std::sqrt(Scalar(std::pow(_tmp15, Scalar(2)) + std::pow(_tmp23, Scalar(2)) + - std::pow(_tmp26, Scalar(2)) + epsilon)); - const Scalar _tmp28 = cd * rho; - const Scalar _tmp29 = Scalar(0.5) * _tmp27 * _tmp28; - const Scalar _tmp30 = _tmp29 * _tmp4; - const Scalar _tmp31 = 2 * _tmp15; - const Scalar _tmp32 = _tmp31 * _tmp8; - const Scalar _tmp33 = 2 * _tmp23; - const Scalar _tmp34 = _tmp20 * _tmp33; - const Scalar _tmp35 = 2 * _tmp26; - const Scalar _tmp36 = _tmp35 * _tmp4; - const Scalar _tmp37 = Scalar(0.25) * _tmp26 * _tmp28 / _tmp27; - const Scalar _tmp38 = -_tmp30 - _tmp37 * (_tmp32 + _tmp34 + _tmp36) - _tmp5; - const Scalar _tmp39 = -_tmp25 * _tmp29 - _tmp25 * cm - - _tmp37 * (_tmp14 * _tmp31 + _tmp22 * _tmp33 + _tmp25 * _tmp35); - const Scalar _tmp40 = 2 * state(3, 0); - const Scalar _tmp41 = _tmp40 * _tmp9; - const Scalar _tmp42 = _tmp2 * state(6, 0); - const Scalar _tmp43 = -_tmp41 + _tmp42; - const Scalar _tmp44 = _tmp11 * _tmp2; - const Scalar _tmp45 = _tmp16 * _tmp9; - const Scalar _tmp46 = _tmp11 * _tmp40; - const Scalar _tmp47 = _tmp16 * state(6, 0); - const Scalar _tmp48 = - -_tmp29 * _tmp43 - - _tmp37 * (_tmp31 * (_tmp46 - _tmp47) + _tmp33 * (-_tmp44 + _tmp45) + _tmp35 * _tmp43) - - _tmp43 * cm; - const Scalar _tmp49 = _tmp2 * _tmp9; - const Scalar _tmp50 = _tmp40 * state(6, 0); - const Scalar _tmp51 = _tmp49 + _tmp50; - const Scalar _tmp52 = _tmp0 * _tmp9; - const Scalar _tmp53 = 4 * state(6, 0); - const Scalar _tmp54 = 4 * _tmp9; - const Scalar _tmp55 = _tmp0 * state(6, 0); + const Scalar _tmp10 = 2 * state(0, 0); + const Scalar _tmp11 = _tmp10 * state(3, 0); + const Scalar _tmp12 = _tmp1 * state(2, 0); + const Scalar _tmp13 = _tmp11 + _tmp12; + const Scalar _tmp14 = -state(23, 0) + state(5, 0); + const Scalar _tmp15 = _tmp10 * state(2, 0); + const Scalar _tmp16 = -_tmp15; + const Scalar _tmp17 = _tmp1 * state(3, 0); + const Scalar _tmp18 = _tmp16 + _tmp17; + const Scalar _tmp19 = _tmp13 * _tmp14 + _tmp18 * state(6, 0); + const Scalar _tmp20 = _tmp19 + _tmp8 * _tmp9; + const Scalar _tmp21 = std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp22 = 1 - 2 * _tmp21; + const Scalar _tmp23 = _tmp22 + _tmp7; + const Scalar _tmp24 = -_tmp2; + const Scalar _tmp25 = _tmp0 + _tmp24; + const Scalar _tmp26 = _tmp15 + _tmp17; + const Scalar _tmp27 = _tmp14 * _tmp25 + _tmp26 * _tmp9; + const Scalar _tmp28 = _tmp23 * state(6, 0) + _tmp27; + const Scalar _tmp29 = _tmp22 + _tmp5; + const Scalar _tmp30 = -_tmp11; + const Scalar _tmp31 = _tmp12 + _tmp30; + const Scalar _tmp32 = _tmp3 * state(6, 0) + _tmp31 * _tmp9; + const Scalar _tmp33 = _tmp14 * _tmp29 + _tmp32; + const Scalar _tmp34 = std::sqrt(Scalar(std::pow(_tmp20, Scalar(2)) + std::pow(_tmp28, Scalar(2)) + + std::pow(_tmp33, Scalar(2)) + epsilon)); + const Scalar _tmp35 = cd * rho; + const Scalar _tmp36 = Scalar(0.5) * _tmp34 * _tmp35; + const Scalar _tmp37 = 2 * _tmp20; + const Scalar _tmp38 = 2 * _tmp28; + const Scalar _tmp39 = 2 * _tmp33; + const Scalar _tmp40 = Scalar(0.25) * _tmp33 * _tmp35 / _tmp34; + const Scalar _tmp41 = + -_tmp3 * _tmp36 - _tmp3 * cm - _tmp40 * (_tmp18 * _tmp37 + _tmp23 * _tmp38 + _tmp3 * _tmp39); + const Scalar _tmp42 = std::pow(state(0, 0), Scalar(2)); + const Scalar _tmp43 = -_tmp42; + const Scalar _tmp44 = -_tmp6; + const Scalar _tmp45 = -_tmp12; + const Scalar _tmp46 = -_tmp0; + const Scalar _tmp47 = -_tmp21; + const Scalar _tmp48 = _tmp4 + _tmp47; + const Scalar _tmp49 = _tmp42 + _tmp44; + const Scalar _tmp50 = _tmp27 + state(6, 0) * (_tmp48 + _tmp49); + const Scalar _tmp51 = + -_tmp36 * _tmp50 - + _tmp40 * (_tmp38 * (_tmp14 * (_tmp21 + _tmp4 + _tmp43 + _tmp44) + _tmp9 * (_tmp11 + _tmp45) + + state(6, 0) * (_tmp24 + _tmp46)) + + _tmp39 * _tmp50) - + _tmp50 * cm; + const Scalar _tmp52 = _tmp43 + _tmp6; + const Scalar _tmp53 = -_tmp17; + const Scalar _tmp54 = + _tmp14 * (_tmp30 + _tmp45) + _tmp9 * (_tmp48 + _tmp52) + state(6, 0) * (_tmp15 + _tmp53); + const Scalar _tmp55 = -_tmp4; const Scalar _tmp56 = - -_tmp29 * _tmp51 - - _tmp37 * (_tmp31 * (_tmp44 - _tmp54 * state(2, 0) - _tmp55) + - _tmp33 * (_tmp46 + _tmp52 - _tmp53 * state(2, 0)) + _tmp35 * _tmp51) - - _tmp51 * cm; - const Scalar _tmp57 = _tmp24 * cm; - const Scalar _tmp58 = _tmp10 * _tmp31; - const Scalar _tmp59 = _tmp19 * _tmp33; - const Scalar _tmp60 = _tmp24 * _tmp35; - const Scalar _tmp61 = _tmp24 * _tmp29; - const Scalar _tmp62 = -_tmp37 * (-_tmp58 - _tmp59 - _tmp60) + _tmp57 + _tmp61; - const Scalar _tmp63 = _tmp0 * _tmp11; - const Scalar _tmp64 = _tmp11 * _tmp16; - const Scalar _tmp65 = 4 * _tmp11; - const Scalar _tmp66 = _tmp45 + _tmp55 - _tmp65 * state(1, 0); - const Scalar _tmp67 = - -_tmp29 * _tmp66 - - _tmp37 * (_tmp31 * (_tmp50 + _tmp64) + _tmp33 * (_tmp41 - _tmp53 * state(1, 0) - _tmp63) + - _tmp35 * _tmp66) - - _tmp66 * cm; - const Scalar _tmp68 = -_tmp37 * (_tmp58 + _tmp59 + _tmp60) - _tmp57 - _tmp61; - const Scalar _tmp69 = _tmp47 - _tmp52 - _tmp65 * state(3, 0); - const Scalar _tmp70 = -_tmp29 * _tmp69 - - _tmp37 * (_tmp31 * (_tmp42 - _tmp54 * state(3, 0) + _tmp63) + - _tmp33 * (_tmp49 + _tmp64) + _tmp35 * _tmp69) - - _tmp69 * cm; - const Scalar _tmp71 = _tmp30 - _tmp37 * (-_tmp32 - _tmp34 - _tmp36) + _tmp5; - const Scalar _tmp72 = P(22, 22) * _tmp71; - const Scalar _tmp73 = P(23, 23) * _tmp62; - const Scalar _tmp74 = R + - _tmp38 * (P(0, 4) * _tmp48 + P(1, 4) * _tmp67 + P(2, 4) * _tmp56 + - P(22, 4) * _tmp71 + P(23, 4) * _tmp62 + P(3, 4) * _tmp70 + - P(4, 4) * _tmp38 + P(5, 4) * _tmp68 + P(6, 4) * _tmp39) + - _tmp39 * (P(0, 6) * _tmp48 + P(1, 6) * _tmp67 + P(2, 6) * _tmp56 + - P(22, 6) * _tmp71 + P(23, 6) * _tmp62 + P(3, 6) * _tmp70 + - P(4, 6) * _tmp38 + P(5, 6) * _tmp68 + P(6, 6) * _tmp39) + - _tmp48 * (P(0, 0) * _tmp48 + P(1, 0) * _tmp67 + P(2, 0) * _tmp56 + - P(22, 0) * _tmp71 + P(23, 0) * _tmp62 + P(3, 0) * _tmp70 + - P(4, 0) * _tmp38 + P(5, 0) * _tmp68 + P(6, 0) * _tmp39) + - _tmp56 * (P(0, 2) * _tmp48 + P(1, 2) * _tmp67 + P(2, 2) * _tmp56 + - P(22, 2) * _tmp71 + P(23, 2) * _tmp62 + P(3, 2) * _tmp70 + - P(4, 2) * _tmp38 + P(5, 2) * _tmp68 + P(6, 2) * _tmp39) + - _tmp62 * (P(0, 23) * _tmp48 + P(1, 23) * _tmp67 + P(2, 23) * _tmp56 + - P(22, 23) * _tmp71 + P(3, 23) * _tmp70 + P(4, 23) * _tmp38 + - P(5, 23) * _tmp68 + P(6, 23) * _tmp39 + _tmp73) + - _tmp67 * (P(0, 1) * _tmp48 + P(1, 1) * _tmp67 + P(2, 1) * _tmp56 + - P(22, 1) * _tmp71 + P(23, 1) * _tmp62 + P(3, 1) * _tmp70 + - P(4, 1) * _tmp38 + P(5, 1) * _tmp68 + P(6, 1) * _tmp39) + - _tmp68 * (P(0, 5) * _tmp48 + P(1, 5) * _tmp67 + P(2, 5) * _tmp56 + - P(22, 5) * _tmp71 + P(23, 5) * _tmp62 + P(3, 5) * _tmp70 + - P(4, 5) * _tmp38 + P(5, 5) * _tmp68 + P(6, 5) * _tmp39) + - _tmp70 * (P(0, 3) * _tmp48 + P(1, 3) * _tmp67 + P(2, 3) * _tmp56 + - P(22, 3) * _tmp71 + P(23, 3) * _tmp62 + P(3, 3) * _tmp70 + - P(4, 3) * _tmp38 + P(5, 3) * _tmp68 + P(6, 3) * _tmp39) + - _tmp71 * (P(0, 22) * _tmp48 + P(1, 22) * _tmp67 + P(2, 22) * _tmp56 + - P(23, 22) * _tmp62 + P(3, 22) * _tmp70 + P(4, 22) * _tmp38 + - P(5, 22) * _tmp68 + P(6, 22) * _tmp39 + _tmp72); - const Scalar _tmp75 = Scalar(1.0) / (math::max(_tmp74, epsilon)); + -_tmp36 * _tmp54 - + _tmp40 * (_tmp37 * (_tmp14 * (_tmp42 + _tmp47 + _tmp55 + _tmp6) + _tmp32) + _tmp39 * _tmp54) - + _tmp54 * cm; + const Scalar _tmp57 = _tmp29 * cm; + const Scalar _tmp58 = _tmp13 * _tmp37; + const Scalar _tmp59 = _tmp25 * _tmp38; + const Scalar _tmp60 = _tmp29 * _tmp39; + const Scalar _tmp61 = _tmp29 * _tmp36; + const Scalar _tmp62 = -_tmp40 * (-_tmp58 - _tmp59 - _tmp60) + _tmp57 + _tmp61; + const Scalar _tmp63 = _tmp21 + _tmp55; + const Scalar _tmp64 = _tmp40 * (_tmp37 * (_tmp14 * (_tmp2 + _tmp46) + _tmp9 * (_tmp16 + _tmp53) + + state(6, 0) * (_tmp52 + _tmp63)) + + _tmp38 * (_tmp19 + _tmp9 * (_tmp49 + _tmp63))); + const Scalar _tmp65 = -_tmp40 * (_tmp58 + _tmp59 + _tmp60) - _tmp57 - _tmp61; + const Scalar _tmp66 = _tmp31 * cm; + const Scalar _tmp67 = _tmp31 * _tmp36; + const Scalar _tmp68 = _tmp37 * _tmp8; + const Scalar _tmp69 = _tmp26 * _tmp38; + const Scalar _tmp70 = _tmp31 * _tmp39; + const Scalar _tmp71 = -_tmp40 * (_tmp68 + _tmp69 + _tmp70) - _tmp66 - _tmp67; + const Scalar _tmp72 = -_tmp40 * (-_tmp68 - _tmp69 - _tmp70) + _tmp66 + _tmp67; + const Scalar _tmp73 = P(22, 22) * _tmp62; + const Scalar _tmp74 = P(21, 21) * _tmp72; + const Scalar _tmp75 = + R + + _tmp41 * (P(0, 5) * _tmp51 - P(1, 5) * _tmp64 + P(2, 5) * _tmp56 + P(21, 5) * _tmp72 + + P(22, 5) * _tmp62 + P(3, 5) * _tmp71 + P(4, 5) * _tmp65 + P(5, 5) * _tmp41) + + _tmp51 * (P(0, 0) * _tmp51 - P(1, 0) * _tmp64 + P(2, 0) * _tmp56 + P(21, 0) * _tmp72 + + P(22, 0) * _tmp62 + P(3, 0) * _tmp71 + P(4, 0) * _tmp65 + P(5, 0) * _tmp41) + + _tmp56 * (P(0, 2) * _tmp51 - P(1, 2) * _tmp64 + P(2, 2) * _tmp56 + P(21, 2) * _tmp72 + + P(22, 2) * _tmp62 + P(3, 2) * _tmp71 + P(4, 2) * _tmp65 + P(5, 2) * _tmp41) + + _tmp62 * (P(0, 22) * _tmp51 - P(1, 22) * _tmp64 + P(2, 22) * _tmp56 + P(21, 22) * _tmp72 + + P(3, 22) * _tmp71 + P(4, 22) * _tmp65 + P(5, 22) * _tmp41 + _tmp73) - + _tmp64 * (P(0, 1) * _tmp51 - P(1, 1) * _tmp64 + P(2, 1) * _tmp56 + P(21, 1) * _tmp72 + + P(22, 1) * _tmp62 + P(3, 1) * _tmp71 + P(4, 1) * _tmp65 + P(5, 1) * _tmp41) + + _tmp65 * (P(0, 4) * _tmp51 - P(1, 4) * _tmp64 + P(2, 4) * _tmp56 + P(21, 4) * _tmp72 + + P(22, 4) * _tmp62 + P(3, 4) * _tmp71 + P(4, 4) * _tmp65 + P(5, 4) * _tmp41) + + _tmp71 * (P(0, 3) * _tmp51 - P(1, 3) * _tmp64 + P(2, 3) * _tmp56 + P(21, 3) * _tmp72 + + P(22, 3) * _tmp62 + P(3, 3) * _tmp71 + P(4, 3) * _tmp65 + P(5, 3) * _tmp41) + + _tmp72 * (P(0, 21) * _tmp51 - P(1, 21) * _tmp64 + P(2, 21) * _tmp56 + P(22, 21) * _tmp62 + + P(3, 21) * _tmp71 + P(4, 21) * _tmp65 + P(5, 21) * _tmp41 + _tmp74); + const Scalar _tmp76 = Scalar(1.0) / (math::max(_tmp75, epsilon)); // Output terms (2) if (innov_var != nullptr) { Scalar& _innov_var = (*innov_var); - _innov_var = _tmp74; + _innov_var = _tmp75; } if (K != nullptr) { - matrix::Matrix& _k = (*K); + matrix::Matrix& _k = (*K); _k.setZero(); - _k(22, 0) = _tmp75 * (P(22, 0) * _tmp48 + P(22, 1) * _tmp67 + P(22, 2) * _tmp56 + - P(22, 23) * _tmp62 + P(22, 3) * _tmp70 + P(22, 4) * _tmp38 + - P(22, 5) * _tmp68 + P(22, 6) * _tmp39 + _tmp72); - _k(23, 0) = _tmp75 * (P(23, 0) * _tmp48 + P(23, 1) * _tmp67 + P(23, 2) * _tmp56 + - P(23, 22) * _tmp71 + P(23, 3) * _tmp70 + P(23, 4) * _tmp38 + - P(23, 5) * _tmp68 + P(23, 6) * _tmp39 + _tmp73); + _k(21, 0) = + _tmp76 * (P(21, 0) * _tmp51 - P(21, 1) * _tmp64 + P(21, 2) * _tmp56 + P(21, 22) * _tmp62 + + P(21, 3) * _tmp71 + P(21, 4) * _tmp65 + P(21, 5) * _tmp41 + _tmp74); + _k(22, 0) = + _tmp76 * (P(22, 0) * _tmp51 - P(22, 1) * _tmp64 + P(22, 2) * _tmp56 + P(22, 21) * _tmp72 + + P(22, 3) * _tmp71 + P(22, 4) * _tmp65 + P(22, 5) * _tmp41 + _tmp73); } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_xy_innov_var_and_hx.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_xy_innov_var_and_hx.h index ffd18295c7af..11dfaacfcc0f 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_xy_innov_var_and_hx.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_xy_innov_var_and_hx.h @@ -17,107 +17,104 @@ namespace sym { * * Args: * state: Matrix24_1 - * P: Matrix24_24 + * P: Matrix23_23 * distance: Scalar * R: Scalar * epsilon: Scalar * * Outputs: * innov_var: Matrix21 - * H: Matrix24_1 + * H: Matrix23_1 */ template void ComputeFlowXyInnovVarAndHx(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar distance, + const matrix::Matrix& P, const Scalar distance, const Scalar R, const Scalar epsilon, matrix::Matrix* const innov_var = nullptr, - matrix::Matrix* const H = nullptr) { - // Total ops: 291 + matrix::Matrix* const H = nullptr) { + // Total ops: 196 // Input arrays - // Intermediate terms (28) - const Scalar _tmp0 = 1 - 2 * std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp1 = + // Intermediate terms (33) + const Scalar _tmp0 = std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp1 = std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp2 = 1 - 2 * _tmp1; + const Scalar _tmp3 = Scalar(1.0) / (distance + epsilon * (2 * math::min(0, (((distance) > 0) - ((distance) < 0))) + 1)); - const Scalar _tmp2 = _tmp1 * (_tmp0 - 2 * std::pow(state(1, 0), Scalar(2))); - const Scalar _tmp3 = 2 * state(1, 0); - const Scalar _tmp4 = 2 * state(3, 0); - const Scalar _tmp5 = _tmp4 * state(6, 0); - const Scalar _tmp6 = _tmp1 * (_tmp3 * state(4, 0) + _tmp5); - const Scalar _tmp7 = _tmp3 * state(6, 0); - const Scalar _tmp8 = _tmp1 * (-_tmp4 * state(4, 0) + _tmp7); - const Scalar _tmp9 = _tmp4 * state(0, 0); - const Scalar _tmp10 = _tmp3 * state(2, 0); - const Scalar _tmp11 = _tmp1 * (_tmp10 - _tmp9); - const Scalar _tmp12 = 2 * state(0, 0); - const Scalar _tmp13 = 4 * state(5, 0); - const Scalar _tmp14 = 2 * state(2, 0); - const Scalar _tmp15 = _tmp14 * state(6, 0); - const Scalar _tmp16 = _tmp1 * (-_tmp12 * state(4, 0) - _tmp13 * state(3, 0) + _tmp15); - const Scalar _tmp17 = _tmp12 * state(6, 0); - const Scalar _tmp18 = _tmp1 * (-_tmp13 * state(1, 0) + _tmp14 * state(4, 0) + _tmp17); - const Scalar _tmp19 = _tmp1 * (_tmp12 * state(1, 0) + _tmp4 * state(2, 0)); - const Scalar _tmp20 = _tmp1 * (_tmp0 - 2 * std::pow(state(2, 0), Scalar(2))); - const Scalar _tmp21 = _tmp1 * (_tmp10 + _tmp9); - const Scalar _tmp22 = _tmp1 * (-_tmp12 * state(2, 0) + _tmp4 * state(1, 0)); - const Scalar _tmp23 = 4 * state(4, 0); - const Scalar _tmp24 = _tmp1 * (_tmp12 * state(5, 0) - _tmp23 * state(3, 0) + _tmp7); - const Scalar _tmp25 = _tmp1 * (-_tmp17 - _tmp23 * state(2, 0) + _tmp3 * state(5, 0)); - const Scalar _tmp26 = _tmp1 * (-_tmp15 + _tmp4 * state(5, 0)); - const Scalar _tmp27 = _tmp1 * (_tmp14 * state(5, 0) + _tmp5); + const Scalar _tmp4 = _tmp3 * (-2 * _tmp0 + _tmp2); + const Scalar _tmp5 = 2 * state(2, 0); + const Scalar _tmp6 = _tmp5 * state(0, 0); + const Scalar _tmp7 = 2 * state(1, 0) * state(3, 0); + const Scalar _tmp8 = _tmp5 * state(3, 0); + const Scalar _tmp9 = 2 * state(0, 0); + const Scalar _tmp10 = _tmp9 * state(1, 0); + const Scalar _tmp11 = std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp12 = std::pow(state(0, 0), Scalar(2)); + const Scalar _tmp13 = -_tmp0; + const Scalar _tmp14 = _tmp12 + _tmp13; + const Scalar _tmp15 = _tmp3 * (state(4, 0) * (_tmp6 + _tmp7) + state(5, 0) * (-_tmp10 + _tmp8) + + state(6, 0) * (_tmp1 - _tmp11 + _tmp14)); + const Scalar _tmp16 = _tmp9 * state(3, 0); + const Scalar _tmp17 = -_tmp16; + const Scalar _tmp18 = _tmp5 * state(1, 0); + const Scalar _tmp19 = _tmp17 + _tmp18; + const Scalar _tmp20 = _tmp19 * _tmp3; + const Scalar _tmp21 = _tmp10 + _tmp8; + const Scalar _tmp22 = _tmp21 * _tmp3; + const Scalar _tmp23 = -_tmp7; + const Scalar _tmp24 = -_tmp12; + const Scalar _tmp25 = _tmp3 * (state(4, 0) * (_tmp1 + _tmp11 + _tmp13 + _tmp24) + + state(5, 0) * (_tmp17 - _tmp18) + state(6, 0) * (_tmp23 + _tmp6)); + const Scalar _tmp26 = _tmp3 * (-2 * _tmp11 + _tmp2); + const Scalar _tmp27 = -_tmp6; + const Scalar _tmp28 = -_tmp1 + _tmp11; + const Scalar _tmp29 = _tmp3 * (state(4, 0) * (_tmp23 + _tmp27) + state(5, 0) * (_tmp10 - _tmp8) + + state(6, 0) * (_tmp0 + _tmp24 + _tmp28)); + const Scalar _tmp30 = + _tmp3 * (_tmp19 * state(4, 0) + _tmp21 * state(6, 0) + state(5, 0) * (_tmp14 + _tmp28)); + const Scalar _tmp31 = _tmp3 * (_tmp16 + _tmp18); + const Scalar _tmp32 = _tmp3 * (_tmp27 + _tmp7); // Output terms (2) if (innov_var != nullptr) { matrix::Matrix& _innov_var = (*innov_var); - _innov_var(0, 0) = - R + - _tmp11 * (P(0, 4) * _tmp8 + P(1, 4) * _tmp18 + P(2, 4) * _tmp6 + P(3, 4) * _tmp16 + - P(4, 4) * _tmp11 + P(5, 4) * _tmp2 + P(6, 4) * _tmp19) + - _tmp16 * (P(0, 3) * _tmp8 + P(1, 3) * _tmp18 + P(2, 3) * _tmp6 + P(3, 3) * _tmp16 + - P(4, 3) * _tmp11 + P(5, 3) * _tmp2 + P(6, 3) * _tmp19) + - _tmp18 * (P(0, 1) * _tmp8 + P(1, 1) * _tmp18 + P(2, 1) * _tmp6 + P(3, 1) * _tmp16 + - P(4, 1) * _tmp11 + P(5, 1) * _tmp2 + P(6, 1) * _tmp19) + - _tmp19 * (P(0, 6) * _tmp8 + P(1, 6) * _tmp18 + P(2, 6) * _tmp6 + P(3, 6) * _tmp16 + - P(4, 6) * _tmp11 + P(5, 6) * _tmp2 + P(6, 6) * _tmp19) + - _tmp2 * (P(0, 5) * _tmp8 + P(1, 5) * _tmp18 + P(2, 5) * _tmp6 + P(3, 5) * _tmp16 + - P(4, 5) * _tmp11 + P(5, 5) * _tmp2 + P(6, 5) * _tmp19) + - _tmp6 * (P(0, 2) * _tmp8 + P(1, 2) * _tmp18 + P(2, 2) * _tmp6 + P(3, 2) * _tmp16 + - P(4, 2) * _tmp11 + P(5, 2) * _tmp2 + P(6, 2) * _tmp19) + - _tmp8 * (P(0, 0) * _tmp8 + P(1, 0) * _tmp18 + P(2, 0) * _tmp6 + P(3, 0) * _tmp16 + - P(4, 0) * _tmp11 + P(5, 0) * _tmp2 + P(6, 0) * _tmp19); - _innov_var(1, 0) = - R - - _tmp20 * (-P(0, 4) * _tmp26 - P(1, 4) * _tmp27 - P(2, 4) * _tmp25 - P(3, 4) * _tmp24 - - P(4, 4) * _tmp20 - P(5, 4) * _tmp21 - P(6, 4) * _tmp22) - - _tmp21 * (-P(0, 5) * _tmp26 - P(1, 5) * _tmp27 - P(2, 5) * _tmp25 - P(3, 5) * _tmp24 - - P(4, 5) * _tmp20 - P(5, 5) * _tmp21 - P(6, 5) * _tmp22) - - _tmp22 * (-P(0, 6) * _tmp26 - P(1, 6) * _tmp27 - P(2, 6) * _tmp25 - P(3, 6) * _tmp24 - - P(4, 6) * _tmp20 - P(5, 6) * _tmp21 - P(6, 6) * _tmp22) - - _tmp24 * (-P(0, 3) * _tmp26 - P(1, 3) * _tmp27 - P(2, 3) * _tmp25 - P(3, 3) * _tmp24 - - P(4, 3) * _tmp20 - P(5, 3) * _tmp21 - P(6, 3) * _tmp22) - - _tmp25 * (-P(0, 2) * _tmp26 - P(1, 2) * _tmp27 - P(2, 2) * _tmp25 - P(3, 2) * _tmp24 - - P(4, 2) * _tmp20 - P(5, 2) * _tmp21 - P(6, 2) * _tmp22) - - _tmp26 * (-P(0, 0) * _tmp26 - P(1, 0) * _tmp27 - P(2, 0) * _tmp25 - P(3, 0) * _tmp24 - - P(4, 0) * _tmp20 - P(5, 0) * _tmp21 - P(6, 0) * _tmp22) - - _tmp27 * (-P(0, 1) * _tmp26 - P(1, 1) * _tmp27 - P(2, 1) * _tmp25 - P(3, 1) * _tmp24 - - P(4, 1) * _tmp20 - P(5, 1) * _tmp21 - P(6, 1) * _tmp22); + _innov_var(0, 0) = R + + _tmp15 * (P(0, 0) * _tmp15 + P(2, 0) * _tmp25 + P(3, 0) * _tmp20 + + P(4, 0) * _tmp4 + P(5, 0) * _tmp22) + + _tmp20 * (P(0, 3) * _tmp15 + P(2, 3) * _tmp25 + P(3, 3) * _tmp20 + + P(4, 3) * _tmp4 + P(5, 3) * _tmp22) + + _tmp22 * (P(0, 5) * _tmp15 + P(2, 5) * _tmp25 + P(3, 5) * _tmp20 + + P(4, 5) * _tmp4 + P(5, 5) * _tmp22) + + _tmp25 * (P(0, 2) * _tmp15 + P(2, 2) * _tmp25 + P(3, 2) * _tmp20 + + P(4, 2) * _tmp4 + P(5, 2) * _tmp22) + + _tmp4 * (P(0, 4) * _tmp15 + P(2, 4) * _tmp25 + P(3, 4) * _tmp20 + + P(4, 4) * _tmp4 + P(5, 4) * _tmp22); + _innov_var(1, 0) = R - + _tmp26 * (-P(1, 3) * _tmp29 - P(2, 3) * _tmp30 - P(3, 3) * _tmp26 - + P(4, 3) * _tmp31 - P(5, 3) * _tmp32) - + _tmp29 * (-P(1, 1) * _tmp29 - P(2, 1) * _tmp30 - P(3, 1) * _tmp26 - + P(4, 1) * _tmp31 - P(5, 1) * _tmp32) - + _tmp30 * (-P(1, 2) * _tmp29 - P(2, 2) * _tmp30 - P(3, 2) * _tmp26 - + P(4, 2) * _tmp31 - P(5, 2) * _tmp32) - + _tmp31 * (-P(1, 4) * _tmp29 - P(2, 4) * _tmp30 - P(3, 4) * _tmp26 - + P(4, 4) * _tmp31 - P(5, 4) * _tmp32) - + _tmp32 * (-P(1, 5) * _tmp29 - P(2, 5) * _tmp30 - P(3, 5) * _tmp26 - + P(4, 5) * _tmp31 - P(5, 5) * _tmp32); } if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); - _h(0, 0) = _tmp8; - _h(1, 0) = _tmp18; - _h(2, 0) = _tmp6; - _h(3, 0) = _tmp16; - _h(4, 0) = _tmp11; - _h(5, 0) = _tmp2; - _h(6, 0) = _tmp19; + _h(0, 0) = _tmp15; + _h(2, 0) = _tmp25; + _h(3, 0) = _tmp20; + _h(4, 0) = _tmp4; + _h(5, 0) = _tmp22; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_y_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_y_innov_var_and_h.h index 43dba354809e..3e00a2f60490 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_y_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_flow_y_innov_var_and_h.h @@ -17,76 +17,78 @@ namespace sym { * * Args: * state: Matrix24_1 - * P: Matrix24_24 + * P: Matrix23_23 * distance: Scalar * R: Scalar * epsilon: Scalar * * Outputs: * innov_var: Scalar - * H: Matrix24_1 + * H: Matrix23_1 */ template void ComputeFlowYInnovVarAndH(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar distance, + const matrix::Matrix& P, const Scalar distance, const Scalar R, const Scalar epsilon, Scalar* const innov_var = nullptr, - matrix::Matrix* const H = nullptr) { - // Total ops: 166 + matrix::Matrix* const H = nullptr) { + // Total ops: 116 // Input arrays - // Intermediate terms (13) - const Scalar _tmp0 = + // Intermediate terms (19) + const Scalar _tmp0 = std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp1 = std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp2 = Scalar(1.0) / (distance + epsilon * (2 * math::min(0, (((distance) > 0) - ((distance) < 0))) + 1)); - const Scalar _tmp1 = - _tmp0 * (-2 * std::pow(state(2, 0), Scalar(2)) - 2 * std::pow(state(3, 0), Scalar(2)) + 1); - const Scalar _tmp2 = 2 * state(3, 0); - const Scalar _tmp3 = 2 * state(2, 0); - const Scalar _tmp4 = _tmp0 * (_tmp2 * state(0, 0) + _tmp3 * state(1, 0)); - const Scalar _tmp5 = _tmp0 * (_tmp2 * state(1, 0) - _tmp3 * state(0, 0)); - const Scalar _tmp6 = 4 * state(4, 0); - const Scalar _tmp7 = 2 * state(5, 0); - const Scalar _tmp8 = 2 * state(6, 0); - const Scalar _tmp9 = _tmp0 * (-_tmp6 * state(3, 0) + _tmp7 * state(0, 0) + _tmp8 * state(1, 0)); - const Scalar _tmp10 = _tmp0 * (-_tmp6 * state(2, 0) + _tmp7 * state(1, 0) - _tmp8 * state(0, 0)); - const Scalar _tmp11 = _tmp0 * (-_tmp3 * state(6, 0) + _tmp7 * state(3, 0)); - const Scalar _tmp12 = _tmp0 * (_tmp2 * state(6, 0) + _tmp3 * state(5, 0)); + const Scalar _tmp3 = _tmp2 * (-2 * _tmp0 - 2 * _tmp1 + 1); + const Scalar _tmp4 = -2 * state(0, 0) * state(2, 0); + const Scalar _tmp5 = 2 * state(3, 0); + const Scalar _tmp6 = _tmp5 * state(1, 0); + const Scalar _tmp7 = _tmp5 * state(2, 0); + const Scalar _tmp8 = 2 * state(1, 0); + const Scalar _tmp9 = _tmp8 * state(0, 0); + const Scalar _tmp10 = std::pow(state(0, 0), Scalar(2)); + const Scalar _tmp11 = std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp12 = -_tmp0 + _tmp1; + const Scalar _tmp13 = _tmp2 * (state(4, 0) * (_tmp4 - _tmp6) + state(5, 0) * (-_tmp7 + _tmp9) + + state(6, 0) * (-_tmp10 + _tmp11 + _tmp12)); + const Scalar _tmp14 = _tmp5 * state(0, 0); + const Scalar _tmp15 = _tmp8 * state(2, 0); + const Scalar _tmp16 = + _tmp2 * (state(4, 0) * (-_tmp14 + _tmp15) + state(5, 0) * (_tmp10 - _tmp11 + _tmp12) + + state(6, 0) * (_tmp7 + _tmp9)); + const Scalar _tmp17 = _tmp2 * (_tmp14 + _tmp15); + const Scalar _tmp18 = _tmp2 * (_tmp4 + _tmp6); // Output terms (2) if (innov_var != nullptr) { Scalar& _innov_var = (*innov_var); _innov_var = R - - _tmp1 * (-P(0, 4) * _tmp11 - P(1, 4) * _tmp12 - P(2, 4) * _tmp10 - - P(3, 4) * _tmp9 - P(4, 4) * _tmp1 - P(5, 4) * _tmp4 - P(6, 4) * _tmp5) - - _tmp10 * (-P(0, 2) * _tmp11 - P(1, 2) * _tmp12 - P(2, 2) * _tmp10 - - P(3, 2) * _tmp9 - P(4, 2) * _tmp1 - P(5, 2) * _tmp4 - P(6, 2) * _tmp5) - - _tmp11 * (-P(0, 0) * _tmp11 - P(1, 0) * _tmp12 - P(2, 0) * _tmp10 - - P(3, 0) * _tmp9 - P(4, 0) * _tmp1 - P(5, 0) * _tmp4 - P(6, 0) * _tmp5) - - _tmp12 * (-P(0, 1) * _tmp11 - P(1, 1) * _tmp12 - P(2, 1) * _tmp10 - - P(3, 1) * _tmp9 - P(4, 1) * _tmp1 - P(5, 1) * _tmp4 - P(6, 1) * _tmp5) - - _tmp4 * (-P(0, 5) * _tmp11 - P(1, 5) * _tmp12 - P(2, 5) * _tmp10 - - P(3, 5) * _tmp9 - P(4, 5) * _tmp1 - P(5, 5) * _tmp4 - P(6, 5) * _tmp5) - - _tmp5 * (-P(0, 6) * _tmp11 - P(1, 6) * _tmp12 - P(2, 6) * _tmp10 - - P(3, 6) * _tmp9 - P(4, 6) * _tmp1 - P(5, 6) * _tmp4 - P(6, 6) * _tmp5) - - _tmp9 * (-P(0, 3) * _tmp11 - P(1, 3) * _tmp12 - P(2, 3) * _tmp10 - - P(3, 3) * _tmp9 - P(4, 3) * _tmp1 - P(5, 3) * _tmp4 - P(6, 3) * _tmp5); + _tmp13 * (-P(1, 1) * _tmp13 - P(2, 1) * _tmp16 - P(3, 1) * _tmp3 - + P(4, 1) * _tmp17 - P(5, 1) * _tmp18) - + _tmp16 * (-P(1, 2) * _tmp13 - P(2, 2) * _tmp16 - P(3, 2) * _tmp3 - + P(4, 2) * _tmp17 - P(5, 2) * _tmp18) - + _tmp17 * (-P(1, 4) * _tmp13 - P(2, 4) * _tmp16 - P(3, 4) * _tmp3 - + P(4, 4) * _tmp17 - P(5, 4) * _tmp18) - + _tmp18 * (-P(1, 5) * _tmp13 - P(2, 5) * _tmp16 - P(3, 5) * _tmp3 - + P(4, 5) * _tmp17 - P(5, 5) * _tmp18) - + _tmp3 * (-P(1, 3) * _tmp13 - P(2, 3) * _tmp16 - P(3, 3) * _tmp3 - + P(4, 3) * _tmp17 - P(5, 3) * _tmp18); } if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); - _h(0, 0) = -_tmp11; - _h(1, 0) = -_tmp12; - _h(2, 0) = -_tmp10; - _h(3, 0) = -_tmp9; - _h(4, 0) = -_tmp1; - _h(5, 0) = -_tmp4; - _h(6, 0) = -_tmp5; + _h(1, 0) = -_tmp13; + _h(2, 0) = -_tmp16; + _h(3, 0) = -_tmp3; + _h(4, 0) = -_tmp17; + _h(5, 0) = -_tmp18; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gnss_yaw_pred_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gnss_yaw_pred_innov_var_and_h.h index 4ef4c91deadd..d1be17dc3556 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gnss_yaw_pred_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gnss_yaw_pred_innov_var_and_h.h @@ -17,7 +17,7 @@ namespace sym { * * Args: * state: Matrix24_1 - * P: Matrix24_24 + * P: Matrix23_23 * antenna_yaw_offset: Scalar * R: Scalar * epsilon: Scalar @@ -25,74 +25,76 @@ namespace sym { * Outputs: * meas_pred: Scalar * innov_var: Scalar - * H: Matrix24_1 + * H: Matrix23_1 */ template void ComputeGnssYawPredInnovVarAndH(const matrix::Matrix& state, - const matrix::Matrix& P, + const matrix::Matrix& P, const Scalar antenna_yaw_offset, const Scalar R, const Scalar epsilon, Scalar* const meas_pred = nullptr, Scalar* const innov_var = nullptr, - matrix::Matrix* const H = nullptr) { - // Total ops: 105 + matrix::Matrix* const H = nullptr) { + // Total ops: 95 // Input arrays - // Intermediate terms (22) - const Scalar _tmp0 = 1 - 2 * std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp1 = std::sin(antenna_yaw_offset); - const Scalar _tmp2 = 2 * state(0, 0) * state(3, 0); - const Scalar _tmp3 = 2 * state(1, 0) * state(2, 0); - const Scalar _tmp4 = std::cos(antenna_yaw_offset); - const Scalar _tmp5 = - _tmp1 * (_tmp0 - 2 * std::pow(state(1, 0), Scalar(2))) + _tmp4 * (_tmp2 + _tmp3); - const Scalar _tmp6 = - _tmp1 * (-_tmp2 + _tmp3) + _tmp4 * (_tmp0 - 2 * std::pow(state(2, 0), Scalar(2))); - const Scalar _tmp7 = _tmp6 + epsilon * ((((_tmp6) > 0) - ((_tmp6) < 0)) + Scalar(0.5)); - const Scalar _tmp8 = 4 * _tmp1; - const Scalar _tmp9 = 2 * _tmp4; - const Scalar _tmp10 = Scalar(1.0) / (_tmp7); - const Scalar _tmp11 = 4 * _tmp4; - const Scalar _tmp12 = 2 * _tmp1; - const Scalar _tmp13 = std::pow(_tmp7, Scalar(2)); - const Scalar _tmp14 = _tmp5 / _tmp13; - const Scalar _tmp15 = _tmp13 / (_tmp13 + std::pow(_tmp5, Scalar(2))); - const Scalar _tmp16 = _tmp15 * (_tmp10 * (-_tmp8 * state(3, 0) + _tmp9 * state(0, 0)) - - _tmp14 * (-_tmp11 * state(3, 0) - _tmp12 * state(0, 0))); - const Scalar _tmp17 = _tmp12 * _tmp14; - const Scalar _tmp18 = _tmp10 * _tmp9; - const Scalar _tmp19 = _tmp15 * (_tmp17 * state(3, 0) + _tmp18 * state(3, 0)); - const Scalar _tmp20 = - _tmp15 * (-_tmp14 * (-_tmp11 * state(2, 0) + _tmp12 * state(1, 0)) + _tmp18 * state(1, 0)); - const Scalar _tmp21 = - _tmp15 * (_tmp10 * (-_tmp8 * state(1, 0) + _tmp9 * state(2, 0)) - _tmp17 * state(2, 0)); + // Intermediate terms (28) + const Scalar _tmp0 = std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp1 = std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp2 = 1 - 2 * _tmp1; + const Scalar _tmp3 = std::sin(antenna_yaw_offset); + const Scalar _tmp4 = 2 * state(0, 0); + const Scalar _tmp5 = _tmp4 * state(3, 0); + const Scalar _tmp6 = 2 * state(2, 0); + const Scalar _tmp7 = _tmp6 * state(1, 0); + const Scalar _tmp8 = std::cos(antenna_yaw_offset); + const Scalar _tmp9 = _tmp3 * (-2 * _tmp0 + _tmp2) + _tmp8 * (_tmp5 + _tmp7); + const Scalar _tmp10 = std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp11 = -_tmp5; + const Scalar _tmp12 = _tmp11 + _tmp7; + const Scalar _tmp13 = _tmp12 * _tmp3 + _tmp8 * (-2 * _tmp10 + _tmp2); + const Scalar _tmp14 = _tmp13 + epsilon * ((((_tmp13) > 0) - ((_tmp13) < 0)) + Scalar(0.5)); + const Scalar _tmp15 = _tmp6 * state(0, 0); + const Scalar _tmp16 = 2 * state(1, 0) * state(3, 0); + const Scalar _tmp17 = std::pow(_tmp14, Scalar(2)); + const Scalar _tmp18 = _tmp9 / _tmp17; + const Scalar _tmp19 = _tmp6 * state(3, 0); + const Scalar _tmp20 = _tmp4 * state(1, 0); + const Scalar _tmp21 = Scalar(1.0) / (_tmp14); + const Scalar _tmp22 = _tmp17 / (_tmp17 + std::pow(_tmp9, Scalar(2))); + const Scalar _tmp23 = + _tmp22 * (-_tmp18 * _tmp8 * (-_tmp15 - _tmp16) + _tmp21 * _tmp8 * (-_tmp19 + _tmp20)); + const Scalar _tmp24 = std::pow(state(0, 0), Scalar(2)); + const Scalar _tmp25 = -_tmp0 + _tmp10; + const Scalar _tmp26 = + _tmp22 * (-_tmp18 * (_tmp12 * _tmp8 + _tmp3 * (_tmp1 - _tmp24 + _tmp25)) + + _tmp21 * (_tmp3 * (_tmp11 - _tmp7) + _tmp8 * (-_tmp1 + _tmp24 + _tmp25))); + const Scalar _tmp27 = + _tmp22 * (-_tmp18 * _tmp3 * (_tmp15 + _tmp16) + _tmp21 * _tmp3 * (_tmp19 - _tmp20)); // Output terms (3) if (meas_pred != nullptr) { Scalar& _meas_pred = (*meas_pred); - _meas_pred = std::atan2(_tmp5, _tmp7); + _meas_pred = std::atan2(_tmp9, _tmp14); } if (innov_var != nullptr) { Scalar& _innov_var = (*innov_var); - _innov_var = - R + _tmp16 * (P(0, 3) * _tmp19 + P(1, 3) * _tmp21 + P(2, 3) * _tmp20 + P(3, 3) * _tmp16) + - _tmp19 * (P(0, 0) * _tmp19 + P(1, 0) * _tmp21 + P(2, 0) * _tmp20 + P(3, 0) * _tmp16) + - _tmp20 * (P(0, 2) * _tmp19 + P(1, 2) * _tmp21 + P(2, 2) * _tmp20 + P(3, 2) * _tmp16) + - _tmp21 * (P(0, 1) * _tmp19 + P(1, 1) * _tmp21 + P(2, 1) * _tmp20 + P(3, 1) * _tmp16); + _innov_var = R + _tmp23 * (P(0, 1) * _tmp27 + P(1, 1) * _tmp23 + P(2, 1) * _tmp26) + + _tmp26 * (P(0, 2) * _tmp27 + P(1, 2) * _tmp23 + P(2, 2) * _tmp26) + + _tmp27 * (P(0, 0) * _tmp27 + P(1, 0) * _tmp23 + P(2, 0) * _tmp26); } if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); - _h(0, 0) = _tmp19; - _h(1, 0) = _tmp21; - _h(2, 0) = _tmp20; - _h(3, 0) = _tmp16; + _h(0, 0) = _tmp27; + _h(1, 0) = _tmp23; + _h(2, 0) = _tmp26; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_innov_var_and_k_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_innov_var_and_k_and_h.h index a64929958aa5..2ac6d93aa3e6 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_innov_var_and_k_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_gravity_innov_var_and_k_and_h.h @@ -17,7 +17,7 @@ namespace sym { * * Args: * state: Matrix24_1 - * P: Matrix24_24 + * P: Matrix23_23 * meas: Matrix31 * R: Scalar * epsilon: Scalar @@ -25,206 +25,165 @@ namespace sym { * Outputs: * innov: Matrix31 * innov_var: Matrix31 - * Kx: Matrix24_1 - * Ky: Matrix24_1 - * Kz: Matrix24_1 + * Kx: Matrix23_1 + * Ky: Matrix23_1 + * Kz: Matrix23_1 */ template void ComputeGravityInnovVarAndKAndH(const matrix::Matrix& state, - const matrix::Matrix& P, + const matrix::Matrix& P, const matrix::Matrix& meas, const Scalar R, const Scalar epsilon, matrix::Matrix* const innov = nullptr, matrix::Matrix* const innov_var = nullptr, - matrix::Matrix* const Kx = nullptr, - matrix::Matrix* const Ky = nullptr, - matrix::Matrix* const Kz = nullptr) { - // Total ops: 617 + matrix::Matrix* const Kx = nullptr, + matrix::Matrix* const Ky = nullptr, + matrix::Matrix* const Kz = nullptr) { + // Total ops: 361 // Input arrays - // Intermediate terms (34) + // Intermediate terms (31) const Scalar _tmp0 = 2 * state(2, 0); - const Scalar _tmp1 = 2 * state(1, 0); - const Scalar _tmp2 = + const Scalar _tmp1 = _tmp0 * state(0, 0); + const Scalar _tmp2 = 2 * state(1, 0); + const Scalar _tmp3 = _tmp2 * state(3, 0); + const Scalar _tmp4 = -_tmp1 + _tmp3; + const Scalar _tmp5 = Scalar(9.8066499999999994) / std::sqrt(Scalar(epsilon + std::pow(meas(0, 0), Scalar(2)) + std::pow(meas(1, 0), Scalar(2)) + std::pow(meas(2, 0), Scalar(2)))); - const Scalar _tmp3 = Scalar(19.613299999999999) * state(1, 0); - const Scalar _tmp4 = -P(3, 0) * _tmp3; - const Scalar _tmp5 = Scalar(19.613299999999999) * state(2, 0); - const Scalar _tmp6 = P(0, 0) * _tmp5; - const Scalar _tmp7 = Scalar(19.613299999999999) * state(0, 0); - const Scalar _tmp8 = Scalar(19.613299999999999) * state(3, 0); - const Scalar _tmp9 = P(2, 1) * _tmp7; - const Scalar _tmp10 = -P(1, 1) * _tmp8; - const Scalar _tmp11 = P(2, 2) * _tmp7; - const Scalar _tmp12 = -P(1, 2) * _tmp8; - const Scalar _tmp13 = -P(3, 3) * _tmp3; - const Scalar _tmp14 = P(0, 3) * _tmp5; - const Scalar _tmp15 = R - _tmp3 * (-P(1, 3) * _tmp8 + P(2, 3) * _tmp7 + _tmp13 + _tmp14) + - _tmp5 * (-P(1, 0) * _tmp8 + P(2, 0) * _tmp7 + _tmp4 + _tmp6) + - _tmp7 * (P(0, 2) * _tmp5 - P(3, 2) * _tmp3 + _tmp11 + _tmp12) - - _tmp8 * (P(0, 1) * _tmp5 - P(3, 1) * _tmp3 + _tmp10 + _tmp9); - const Scalar _tmp16 = P(3, 0) * _tmp5; - const Scalar _tmp17 = -P(0, 0) * _tmp3; - const Scalar _tmp18 = -P(2, 2) * _tmp8; - const Scalar _tmp19 = P(1, 2) * _tmp7; - const Scalar _tmp20 = -P(2, 1) * _tmp8; - const Scalar _tmp21 = -P(1, 1) * _tmp7; - const Scalar _tmp22 = -P(3, 3) * _tmp5; - const Scalar _tmp23 = -P(0, 3) * _tmp3; - const Scalar _tmp24 = R - _tmp3 * (-P(1, 0) * _tmp7 - P(2, 0) * _tmp8 - _tmp16 + _tmp17) - - _tmp5 * (-P(1, 3) * _tmp7 - P(2, 3) * _tmp8 + _tmp22 + _tmp23) - - _tmp7 * (-P(0, 1) * _tmp3 - P(3, 1) * _tmp5 + _tmp20 + _tmp21) - - _tmp8 * (-P(0, 2) * _tmp3 - P(3, 2) * _tmp5 + _tmp18 - _tmp19); - const Scalar _tmp25 = Scalar(39.226599999999998) * state(2, 0); - const Scalar _tmp26 = P(2, 2) * _tmp25; - const Scalar _tmp27 = Scalar(39.226599999999998) * state(1, 0); - const Scalar _tmp28 = P(1, 1) * _tmp27; - const Scalar _tmp29 = - R + _tmp25 * (P(1, 2) * _tmp27 + _tmp26) + _tmp27 * (P(2, 1) * _tmp25 + _tmp28); - const Scalar _tmp30 = Scalar(1.0) / (_tmp15); - const Scalar _tmp31 = Scalar(19.613299999999999) * P(6, 3); - const Scalar _tmp32 = Scalar(1.0) / (_tmp24); - const Scalar _tmp33 = Scalar(1.0) / (_tmp29); + const Scalar _tmp6 = _tmp0 * state(3, 0); + const Scalar _tmp7 = _tmp2 * state(0, 0); + const Scalar _tmp8 = _tmp6 + _tmp7; + const Scalar _tmp9 = std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp10 = std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp11 = std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp12 = std::pow(state(0, 0), Scalar(2)); + const Scalar _tmp13 = -Scalar(9.8066499999999994) * _tmp10 + Scalar(9.8066499999999994) * _tmp11 + + Scalar(9.8066499999999994) * _tmp12 - Scalar(9.8066499999999994) * _tmp9; + const Scalar _tmp14 = -Scalar(9.8066499999999994) * _tmp8; + const Scalar _tmp15 = P(2, 2) * _tmp14; + const Scalar _tmp16 = P(1, 1) * _tmp13; + const Scalar _tmp17 = + R + _tmp13 * (P(2, 1) * _tmp14 + _tmp16) + _tmp14 * (P(1, 2) * _tmp13 + _tmp15); + const Scalar _tmp18 = Scalar(9.8066499999999994) * _tmp10 - Scalar(9.8066499999999994) * _tmp11 - + Scalar(9.8066499999999994) * _tmp12 + Scalar(9.8066499999999994) * _tmp9; + const Scalar _tmp19 = -Scalar(9.8066499999999994) * _tmp1 + Scalar(9.8066499999999994) * _tmp3; + const Scalar _tmp20 = P(2, 2) * _tmp19; + const Scalar _tmp21 = P(0, 0) * _tmp18; + const Scalar _tmp22 = + R + _tmp18 * (P(2, 0) * _tmp19 + _tmp21) + _tmp19 * (P(0, 2) * _tmp18 + _tmp20); + const Scalar _tmp23 = Scalar(9.8066499999999994) * _tmp6 + Scalar(9.8066499999999994) * _tmp7; + const Scalar _tmp24 = -Scalar(9.8066499999999994) * _tmp4; + const Scalar _tmp25 = P(1, 1) * _tmp24; + const Scalar _tmp26 = P(0, 0) * _tmp23; + const Scalar _tmp27 = + R + _tmp23 * (P(1, 0) * _tmp24 + _tmp26) + _tmp24 * (P(0, 1) * _tmp23 + _tmp25); + const Scalar _tmp28 = Scalar(1.0) / (_tmp17); + const Scalar _tmp29 = Scalar(1.0) / (_tmp22); + const Scalar _tmp30 = Scalar(1.0) / (_tmp27); // Output terms (5) if (innov != nullptr) { matrix::Matrix& _innov = (*innov); - _innov(0, 0) = Scalar(9.8066499999999994) * _tmp0 * state(0, 0) - - Scalar(9.8066499999999994) * _tmp1 * state(3, 0) - _tmp2 * meas(0, 0); - _innov(1, 0) = -Scalar(9.8066499999999994) * _tmp0 * state(3, 0) - - Scalar(9.8066499999999994) * _tmp1 * state(0, 0) - _tmp2 * meas(1, 0); - _innov(2, 0) = - -_tmp2 * meas(2, 0) + Scalar(19.613299999999999) * std::pow(state(1, 0), Scalar(2)) + - Scalar(19.613299999999999) * std::pow(state(2, 0), Scalar(2)) + Scalar(-9.8066499999999994); + _innov(0, 0) = -Scalar(9.8066499999999994) * _tmp4 - _tmp5 * meas(0, 0); + _innov(1, 0) = -_tmp5 * meas(1, 0) - Scalar(9.8066499999999994) * _tmp8; + _innov(2, 0) = Scalar(19.613299999999999) * _tmp10 - _tmp5 * meas(2, 0) + + Scalar(19.613299999999999) * _tmp9 + Scalar(-9.8066499999999994); } if (innov_var != nullptr) { matrix::Matrix& _innov_var = (*innov_var); - _innov_var(0, 0) = _tmp15; - _innov_var(1, 0) = _tmp24; - _innov_var(2, 0) = _tmp29; + _innov_var(0, 0) = _tmp17; + _innov_var(1, 0) = _tmp22; + _innov_var(2, 0) = _tmp27; } if (Kx != nullptr) { - matrix::Matrix& _kx = (*Kx); - - _kx(0, 0) = _tmp30 * (-P(0, 1) * _tmp8 + P(0, 2) * _tmp7 + _tmp23 + _tmp6); - _kx(1, 0) = _tmp30 * (P(1, 0) * _tmp5 - P(1, 3) * _tmp3 + _tmp10 + _tmp19); - _kx(2, 0) = _tmp30 * (P(2, 0) * _tmp5 - P(2, 3) * _tmp3 + _tmp11 + _tmp20); - _kx(3, 0) = _tmp30 * (-P(3, 1) * _tmp8 + P(3, 2) * _tmp7 + _tmp13 + _tmp16); - _kx(4, 0) = _tmp30 * (P(4, 0) * _tmp5 - P(4, 1) * _tmp8 + P(4, 2) * _tmp7 - P(4, 3) * _tmp3); - _kx(5, 0) = _tmp30 * (P(5, 0) * _tmp5 - P(5, 1) * _tmp8 + P(5, 2) * _tmp7 - P(5, 3) * _tmp3); - _kx(6, 0) = - _tmp30 * (P(6, 0) * _tmp5 - P(6, 1) * _tmp8 + P(6, 2) * _tmp7 - _tmp31 * state(1, 0)); - _kx(7, 0) = _tmp30 * (P(7, 0) * _tmp5 - P(7, 1) * _tmp8 + P(7, 2) * _tmp7 - P(7, 3) * _tmp3); - _kx(8, 0) = _tmp30 * (P(8, 0) * _tmp5 - P(8, 1) * _tmp8 + P(8, 2) * _tmp7 - P(8, 3) * _tmp3); - _kx(9, 0) = _tmp30 * (P(9, 0) * _tmp5 - P(9, 1) * _tmp8 + P(9, 2) * _tmp7 - P(9, 3) * _tmp3); - _kx(10, 0) = - _tmp30 * (P(10, 0) * _tmp5 - P(10, 1) * _tmp8 + P(10, 2) * _tmp7 - P(10, 3) * _tmp3); - _kx(11, 0) = - _tmp30 * (P(11, 0) * _tmp5 - P(11, 1) * _tmp8 + P(11, 2) * _tmp7 - P(11, 3) * _tmp3); - _kx(12, 0) = - _tmp30 * (P(12, 0) * _tmp5 - P(12, 1) * _tmp8 + P(12, 2) * _tmp7 - P(12, 3) * _tmp3); - _kx(13, 0) = - _tmp30 * (P(13, 0) * _tmp5 - P(13, 1) * _tmp8 + P(13, 2) * _tmp7 - P(13, 3) * _tmp3); - _kx(14, 0) = - _tmp30 * (P(14, 0) * _tmp5 - P(14, 1) * _tmp8 + P(14, 2) * _tmp7 - P(14, 3) * _tmp3); - _kx(15, 0) = - _tmp30 * (P(15, 0) * _tmp5 - P(15, 1) * _tmp8 + P(15, 2) * _tmp7 - P(15, 3) * _tmp3); - _kx(16, 0) = - _tmp30 * (P(16, 0) * _tmp5 - P(16, 1) * _tmp8 + P(16, 2) * _tmp7 - P(16, 3) * _tmp3); - _kx(17, 0) = - _tmp30 * (P(17, 0) * _tmp5 - P(17, 1) * _tmp8 + P(17, 2) * _tmp7 - P(17, 3) * _tmp3); - _kx(18, 0) = - _tmp30 * (P(18, 0) * _tmp5 - P(18, 1) * _tmp8 + P(18, 2) * _tmp7 - P(18, 3) * _tmp3); - _kx(19, 0) = - _tmp30 * (P(19, 0) * _tmp5 - P(19, 1) * _tmp8 + P(19, 2) * _tmp7 - P(19, 3) * _tmp3); - _kx(20, 0) = - _tmp30 * (P(20, 0) * _tmp5 - P(20, 1) * _tmp8 + P(20, 2) * _tmp7 - P(20, 3) * _tmp3); - _kx(21, 0) = - _tmp30 * (P(21, 0) * _tmp5 - P(21, 1) * _tmp8 + P(21, 2) * _tmp7 - P(21, 3) * _tmp3); - _kx(22, 0) = - _tmp30 * (P(22, 0) * _tmp5 - P(22, 1) * _tmp8 + P(22, 2) * _tmp7 - P(22, 3) * _tmp3); - _kx(23, 0) = - _tmp30 * (P(23, 0) * _tmp5 - P(23, 1) * _tmp8 + P(23, 2) * _tmp7 - P(23, 3) * _tmp3); + matrix::Matrix& _kx = (*Kx); + + _kx(0, 0) = _tmp28 * (P(0, 1) * _tmp13 + P(0, 2) * _tmp14); + _kx(1, 0) = _tmp28 * (P(1, 2) * _tmp14 + _tmp16); + _kx(2, 0) = _tmp28 * (P(2, 1) * _tmp13 + _tmp15); + _kx(3, 0) = _tmp28 * (P(3, 1) * _tmp13 + P(3, 2) * _tmp14); + _kx(4, 0) = _tmp28 * (P(4, 1) * _tmp13 + P(4, 2) * _tmp14); + _kx(5, 0) = _tmp28 * (P(5, 1) * _tmp13 + P(5, 2) * _tmp14); + _kx(6, 0) = _tmp28 * (P(6, 1) * _tmp13 + P(6, 2) * _tmp14); + _kx(7, 0) = _tmp28 * (P(7, 1) * _tmp13 + P(7, 2) * _tmp14); + _kx(8, 0) = _tmp28 * (P(8, 1) * _tmp13 + P(8, 2) * _tmp14); + _kx(9, 0) = _tmp28 * (P(9, 1) * _tmp13 + P(9, 2) * _tmp14); + _kx(10, 0) = _tmp28 * (P(10, 1) * _tmp13 + P(10, 2) * _tmp14); + _kx(11, 0) = _tmp28 * (P(11, 1) * _tmp13 + P(11, 2) * _tmp14); + _kx(12, 0) = _tmp28 * (P(12, 1) * _tmp13 + P(12, 2) * _tmp14); + _kx(13, 0) = _tmp28 * (P(13, 1) * _tmp13 + P(13, 2) * _tmp14); + _kx(14, 0) = _tmp28 * (P(14, 1) * _tmp13 + P(14, 2) * _tmp14); + _kx(15, 0) = _tmp28 * (P(15, 1) * _tmp13 + P(15, 2) * _tmp14); + _kx(16, 0) = _tmp28 * (P(16, 1) * _tmp13 + P(16, 2) * _tmp14); + _kx(17, 0) = _tmp28 * (P(17, 1) * _tmp13 + P(17, 2) * _tmp14); + _kx(18, 0) = _tmp28 * (P(18, 1) * _tmp13 + P(18, 2) * _tmp14); + _kx(19, 0) = _tmp28 * (P(19, 1) * _tmp13 + P(19, 2) * _tmp14); + _kx(20, 0) = _tmp28 * (P(20, 1) * _tmp13 + P(20, 2) * _tmp14); + _kx(21, 0) = _tmp28 * (P(21, 1) * _tmp13 + P(21, 2) * _tmp14); + _kx(22, 0) = _tmp28 * (P(22, 1) * _tmp13 + P(22, 2) * _tmp14); } if (Ky != nullptr) { - matrix::Matrix& _ky = (*Ky); - - _ky(0, 0) = _tmp32 * (-P(0, 1) * _tmp7 - P(0, 2) * _tmp8 - _tmp14 + _tmp17); - _ky(1, 0) = _tmp32 * (-P(1, 0) * _tmp3 - P(1, 3) * _tmp5 + _tmp12 + _tmp21); - _ky(2, 0) = _tmp32 * (-P(2, 0) * _tmp3 - P(2, 3) * _tmp5 + _tmp18 - _tmp9); - _ky(3, 0) = _tmp32 * (-P(3, 1) * _tmp7 - P(3, 2) * _tmp8 + _tmp22 + _tmp4); - _ky(4, 0) = _tmp32 * (-P(4, 0) * _tmp3 - P(4, 1) * _tmp7 - P(4, 2) * _tmp8 - P(4, 3) * _tmp5); - _ky(5, 0) = _tmp32 * (-P(5, 0) * _tmp3 - P(5, 1) * _tmp7 - P(5, 2) * _tmp8 - P(5, 3) * _tmp5); - _ky(6, 0) = - _tmp32 * (-P(6, 0) * _tmp3 - P(6, 1) * _tmp7 - P(6, 2) * _tmp8 - _tmp31 * state(2, 0)); - _ky(7, 0) = _tmp32 * (-P(7, 0) * _tmp3 - P(7, 1) * _tmp7 - P(7, 2) * _tmp8 - P(7, 3) * _tmp5); - _ky(8, 0) = _tmp32 * (-P(8, 0) * _tmp3 - P(8, 1) * _tmp7 - P(8, 2) * _tmp8 - P(8, 3) * _tmp5); - _ky(9, 0) = _tmp32 * (-P(9, 0) * _tmp3 - P(9, 1) * _tmp7 - P(9, 2) * _tmp8 - P(9, 3) * _tmp5); - _ky(10, 0) = - _tmp32 * (-P(10, 0) * _tmp3 - P(10, 1) * _tmp7 - P(10, 2) * _tmp8 - P(10, 3) * _tmp5); - _ky(11, 0) = - _tmp32 * (-P(11, 0) * _tmp3 - P(11, 1) * _tmp7 - P(11, 2) * _tmp8 - P(11, 3) * _tmp5); - _ky(12, 0) = - _tmp32 * (-P(12, 0) * _tmp3 - P(12, 1) * _tmp7 - P(12, 2) * _tmp8 - P(12, 3) * _tmp5); - _ky(13, 0) = - _tmp32 * (-P(13, 0) * _tmp3 - P(13, 1) * _tmp7 - P(13, 2) * _tmp8 - P(13, 3) * _tmp5); - _ky(14, 0) = - _tmp32 * (-P(14, 0) * _tmp3 - P(14, 1) * _tmp7 - P(14, 2) * _tmp8 - P(14, 3) * _tmp5); - _ky(15, 0) = - _tmp32 * (-P(15, 0) * _tmp3 - P(15, 1) * _tmp7 - P(15, 2) * _tmp8 - P(15, 3) * _tmp5); - _ky(16, 0) = - _tmp32 * (-P(16, 0) * _tmp3 - P(16, 1) * _tmp7 - P(16, 2) * _tmp8 - P(16, 3) * _tmp5); - _ky(17, 0) = - _tmp32 * (-P(17, 0) * _tmp3 - P(17, 1) * _tmp7 - P(17, 2) * _tmp8 - P(17, 3) * _tmp5); - _ky(18, 0) = - _tmp32 * (-P(18, 0) * _tmp3 - P(18, 1) * _tmp7 - P(18, 2) * _tmp8 - P(18, 3) * _tmp5); - _ky(19, 0) = - _tmp32 * (-P(19, 0) * _tmp3 - P(19, 1) * _tmp7 - P(19, 2) * _tmp8 - P(19, 3) * _tmp5); - _ky(20, 0) = - _tmp32 * (-P(20, 0) * _tmp3 - P(20, 1) * _tmp7 - P(20, 2) * _tmp8 - P(20, 3) * _tmp5); - _ky(21, 0) = - _tmp32 * (-P(21, 0) * _tmp3 - P(21, 1) * _tmp7 - P(21, 2) * _tmp8 - P(21, 3) * _tmp5); - _ky(22, 0) = - _tmp32 * (-P(22, 0) * _tmp3 - P(22, 1) * _tmp7 - P(22, 2) * _tmp8 - P(22, 3) * _tmp5); - _ky(23, 0) = - _tmp32 * (-P(23, 0) * _tmp3 - P(23, 1) * _tmp7 - P(23, 2) * _tmp8 - P(23, 3) * _tmp5); + matrix::Matrix& _ky = (*Ky); + + _ky(0, 0) = _tmp29 * (P(0, 2) * _tmp19 + _tmp21); + _ky(1, 0) = _tmp29 * (P(1, 0) * _tmp18 + P(1, 2) * _tmp19); + _ky(2, 0) = _tmp29 * (P(2, 0) * _tmp18 + _tmp20); + _ky(3, 0) = _tmp29 * (P(3, 0) * _tmp18 + P(3, 2) * _tmp19); + _ky(4, 0) = _tmp29 * (P(4, 0) * _tmp18 + P(4, 2) * _tmp19); + _ky(5, 0) = _tmp29 * (P(5, 0) * _tmp18 + P(5, 2) * _tmp19); + _ky(6, 0) = _tmp29 * (P(6, 0) * _tmp18 + P(6, 2) * _tmp19); + _ky(7, 0) = _tmp29 * (P(7, 0) * _tmp18 + P(7, 2) * _tmp19); + _ky(8, 0) = _tmp29 * (P(8, 0) * _tmp18 + P(8, 2) * _tmp19); + _ky(9, 0) = _tmp29 * (P(9, 0) * _tmp18 + P(9, 2) * _tmp19); + _ky(10, 0) = _tmp29 * (P(10, 0) * _tmp18 + P(10, 2) * _tmp19); + _ky(11, 0) = _tmp29 * (P(11, 0) * _tmp18 + P(11, 2) * _tmp19); + _ky(12, 0) = _tmp29 * (P(12, 0) * _tmp18 + P(12, 2) * _tmp19); + _ky(13, 0) = _tmp29 * (P(13, 0) * _tmp18 + P(13, 2) * _tmp19); + _ky(14, 0) = _tmp29 * (P(14, 0) * _tmp18 + P(14, 2) * _tmp19); + _ky(15, 0) = _tmp29 * (P(15, 0) * _tmp18 + P(15, 2) * _tmp19); + _ky(16, 0) = _tmp29 * (P(16, 0) * _tmp18 + P(16, 2) * _tmp19); + _ky(17, 0) = _tmp29 * (P(17, 0) * _tmp18 + P(17, 2) * _tmp19); + _ky(18, 0) = _tmp29 * (P(18, 0) * _tmp18 + P(18, 2) * _tmp19); + _ky(19, 0) = _tmp29 * (P(19, 0) * _tmp18 + P(19, 2) * _tmp19); + _ky(20, 0) = _tmp29 * (P(20, 0) * _tmp18 + P(20, 2) * _tmp19); + _ky(21, 0) = _tmp29 * (P(21, 0) * _tmp18 + P(21, 2) * _tmp19); + _ky(22, 0) = _tmp29 * (P(22, 0) * _tmp18 + P(22, 2) * _tmp19); } if (Kz != nullptr) { - matrix::Matrix& _kz = (*Kz); - - _kz(0, 0) = _tmp33 * (P(0, 1) * _tmp27 + P(0, 2) * _tmp25); - _kz(1, 0) = _tmp33 * (P(1, 2) * _tmp25 + _tmp28); - _kz(2, 0) = _tmp33 * (P(2, 1) * _tmp27 + _tmp26); - _kz(3, 0) = _tmp33 * (P(3, 1) * _tmp27 + P(3, 2) * _tmp25); - _kz(4, 0) = _tmp33 * (P(4, 1) * _tmp27 + P(4, 2) * _tmp25); - _kz(5, 0) = _tmp33 * (P(5, 1) * _tmp27 + P(5, 2) * _tmp25); - _kz(6, 0) = _tmp33 * (P(6, 1) * _tmp27 + P(6, 2) * _tmp25); - _kz(7, 0) = _tmp33 * (P(7, 1) * _tmp27 + P(7, 2) * _tmp25); - _kz(8, 0) = _tmp33 * (P(8, 1) * _tmp27 + P(8, 2) * _tmp25); - _kz(9, 0) = _tmp33 * (P(9, 1) * _tmp27 + P(9, 2) * _tmp25); - _kz(10, 0) = _tmp33 * (P(10, 1) * _tmp27 + P(10, 2) * _tmp25); - _kz(11, 0) = _tmp33 * (P(11, 1) * _tmp27 + P(11, 2) * _tmp25); - _kz(12, 0) = _tmp33 * (P(12, 1) * _tmp27 + P(12, 2) * _tmp25); - _kz(13, 0) = _tmp33 * (P(13, 1) * _tmp27 + P(13, 2) * _tmp25); - _kz(14, 0) = _tmp33 * (P(14, 1) * _tmp27 + P(14, 2) * _tmp25); - _kz(15, 0) = _tmp33 * (P(15, 1) * _tmp27 + P(15, 2) * _tmp25); - _kz(16, 0) = _tmp33 * (P(16, 1) * _tmp27 + P(16, 2) * _tmp25); - _kz(17, 0) = _tmp33 * (P(17, 1) * _tmp27 + P(17, 2) * _tmp25); - _kz(18, 0) = _tmp33 * (P(18, 1) * _tmp27 + P(18, 2) * _tmp25); - _kz(19, 0) = _tmp33 * (P(19, 1) * _tmp27 + P(19, 2) * _tmp25); - _kz(20, 0) = _tmp33 * (P(20, 1) * _tmp27 + P(20, 2) * _tmp25); - _kz(21, 0) = _tmp33 * (P(21, 1) * _tmp27 + P(21, 2) * _tmp25); - _kz(22, 0) = _tmp33 * (P(22, 1) * _tmp27 + P(22, 2) * _tmp25); - _kz(23, 0) = _tmp33 * (P(23, 1) * _tmp27 + P(23, 2) * _tmp25); + matrix::Matrix& _kz = (*Kz); + + _kz(0, 0) = _tmp30 * (P(0, 1) * _tmp24 + _tmp26); + _kz(1, 0) = _tmp30 * (P(1, 0) * _tmp23 + _tmp25); + _kz(2, 0) = _tmp30 * (P(2, 0) * _tmp23 + P(2, 1) * _tmp24); + _kz(3, 0) = _tmp30 * (P(3, 0) * _tmp23 + P(3, 1) * _tmp24); + _kz(4, 0) = _tmp30 * (P(4, 0) * _tmp23 + P(4, 1) * _tmp24); + _kz(5, 0) = _tmp30 * (P(5, 0) * _tmp23 + P(5, 1) * _tmp24); + _kz(6, 0) = _tmp30 * (P(6, 0) * _tmp23 + P(6, 1) * _tmp24); + _kz(7, 0) = _tmp30 * (P(7, 0) * _tmp23 + P(7, 1) * _tmp24); + _kz(8, 0) = _tmp30 * (P(8, 0) * _tmp23 + P(8, 1) * _tmp24); + _kz(9, 0) = _tmp30 * (P(9, 0) * _tmp23 + P(9, 1) * _tmp24); + _kz(10, 0) = _tmp30 * (P(10, 0) * _tmp23 + P(10, 1) * _tmp24); + _kz(11, 0) = _tmp30 * (P(11, 0) * _tmp23 + P(11, 1) * _tmp24); + _kz(12, 0) = _tmp30 * (P(12, 0) * _tmp23 + P(12, 1) * _tmp24); + _kz(13, 0) = _tmp30 * (P(13, 0) * _tmp23 + P(13, 1) * _tmp24); + _kz(14, 0) = _tmp30 * (P(14, 0) * _tmp23 + P(14, 1) * _tmp24); + _kz(15, 0) = _tmp30 * (P(15, 0) * _tmp23 + P(15, 1) * _tmp24); + _kz(16, 0) = _tmp30 * (P(16, 0) * _tmp23 + P(16, 1) * _tmp24); + _kz(17, 0) = _tmp30 * (P(17, 0) * _tmp23 + P(17, 1) * _tmp24); + _kz(18, 0) = _tmp30 * (P(18, 0) * _tmp23 + P(18, 1) * _tmp24); + _kz(19, 0) = _tmp30 * (P(19, 0) * _tmp23 + P(19, 1) * _tmp24); + _kz(20, 0) = _tmp30 * (P(20, 0) * _tmp23 + P(20, 1) * _tmp24); + _kz(21, 0) = _tmp30 * (P(21, 0) * _tmp23 + P(21, 1) * _tmp24); + _kz(22, 0) = _tmp30 * (P(22, 0) * _tmp23 + P(22, 1) * _tmp24); } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_declination_pred_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_declination_pred_innov_var_and_h.h index cb9e30854051..009892f6d9d1 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_declination_pred_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_declination_pred_innov_var_and_h.h @@ -17,21 +17,21 @@ namespace sym { * * Args: * state: Matrix24_1 - * P: Matrix24_24 + * P: Matrix23_23 * R: Scalar * epsilon: Scalar * * Outputs: * pred: Scalar * innov_var: Scalar - * H: Matrix24_1 + * H: Matrix23_1 */ template void ComputeMagDeclinationPredInnovVarAndH(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar R, + const matrix::Matrix& P, const Scalar R, const Scalar epsilon, Scalar* const pred = nullptr, Scalar* const innov_var = nullptr, - matrix::Matrix* const H = nullptr) { + matrix::Matrix* const H = nullptr) { // Total ops: 22 // Input arrays @@ -54,17 +54,17 @@ void ComputeMagDeclinationPredInnovVarAndH(const matrix::Matrix& if (innov_var != nullptr) { Scalar& _innov_var = (*innov_var); - _innov_var = R - _tmp2 * (-P(16, 16) * _tmp2 + P(17, 16) * _tmp3) + - _tmp3 * (-P(16, 17) * _tmp2 + P(17, 17) * _tmp3); + _innov_var = R - _tmp2 * (-P(15, 15) * _tmp2 + P(16, 15) * _tmp3) + + _tmp3 * (-P(15, 16) * _tmp2 + P(16, 16) * _tmp3); } if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); - _h(16, 0) = -_tmp2; - _h(17, 0) = _tmp3; + _h(15, 0) = -_tmp2; + _h(16, 0) = _tmp3; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_innov_innov_var_and_hx.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_innov_innov_var_and_hx.h index 1c63223f5dbc..dde9a8cd9ee9 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_innov_innov_var_and_hx.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_innov_innov_var_and_hx.h @@ -17,7 +17,7 @@ namespace sym { * * Args: * state: Matrix24_1 - * P: Matrix24_24 + * P: Matrix23_23 * meas: Matrix31 * R: Scalar * epsilon: Scalar @@ -25,155 +25,137 @@ namespace sym { * Outputs: * innov: Matrix31 * innov_var: Matrix31 - * Hx: Matrix24_1 + * Hx: Matrix23_1 */ template void ComputeMagInnovInnovVarAndHx(const matrix::Matrix& state, - const matrix::Matrix& P, + const matrix::Matrix& P, const matrix::Matrix& meas, const Scalar R, const Scalar epsilon, matrix::Matrix* const innov = nullptr, matrix::Matrix* const innov_var = nullptr, - matrix::Matrix* const Hx = nullptr) { - // Total ops: 471 + matrix::Matrix* const Hx = nullptr) { + // Total ops: 314 // Unused inputs (void)epsilon; // Input arrays - // Intermediate terms (49) - const Scalar _tmp0 = -2 * std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp1 = -2 * std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp2 = _tmp0 + _tmp1 + 1; - const Scalar _tmp3 = 2 * state(0, 0); - const Scalar _tmp4 = _tmp3 * state(3, 0); - const Scalar _tmp5 = 2 * state(2, 0); - const Scalar _tmp6 = _tmp5 * state(1, 0); - const Scalar _tmp7 = _tmp4 + _tmp6; - const Scalar _tmp8 = _tmp5 * state(0, 0); - const Scalar _tmp9 = 2 * state(1, 0); - const Scalar _tmp10 = _tmp9 * state(3, 0); - const Scalar _tmp11 = _tmp10 - _tmp8; - const Scalar _tmp12 = 1 - 2 * std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp13 = _tmp0 + _tmp12; - const Scalar _tmp14 = _tmp5 * state(3, 0); - const Scalar _tmp15 = _tmp3 * state(1, 0); - const Scalar _tmp16 = _tmp14 + _tmp15; - const Scalar _tmp17 = -_tmp4 + _tmp6; - const Scalar _tmp18 = _tmp1 + _tmp12; - const Scalar _tmp19 = _tmp14 - _tmp15; - const Scalar _tmp20 = _tmp10 + _tmp8; - const Scalar _tmp21 = _tmp9 * state(18, 0); - const Scalar _tmp22 = _tmp3 * state(17, 0); - const Scalar _tmp23 = _tmp21 + _tmp22 - 4 * state(16, 0) * state(3, 0); - const Scalar _tmp24 = 4 * state(2, 0); - const Scalar _tmp25 = _tmp9 * state(17, 0); - const Scalar _tmp26 = _tmp3 * state(18, 0); - const Scalar _tmp27 = -_tmp24 * state(16, 0) + _tmp25 - _tmp26; - const Scalar _tmp28 = state(17, 0) * state(3, 0); - const Scalar _tmp29 = 2 * _tmp28; - const Scalar _tmp30 = _tmp5 * state(18, 0); - const Scalar _tmp31 = _tmp29 - _tmp30; - const Scalar _tmp32 = 2 * state(3, 0); - const Scalar _tmp33 = _tmp32 * state(18, 0); - const Scalar _tmp34 = _tmp5 * state(17, 0); - const Scalar _tmp35 = _tmp33 + _tmp34; - const Scalar _tmp36 = _tmp5 * state(16, 0); - const Scalar _tmp37 = 4 * state(1, 0); - const Scalar _tmp38 = _tmp26 + _tmp36 - _tmp37 * state(17, 0); - const Scalar _tmp39 = _tmp3 * state(16, 0); - const Scalar _tmp40 = -4 * _tmp28 + _tmp30 - _tmp39; - const Scalar _tmp41 = _tmp32 * state(16, 0); - const Scalar _tmp42 = _tmp21 - _tmp41; - const Scalar _tmp43 = _tmp9 * state(16, 0); - const Scalar _tmp44 = _tmp33 + _tmp43; - const Scalar _tmp45 = -_tmp22 - _tmp37 * state(18, 0) + _tmp41; - const Scalar _tmp46 = -_tmp24 * state(18, 0) + _tmp29 + _tmp39; - const Scalar _tmp47 = _tmp34 + _tmp43; - const Scalar _tmp48 = -_tmp25 + _tmp36; + // Intermediate terms (47) + const Scalar _tmp0 = std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp1 = -2 * _tmp0; + const Scalar _tmp2 = std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp3 = -2 * _tmp2; + const Scalar _tmp4 = _tmp1 + _tmp3 + 1; + const Scalar _tmp5 = 2 * state(0, 0); + const Scalar _tmp6 = _tmp5 * state(3, 0); + const Scalar _tmp7 = 2 * state(1, 0); + const Scalar _tmp8 = _tmp7 * state(2, 0); + const Scalar _tmp9 = _tmp6 + _tmp8; + const Scalar _tmp10 = _tmp5 * state(2, 0); + const Scalar _tmp11 = -_tmp10; + const Scalar _tmp12 = _tmp7 * state(3, 0); + const Scalar _tmp13 = _tmp11 + _tmp12; + const Scalar _tmp14 = _tmp13 * state(18, 0) + _tmp9 * state(17, 0); + const Scalar _tmp15 = std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp16 = 1 - 2 * _tmp15; + const Scalar _tmp17 = _tmp1 + _tmp16; + const Scalar _tmp18 = 2 * state(2, 0) * state(3, 0); + const Scalar _tmp19 = _tmp7 * state(0, 0); + const Scalar _tmp20 = _tmp18 + _tmp19; + const Scalar _tmp21 = -_tmp6; + const Scalar _tmp22 = _tmp21 + _tmp8; + const Scalar _tmp23 = _tmp20 * state(18, 0) + _tmp22 * state(16, 0); + const Scalar _tmp24 = _tmp16 + _tmp3; + const Scalar _tmp25 = -_tmp19; + const Scalar _tmp26 = _tmp18 + _tmp25; + const Scalar _tmp27 = _tmp10 + _tmp12; + const Scalar _tmp28 = _tmp26 * state(17, 0) + _tmp27 * state(16, 0); + const Scalar _tmp29 = std::pow(state(0, 0), Scalar(2)); + const Scalar _tmp30 = -_tmp29; + const Scalar _tmp31 = _tmp2 + _tmp30; + const Scalar _tmp32 = -_tmp0; + const Scalar _tmp33 = _tmp15 + _tmp32; + const Scalar _tmp34 = -_tmp18; + const Scalar _tmp35 = -_tmp12; + const Scalar _tmp36 = state(16, 0) * (_tmp11 + _tmp35) + state(17, 0) * (_tmp19 + _tmp34) + + state(18, 0) * (_tmp31 + _tmp33); + const Scalar _tmp37 = -_tmp15; + const Scalar _tmp38 = _tmp23 + state(17, 0) * (_tmp2 + _tmp29 + _tmp32 + _tmp37); + const Scalar _tmp39 = _tmp0 + _tmp37; + const Scalar _tmp40 = -_tmp8; + const Scalar _tmp41 = state(16, 0) * (_tmp31 + _tmp39) + state(17, 0) * (_tmp21 + _tmp40) + + state(18, 0) * (_tmp10 + _tmp35); + const Scalar _tmp42 = -_tmp2; + const Scalar _tmp43 = _tmp29 + _tmp42; + const Scalar _tmp44 = _tmp28 + state(18, 0) * (_tmp39 + _tmp43); + const Scalar _tmp45 = _tmp14 + state(16, 0) * (_tmp33 + _tmp43); + const Scalar _tmp46 = state(16, 0) * (_tmp40 + _tmp6) + + state(17, 0) * (_tmp0 + _tmp15 + _tmp30 + _tmp42) + + state(18, 0) * (_tmp25 + _tmp34); // Output terms (3) if (innov != nullptr) { matrix::Matrix& _innov = (*innov); - _innov(0, 0) = _tmp11 * state(18, 0) + _tmp2 * state(16, 0) + _tmp7 * state(17, 0) - - meas(0, 0) + state(19, 0); - _innov(1, 0) = _tmp13 * state(17, 0) + _tmp16 * state(18, 0) + _tmp17 * state(16, 0) - - meas(1, 0) + state(20, 0); - _innov(2, 0) = _tmp18 * state(18, 0) + _tmp19 * state(17, 0) + _tmp20 * state(16, 0) - - meas(2, 0) + state(21, 0); + _innov(0, 0) = _tmp14 + _tmp4 * state(16, 0) - meas(0, 0) + state(19, 0); + _innov(1, 0) = _tmp17 * state(17, 0) + _tmp23 - meas(1, 0) + state(20, 0); + _innov(2, 0) = _tmp24 * state(18, 0) + _tmp28 - meas(2, 0) + state(21, 0); } if (innov_var != nullptr) { matrix::Matrix& _innov_var = (*innov_var); - _innov_var(0, 0) = - P(0, 19) * _tmp31 + P(1, 19) * _tmp35 + P(16, 19) * _tmp2 + P(17, 19) * _tmp7 + - P(18, 19) * _tmp11 + P(19, 19) + P(2, 19) * _tmp27 + P(3, 19) * _tmp23 + R + - _tmp11 * (P(0, 18) * _tmp31 + P(1, 18) * _tmp35 + P(16, 18) * _tmp2 + P(17, 18) * _tmp7 + - P(18, 18) * _tmp11 + P(19, 18) + P(2, 18) * _tmp27 + P(3, 18) * _tmp23) + - _tmp2 * (P(0, 16) * _tmp31 + P(1, 16) * _tmp35 + P(16, 16) * _tmp2 + P(17, 16) * _tmp7 + - P(18, 16) * _tmp11 + P(19, 16) + P(2, 16) * _tmp27 + P(3, 16) * _tmp23) + - _tmp23 * (P(0, 3) * _tmp31 + P(1, 3) * _tmp35 + P(16, 3) * _tmp2 + P(17, 3) * _tmp7 + - P(18, 3) * _tmp11 + P(19, 3) + P(2, 3) * _tmp27 + P(3, 3) * _tmp23) + - _tmp27 * (P(0, 2) * _tmp31 + P(1, 2) * _tmp35 + P(16, 2) * _tmp2 + P(17, 2) * _tmp7 + - P(18, 2) * _tmp11 + P(19, 2) + P(2, 2) * _tmp27 + P(3, 2) * _tmp23) + - _tmp31 * (P(0, 0) * _tmp31 + P(1, 0) * _tmp35 + P(16, 0) * _tmp2 + P(17, 0) * _tmp7 + - P(18, 0) * _tmp11 + P(19, 0) + P(2, 0) * _tmp27 + P(3, 0) * _tmp23) + - _tmp35 * (P(0, 1) * _tmp31 + P(1, 1) * _tmp35 + P(16, 1) * _tmp2 + P(17, 1) * _tmp7 + - P(18, 1) * _tmp11 + P(19, 1) + P(2, 1) * _tmp27 + P(3, 1) * _tmp23) + - _tmp7 * (P(0, 17) * _tmp31 + P(1, 17) * _tmp35 + P(16, 17) * _tmp2 + P(17, 17) * _tmp7 + - P(18, 17) * _tmp11 + P(19, 17) + P(2, 17) * _tmp27 + P(3, 17) * _tmp23); - _innov_var(1, 0) = - P(0, 20) * _tmp42 + P(1, 20) * _tmp38 + P(16, 20) * _tmp17 + P(17, 20) * _tmp13 + - P(18, 20) * _tmp16 + P(2, 20) * _tmp44 + P(20, 20) + P(3, 20) * _tmp40 + R + - _tmp13 * (P(0, 17) * _tmp42 + P(1, 17) * _tmp38 + P(16, 17) * _tmp17 + P(17, 17) * _tmp13 + - P(18, 17) * _tmp16 + P(2, 17) * _tmp44 + P(20, 17) + P(3, 17) * _tmp40) + - _tmp16 * (P(0, 18) * _tmp42 + P(1, 18) * _tmp38 + P(16, 18) * _tmp17 + P(17, 18) * _tmp13 + - P(18, 18) * _tmp16 + P(2, 18) * _tmp44 + P(20, 18) + P(3, 18) * _tmp40) + - _tmp17 * (P(0, 16) * _tmp42 + P(1, 16) * _tmp38 + P(16, 16) * _tmp17 + P(17, 16) * _tmp13 + - P(18, 16) * _tmp16 + P(2, 16) * _tmp44 + P(20, 16) + P(3, 16) * _tmp40) + - _tmp38 * (P(0, 1) * _tmp42 + P(1, 1) * _tmp38 + P(16, 1) * _tmp17 + P(17, 1) * _tmp13 + - P(18, 1) * _tmp16 + P(2, 1) * _tmp44 + P(20, 1) + P(3, 1) * _tmp40) + - _tmp40 * (P(0, 3) * _tmp42 + P(1, 3) * _tmp38 + P(16, 3) * _tmp17 + P(17, 3) * _tmp13 + - P(18, 3) * _tmp16 + P(2, 3) * _tmp44 + P(20, 3) + P(3, 3) * _tmp40) + - _tmp42 * (P(0, 0) * _tmp42 + P(1, 0) * _tmp38 + P(16, 0) * _tmp17 + P(17, 0) * _tmp13 + - P(18, 0) * _tmp16 + P(2, 0) * _tmp44 + P(20, 0) + P(3, 0) * _tmp40) + - _tmp44 * (P(0, 2) * _tmp42 + P(1, 2) * _tmp38 + P(16, 2) * _tmp17 + P(17, 2) * _tmp13 + - P(18, 2) * _tmp16 + P(2, 2) * _tmp44 + P(20, 2) + P(3, 2) * _tmp40); - _innov_var(2, 0) = - P(0, 21) * _tmp48 + P(1, 21) * _tmp45 + P(16, 21) * _tmp20 + P(17, 21) * _tmp19 + - P(18, 21) * _tmp18 + P(2, 21) * _tmp46 + P(21, 21) + P(3, 21) * _tmp47 + R + - _tmp18 * (P(0, 18) * _tmp48 + P(1, 18) * _tmp45 + P(16, 18) * _tmp20 + P(17, 18) * _tmp19 + - P(18, 18) * _tmp18 + P(2, 18) * _tmp46 + P(21, 18) + P(3, 18) * _tmp47) + - _tmp19 * (P(0, 17) * _tmp48 + P(1, 17) * _tmp45 + P(16, 17) * _tmp20 + P(17, 17) * _tmp19 + - P(18, 17) * _tmp18 + P(2, 17) * _tmp46 + P(21, 17) + P(3, 17) * _tmp47) + - _tmp20 * (P(0, 16) * _tmp48 + P(1, 16) * _tmp45 + P(16, 16) * _tmp20 + P(17, 16) * _tmp19 + - P(18, 16) * _tmp18 + P(2, 16) * _tmp46 + P(21, 16) + P(3, 16) * _tmp47) + - _tmp45 * (P(0, 1) * _tmp48 + P(1, 1) * _tmp45 + P(16, 1) * _tmp20 + P(17, 1) * _tmp19 + - P(18, 1) * _tmp18 + P(2, 1) * _tmp46 + P(21, 1) + P(3, 1) * _tmp47) + - _tmp46 * (P(0, 2) * _tmp48 + P(1, 2) * _tmp45 + P(16, 2) * _tmp20 + P(17, 2) * _tmp19 + - P(18, 2) * _tmp18 + P(2, 2) * _tmp46 + P(21, 2) + P(3, 2) * _tmp47) + - _tmp47 * (P(0, 3) * _tmp48 + P(1, 3) * _tmp45 + P(16, 3) * _tmp20 + P(17, 3) * _tmp19 + - P(18, 3) * _tmp18 + P(2, 3) * _tmp46 + P(21, 3) + P(3, 3) * _tmp47) + - _tmp48 * (P(0, 0) * _tmp48 + P(1, 0) * _tmp45 + P(16, 0) * _tmp20 + P(17, 0) * _tmp19 + - P(18, 0) * _tmp18 + P(2, 0) * _tmp46 + P(21, 0) + P(3, 0) * _tmp47); + _innov_var(0, 0) = P(1, 18) * _tmp36 + P(15, 18) * _tmp4 + P(16, 18) * _tmp9 + + P(17, 18) * _tmp13 + P(18, 18) + P(2, 18) * _tmp38 + R + + _tmp13 * (P(1, 17) * _tmp36 + P(15, 17) * _tmp4 + P(16, 17) * _tmp9 + + P(17, 17) * _tmp13 + P(18, 17) + P(2, 17) * _tmp38) + + _tmp36 * (P(1, 1) * _tmp36 + P(15, 1) * _tmp4 + P(16, 1) * _tmp9 + + P(17, 1) * _tmp13 + P(18, 1) + P(2, 1) * _tmp38) + + _tmp38 * (P(1, 2) * _tmp36 + P(15, 2) * _tmp4 + P(16, 2) * _tmp9 + + P(17, 2) * _tmp13 + P(18, 2) + P(2, 2) * _tmp38) + + _tmp4 * (P(1, 15) * _tmp36 + P(15, 15) * _tmp4 + P(16, 15) * _tmp9 + + P(17, 15) * _tmp13 + P(18, 15) + P(2, 15) * _tmp38) + + _tmp9 * (P(1, 16) * _tmp36 + P(15, 16) * _tmp4 + P(16, 16) * _tmp9 + + P(17, 16) * _tmp13 + P(18, 16) + P(2, 16) * _tmp38); + _innov_var(1, 0) = P(0, 19) * _tmp44 + P(15, 19) * _tmp22 + P(16, 19) * _tmp17 + + P(17, 19) * _tmp20 + P(19, 19) + P(2, 19) * _tmp41 + R + + _tmp17 * (P(0, 16) * _tmp44 + P(15, 16) * _tmp22 + P(16, 16) * _tmp17 + + P(17, 16) * _tmp20 + P(19, 16) + P(2, 16) * _tmp41) + + _tmp20 * (P(0, 17) * _tmp44 + P(15, 17) * _tmp22 + P(16, 17) * _tmp17 + + P(17, 17) * _tmp20 + P(19, 17) + P(2, 17) * _tmp41) + + _tmp22 * (P(0, 15) * _tmp44 + P(15, 15) * _tmp22 + P(16, 15) * _tmp17 + + P(17, 15) * _tmp20 + P(19, 15) + P(2, 15) * _tmp41) + + _tmp41 * (P(0, 2) * _tmp44 + P(15, 2) * _tmp22 + P(16, 2) * _tmp17 + + P(17, 2) * _tmp20 + P(19, 2) + P(2, 2) * _tmp41) + + _tmp44 * (P(0, 0) * _tmp44 + P(15, 0) * _tmp22 + P(16, 0) * _tmp17 + + P(17, 0) * _tmp20 + P(19, 0) + P(2, 0) * _tmp41); + _innov_var(2, 0) = P(0, 20) * _tmp46 + P(1, 20) * _tmp45 + P(15, 20) * _tmp27 + + P(16, 20) * _tmp26 + P(17, 20) * _tmp24 + P(20, 20) + R + + _tmp24 * (P(0, 17) * _tmp46 + P(1, 17) * _tmp45 + P(15, 17) * _tmp27 + + P(16, 17) * _tmp26 + P(17, 17) * _tmp24 + P(20, 17)) + + _tmp26 * (P(0, 16) * _tmp46 + P(1, 16) * _tmp45 + P(15, 16) * _tmp27 + + P(16, 16) * _tmp26 + P(17, 16) * _tmp24 + P(20, 16)) + + _tmp27 * (P(0, 15) * _tmp46 + P(1, 15) * _tmp45 + P(15, 15) * _tmp27 + + P(16, 15) * _tmp26 + P(17, 15) * _tmp24 + P(20, 15)) + + _tmp45 * (P(0, 1) * _tmp46 + P(1, 1) * _tmp45 + P(15, 1) * _tmp27 + + P(16, 1) * _tmp26 + P(17, 1) * _tmp24 + P(20, 1)) + + _tmp46 * (P(0, 0) * _tmp46 + P(1, 0) * _tmp45 + P(15, 0) * _tmp27 + + P(16, 0) * _tmp26 + P(17, 0) * _tmp24 + P(20, 0)); } if (Hx != nullptr) { - matrix::Matrix& _hx = (*Hx); + matrix::Matrix& _hx = (*Hx); _hx.setZero(); - _hx(0, 0) = _tmp31; - _hx(1, 0) = _tmp35; - _hx(2, 0) = _tmp27; - _hx(3, 0) = _tmp23; - _hx(16, 0) = _tmp2; - _hx(17, 0) = _tmp7; - _hx(18, 0) = _tmp11; - _hx(19, 0) = 1; + _hx(1, 0) = _tmp36; + _hx(2, 0) = _tmp38; + _hx(15, 0) = _tmp4; + _hx(16, 0) = _tmp9; + _hx(17, 0) = _tmp13; + _hx(18, 0) = 1; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_y_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_y_innov_var_and_h.h index 8eaac986f1ab..9f22c4f1fac7 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_y_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_y_innov_var_and_h.h @@ -17,77 +17,77 @@ namespace sym { * * Args: * state: Matrix24_1 - * P: Matrix24_24 + * P: Matrix23_23 * R: Scalar * epsilon: Scalar * * Outputs: * innov_var: Scalar - * H: Matrix24_1 + * H: Matrix23_1 */ template void ComputeMagYInnovVarAndH(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar R, + const matrix::Matrix& P, const Scalar R, const Scalar epsilon, Scalar* const innov_var = nullptr, - matrix::Matrix* const H = nullptr) { - // Total ops: 160 + matrix::Matrix* const H = nullptr) { + // Total ops: 110 // Unused inputs (void)epsilon; // Input arrays - // Intermediate terms (12) - const Scalar _tmp0 = 2 * state(16, 0); - const Scalar _tmp1 = 4 * state(17, 0); - const Scalar _tmp2 = 2 * state(18, 0); - const Scalar _tmp3 = _tmp0 * state(2, 0) - _tmp1 * state(1, 0) + _tmp2 * state(0, 0); - const Scalar _tmp4 = -_tmp0 * state(0, 0) - _tmp1 * state(3, 0) + _tmp2 * state(2, 0); - const Scalar _tmp5 = -_tmp0 * state(3, 0) + _tmp2 * state(1, 0); - const Scalar _tmp6 = _tmp0 * state(1, 0) + _tmp2 * state(3, 0); - const Scalar _tmp7 = - -2 * std::pow(state(1, 0), Scalar(2)) - 2 * std::pow(state(3, 0), Scalar(2)) + 1; - const Scalar _tmp8 = 2 * state(3, 0); - const Scalar _tmp9 = 2 * state(1, 0); - const Scalar _tmp10 = _tmp8 * state(2, 0) + _tmp9 * state(0, 0); - const Scalar _tmp11 = -_tmp8 * state(0, 0) + _tmp9 * state(2, 0); + // Intermediate terms (18) + const Scalar _tmp0 = std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp1 = std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp2 = -2 * _tmp0 - 2 * _tmp1 + 1; + const Scalar _tmp3 = 2 * state(2, 0); + const Scalar _tmp4 = _tmp3 * state(3, 0); + const Scalar _tmp5 = 2 * state(0, 0); + const Scalar _tmp6 = _tmp5 * state(1, 0); + const Scalar _tmp7 = _tmp4 + _tmp6; + const Scalar _tmp8 = -_tmp5 * state(3, 0); + const Scalar _tmp9 = _tmp3 * state(1, 0); + const Scalar _tmp10 = _tmp8 + _tmp9; + const Scalar _tmp11 = std::pow(state(0, 0), Scalar(2)); + const Scalar _tmp12 = std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp13 = _tmp0 - _tmp1; + const Scalar _tmp14 = _tmp3 * state(0, 0); + const Scalar _tmp15 = 2 * state(1, 0) * state(3, 0); + const Scalar _tmp16 = state(16, 0) * (-_tmp11 + _tmp12 + _tmp13) + + state(17, 0) * (_tmp8 - _tmp9) + state(18, 0) * (_tmp14 - _tmp15); + const Scalar _tmp17 = state(16, 0) * (_tmp14 + _tmp15) + state(17, 0) * (_tmp4 - _tmp6) + + state(18, 0) * (_tmp11 - _tmp12 + _tmp13); // Output terms (2) if (innov_var != nullptr) { Scalar& _innov_var = (*innov_var); - _innov_var = - P(0, 20) * _tmp5 + P(1, 20) * _tmp3 + P(16, 20) * _tmp11 + P(17, 20) * _tmp7 + - P(18, 20) * _tmp10 + P(2, 20) * _tmp6 + P(20, 20) + P(3, 20) * _tmp4 + R + - _tmp10 * (P(0, 18) * _tmp5 + P(1, 18) * _tmp3 + P(16, 18) * _tmp11 + P(17, 18) * _tmp7 + - P(18, 18) * _tmp10 + P(2, 18) * _tmp6 + P(20, 18) + P(3, 18) * _tmp4) + - _tmp11 * (P(0, 16) * _tmp5 + P(1, 16) * _tmp3 + P(16, 16) * _tmp11 + P(17, 16) * _tmp7 + - P(18, 16) * _tmp10 + P(2, 16) * _tmp6 + P(20, 16) + P(3, 16) * _tmp4) + - _tmp3 * (P(0, 1) * _tmp5 + P(1, 1) * _tmp3 + P(16, 1) * _tmp11 + P(17, 1) * _tmp7 + - P(18, 1) * _tmp10 + P(2, 1) * _tmp6 + P(20, 1) + P(3, 1) * _tmp4) + - _tmp4 * (P(0, 3) * _tmp5 + P(1, 3) * _tmp3 + P(16, 3) * _tmp11 + P(17, 3) * _tmp7 + - P(18, 3) * _tmp10 + P(2, 3) * _tmp6 + P(20, 3) + P(3, 3) * _tmp4) + - _tmp5 * (P(0, 0) * _tmp5 + P(1, 0) * _tmp3 + P(16, 0) * _tmp11 + P(17, 0) * _tmp7 + - P(18, 0) * _tmp10 + P(2, 0) * _tmp6 + P(20, 0) + P(3, 0) * _tmp4) + - _tmp6 * (P(0, 2) * _tmp5 + P(1, 2) * _tmp3 + P(16, 2) * _tmp11 + P(17, 2) * _tmp7 + - P(18, 2) * _tmp10 + P(2, 2) * _tmp6 + P(20, 2) + P(3, 2) * _tmp4) + - _tmp7 * (P(0, 17) * _tmp5 + P(1, 17) * _tmp3 + P(16, 17) * _tmp11 + P(17, 17) * _tmp7 + - P(18, 17) * _tmp10 + P(2, 17) * _tmp6 + P(20, 17) + P(3, 17) * _tmp4); + _innov_var = P(0, 19) * _tmp17 + P(15, 19) * _tmp10 + P(16, 19) * _tmp2 + P(17, 19) * _tmp7 + + P(19, 19) + P(2, 19) * _tmp16 + R + + _tmp10 * (P(0, 15) * _tmp17 + P(15, 15) * _tmp10 + P(16, 15) * _tmp2 + + P(17, 15) * _tmp7 + P(19, 15) + P(2, 15) * _tmp16) + + _tmp16 * (P(0, 2) * _tmp17 + P(15, 2) * _tmp10 + P(16, 2) * _tmp2 + + P(17, 2) * _tmp7 + P(19, 2) + P(2, 2) * _tmp16) + + _tmp17 * (P(0, 0) * _tmp17 + P(15, 0) * _tmp10 + P(16, 0) * _tmp2 + + P(17, 0) * _tmp7 + P(19, 0) + P(2, 0) * _tmp16) + + _tmp2 * (P(0, 16) * _tmp17 + P(15, 16) * _tmp10 + P(16, 16) * _tmp2 + + P(17, 16) * _tmp7 + P(19, 16) + P(2, 16) * _tmp16) + + _tmp7 * (P(0, 17) * _tmp17 + P(15, 17) * _tmp10 + P(16, 17) * _tmp2 + + P(17, 17) * _tmp7 + P(19, 17) + P(2, 17) * _tmp16); } if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); - _h(0, 0) = _tmp5; - _h(1, 0) = _tmp3; - _h(2, 0) = _tmp6; - _h(3, 0) = _tmp4; - _h(16, 0) = _tmp11; + _h(0, 0) = _tmp17; + _h(2, 0) = _tmp16; + _h(15, 0) = _tmp10; + _h(16, 0) = _tmp2; _h(17, 0) = _tmp7; - _h(18, 0) = _tmp10; - _h(20, 0) = 1; + _h(19, 0) = 1; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_z_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_z_innov_var_and_h.h index 906f28119ee3..0563f1df9e22 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_z_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_mag_z_innov_var_and_h.h @@ -17,77 +17,77 @@ namespace sym { * * Args: * state: Matrix24_1 - * P: Matrix24_24 + * P: Matrix23_23 * R: Scalar * epsilon: Scalar * * Outputs: * innov_var: Scalar - * H: Matrix24_1 + * H: Matrix23_1 */ template void ComputeMagZInnovVarAndH(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar R, + const matrix::Matrix& P, const Scalar R, const Scalar epsilon, Scalar* const innov_var = nullptr, - matrix::Matrix* const H = nullptr) { - // Total ops: 160 + matrix::Matrix* const H = nullptr) { + // Total ops: 110 // Unused inputs (void)epsilon; // Input arrays - // Intermediate terms (12) - const Scalar _tmp0 = 2 * state(16, 0); - const Scalar _tmp1 = 4 * state(18, 0); - const Scalar _tmp2 = 2 * state(17, 0); - const Scalar _tmp3 = _tmp0 * state(3, 0) - _tmp1 * state(1, 0) - _tmp2 * state(0, 0); - const Scalar _tmp4 = _tmp0 * state(0, 0) - _tmp1 * state(2, 0) + _tmp2 * state(3, 0); - const Scalar _tmp5 = _tmp0 * state(1, 0) + _tmp2 * state(2, 0); - const Scalar _tmp6 = _tmp0 * state(2, 0) - _tmp2 * state(1, 0); - const Scalar _tmp7 = 2 * state(2, 0); - const Scalar _tmp8 = 2 * state(1, 0); - const Scalar _tmp9 = _tmp7 * state(0, 0) + _tmp8 * state(3, 0); - const Scalar _tmp10 = _tmp7 * state(3, 0) - _tmp8 * state(0, 0); - const Scalar _tmp11 = - -2 * std::pow(state(1, 0), Scalar(2)) - 2 * std::pow(state(2, 0), Scalar(2)) + 1; + // Intermediate terms (18) + const Scalar _tmp0 = std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp1 = std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp2 = -2 * _tmp0 - 2 * _tmp1 + 1; + const Scalar _tmp3 = 2 * state(2, 0); + const Scalar _tmp4 = _tmp3 * state(3, 0); + const Scalar _tmp5 = 2 * state(0, 0); + const Scalar _tmp6 = -_tmp5 * state(1, 0); + const Scalar _tmp7 = _tmp4 + _tmp6; + const Scalar _tmp8 = _tmp3 * state(0, 0); + const Scalar _tmp9 = 2 * state(1, 0) * state(3, 0); + const Scalar _tmp10 = _tmp8 + _tmp9; + const Scalar _tmp11 = std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp12 = std::pow(state(0, 0), Scalar(2)); + const Scalar _tmp13 = -_tmp0 + _tmp1; + const Scalar _tmp14 = _tmp5 * state(3, 0); + const Scalar _tmp15 = _tmp3 * state(1, 0); + const Scalar _tmp16 = state(16, 0) * (-_tmp11 + _tmp12 + _tmp13) + + state(17, 0) * (_tmp14 + _tmp15) + state(18, 0) * (-_tmp8 + _tmp9); + const Scalar _tmp17 = state(16, 0) * (_tmp14 - _tmp15) + + state(17, 0) * (_tmp11 - _tmp12 + _tmp13) + state(18, 0) * (-_tmp4 + _tmp6); // Output terms (2) if (innov_var != nullptr) { Scalar& _innov_var = (*innov_var); - _innov_var = - P(0, 21) * _tmp6 + P(1, 21) * _tmp3 + P(16, 21) * _tmp9 + P(17, 21) * _tmp10 + - P(18, 21) * _tmp11 + P(2, 21) * _tmp4 + P(21, 21) + P(3, 21) * _tmp5 + R + - _tmp10 * (P(0, 17) * _tmp6 + P(1, 17) * _tmp3 + P(16, 17) * _tmp9 + P(17, 17) * _tmp10 + - P(18, 17) * _tmp11 + P(2, 17) * _tmp4 + P(21, 17) + P(3, 17) * _tmp5) + - _tmp11 * (P(0, 18) * _tmp6 + P(1, 18) * _tmp3 + P(16, 18) * _tmp9 + P(17, 18) * _tmp10 + - P(18, 18) * _tmp11 + P(2, 18) * _tmp4 + P(21, 18) + P(3, 18) * _tmp5) + - _tmp3 * (P(0, 1) * _tmp6 + P(1, 1) * _tmp3 + P(16, 1) * _tmp9 + P(17, 1) * _tmp10 + - P(18, 1) * _tmp11 + P(2, 1) * _tmp4 + P(21, 1) + P(3, 1) * _tmp5) + - _tmp4 * (P(0, 2) * _tmp6 + P(1, 2) * _tmp3 + P(16, 2) * _tmp9 + P(17, 2) * _tmp10 + - P(18, 2) * _tmp11 + P(2, 2) * _tmp4 + P(21, 2) + P(3, 2) * _tmp5) + - _tmp5 * (P(0, 3) * _tmp6 + P(1, 3) * _tmp3 + P(16, 3) * _tmp9 + P(17, 3) * _tmp10 + - P(18, 3) * _tmp11 + P(2, 3) * _tmp4 + P(21, 3) + P(3, 3) * _tmp5) + - _tmp6 * (P(0, 0) * _tmp6 + P(1, 0) * _tmp3 + P(16, 0) * _tmp9 + P(17, 0) * _tmp10 + - P(18, 0) * _tmp11 + P(2, 0) * _tmp4 + P(21, 0) + P(3, 0) * _tmp5) + - _tmp9 * (P(0, 16) * _tmp6 + P(1, 16) * _tmp3 + P(16, 16) * _tmp9 + P(17, 16) * _tmp10 + - P(18, 16) * _tmp11 + P(2, 16) * _tmp4 + P(21, 16) + P(3, 16) * _tmp5); + _innov_var = P(0, 20) * _tmp17 + P(1, 20) * _tmp16 + P(15, 20) * _tmp10 + P(16, 20) * _tmp7 + + P(17, 20) * _tmp2 + P(20, 20) + R + + _tmp10 * (P(0, 15) * _tmp17 + P(1, 15) * _tmp16 + P(15, 15) * _tmp10 + + P(16, 15) * _tmp7 + P(17, 15) * _tmp2 + P(20, 15)) + + _tmp16 * (P(0, 1) * _tmp17 + P(1, 1) * _tmp16 + P(15, 1) * _tmp10 + + P(16, 1) * _tmp7 + P(17, 1) * _tmp2 + P(20, 1)) + + _tmp17 * (P(0, 0) * _tmp17 + P(1, 0) * _tmp16 + P(15, 0) * _tmp10 + + P(16, 0) * _tmp7 + P(17, 0) * _tmp2 + P(20, 0)) + + _tmp2 * (P(0, 17) * _tmp17 + P(1, 17) * _tmp16 + P(15, 17) * _tmp10 + + P(16, 17) * _tmp7 + P(17, 17) * _tmp2 + P(20, 17)) + + _tmp7 * (P(0, 16) * _tmp17 + P(1, 16) * _tmp16 + P(15, 16) * _tmp10 + + P(16, 16) * _tmp7 + P(17, 16) * _tmp2 + P(20, 16)); } if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); - _h(0, 0) = _tmp6; - _h(1, 0) = _tmp3; - _h(2, 0) = _tmp4; - _h(3, 0) = _tmp5; - _h(16, 0) = _tmp9; - _h(17, 0) = _tmp10; - _h(18, 0) = _tmp11; - _h(21, 0) = 1; + _h(0, 0) = _tmp17; + _h(1, 0) = _tmp16; + _h(15, 0) = _tmp10; + _h(16, 0) = _tmp7; + _h(17, 0) = _tmp2; + _h(20, 0) = 1; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_h_and_k.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_h_and_k.h index 31b31db236e9..30acca8d22cc 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_h_and_k.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_h_and_k.h @@ -17,162 +17,165 @@ namespace sym { * * Args: * state: Matrix24_1 - * P: Matrix24_24 + * P: Matrix23_23 * innov_var: Scalar * epsilon: Scalar * * Outputs: - * H: Matrix24_1 - * K: Matrix24_1 + * H: Matrix23_1 + * K: Matrix23_1 */ template void ComputeSideslipHAndK(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar innov_var, - const Scalar epsilon, matrix::Matrix* const H = nullptr, - matrix::Matrix* const K = nullptr) { - // Total ops: 533 + const matrix::Matrix& P, const Scalar innov_var, + const Scalar epsilon, matrix::Matrix* const H = nullptr, + matrix::Matrix* const K = nullptr) { + // Total ops: 469 // Input arrays - // Intermediate terms (40) - const Scalar _tmp0 = -state(23, 0) + state(5, 0); - const Scalar _tmp1 = 2 * state(3, 0); - const Scalar _tmp2 = 2 * state(6, 0); - const Scalar _tmp3 = _tmp2 * state(2, 0); - const Scalar _tmp4 = 1 - 2 * std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp5 = _tmp4 - 2 * std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp6 = -state(22, 0) + state(4, 0); - const Scalar _tmp7 = _tmp1 * state(0, 0); - const Scalar _tmp8 = 2 * state(1, 0) * state(2, 0); - const Scalar _tmp9 = _tmp7 + _tmp8; - const Scalar _tmp10 = 2 * state(0, 0); - const Scalar _tmp11 = _tmp1 * state(1, 0) - _tmp10 * state(2, 0); - const Scalar _tmp12 = _tmp0 * _tmp9 + _tmp11 * state(6, 0) + _tmp5 * _tmp6; - const Scalar _tmp13 = - _tmp12 + epsilon * (2 * math::min(0, (((_tmp12) > 0) - ((_tmp12) < 0))) + 1); - const Scalar _tmp14 = _tmp4 - 2 * std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp15 = -_tmp7 + _tmp8; - const Scalar _tmp16 = _tmp1 * state(2, 0) + _tmp10 * state(1, 0); - const Scalar _tmp17 = - (_tmp0 * _tmp14 + _tmp15 * _tmp6 + _tmp16 * state(6, 0)) / std::pow(_tmp13, Scalar(2)); - const Scalar _tmp18 = _tmp2 * state(1, 0); - const Scalar _tmp19 = Scalar(1.0) / (_tmp13); - const Scalar _tmp20 = -_tmp17 * (_tmp0 * _tmp1 - _tmp3) + _tmp19 * (-_tmp1 * _tmp6 + _tmp18); - const Scalar _tmp21 = 2 * _tmp0; - const Scalar _tmp22 = _tmp1 * state(6, 0); - const Scalar _tmp23 = 4 * _tmp0; - const Scalar _tmp24 = 2 * _tmp6; - const Scalar _tmp25 = _tmp2 * state(0, 0); - const Scalar _tmp26 = -_tmp17 * (_tmp21 * state(2, 0) + _tmp22) + - _tmp19 * (-_tmp23 * state(1, 0) + _tmp24 * state(2, 0) + _tmp25); - const Scalar _tmp27 = 4 * _tmp6; - const Scalar _tmp28 = -_tmp17 * (_tmp21 * state(1, 0) - _tmp25 - _tmp27 * state(2, 0)) + - _tmp19 * (_tmp22 + _tmp24 * state(1, 0)); - const Scalar _tmp29 = -_tmp17 * (_tmp18 + _tmp21 * state(0, 0) - _tmp27 * state(3, 0)) + - _tmp19 * (-_tmp23 * state(3, 0) - _tmp24 * state(0, 0) + _tmp3); - const Scalar _tmp30 = _tmp17 * _tmp5; - const Scalar _tmp31 = _tmp15 * _tmp19; - const Scalar _tmp32 = -_tmp30 + _tmp31; - const Scalar _tmp33 = _tmp17 * _tmp9; - const Scalar _tmp34 = _tmp14 * _tmp19; - const Scalar _tmp35 = -_tmp33 + _tmp34; - const Scalar _tmp36 = -_tmp11 * _tmp17 + _tmp16 * _tmp19; - const Scalar _tmp37 = _tmp30 - _tmp31; - const Scalar _tmp38 = _tmp33 - _tmp34; - const Scalar _tmp39 = Scalar(1.0) / (math::max(epsilon, innov_var)); + // Intermediate terms (46) + const Scalar _tmp0 = std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp1 = std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp2 = 1 - 2 * _tmp1; + const Scalar _tmp3 = -2 * _tmp0 + _tmp2; + const Scalar _tmp4 = -state(22, 0) + state(4, 0); + const Scalar _tmp5 = 2 * state(0, 0); + const Scalar _tmp6 = _tmp5 * state(3, 0); + const Scalar _tmp7 = 2 * state(2, 0); + const Scalar _tmp8 = _tmp7 * state(1, 0); + const Scalar _tmp9 = _tmp6 + _tmp8; + const Scalar _tmp10 = -state(23, 0) + state(5, 0); + const Scalar _tmp11 = _tmp7 * state(0, 0); + const Scalar _tmp12 = -_tmp11; + const Scalar _tmp13 = 2 * state(1, 0) * state(3, 0); + const Scalar _tmp14 = _tmp12 + _tmp13; + const Scalar _tmp15 = _tmp10 * _tmp9 + _tmp14 * state(6, 0) + _tmp3 * _tmp4; + const Scalar _tmp16 = + _tmp15 + epsilon * (2 * math::min(0, (((_tmp15) > 0) - ((_tmp15) < 0))) + 1); + const Scalar _tmp17 = Scalar(1.0) / (_tmp16); + const Scalar _tmp18 = _tmp7 * state(3, 0); + const Scalar _tmp19 = _tmp5 * state(1, 0); + const Scalar _tmp20 = std::pow(state(0, 0), Scalar(2)); + const Scalar _tmp21 = std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp22 = -_tmp21; + const Scalar _tmp23 = _tmp20 + _tmp22; + const Scalar _tmp24 = _tmp17 * (_tmp10 * (_tmp18 - _tmp19) + _tmp4 * (_tmp11 + _tmp13) + + state(6, 0) * (-_tmp0 + _tmp1 + _tmp23)); + const Scalar _tmp25 = -_tmp13; + const Scalar _tmp26 = -_tmp20; + const Scalar _tmp27 = _tmp0 - _tmp1; + const Scalar _tmp28 = _tmp2 - 2 * _tmp21; + const Scalar _tmp29 = -_tmp6; + const Scalar _tmp30 = _tmp29 + _tmp8; + const Scalar _tmp31 = _tmp18 + _tmp19; + const Scalar _tmp32 = _tmp30 * _tmp4 + _tmp31 * state(6, 0); + const Scalar _tmp33 = (_tmp10 * _tmp28 + _tmp32) / std::pow(_tmp16, Scalar(2)); + const Scalar _tmp34 = _tmp33 * (_tmp10 * (-_tmp18 + _tmp19) + _tmp4 * (_tmp12 + _tmp25) + + state(6, 0) * (_tmp21 + _tmp26 + _tmp27)); + const Scalar _tmp35 = + _tmp17 * (_tmp10 * (_tmp29 - _tmp8) + _tmp4 * (_tmp0 + _tmp1 + _tmp22 + _tmp26) + + state(6, 0) * (_tmp11 + _tmp25)) - + _tmp33 * (_tmp10 * (_tmp23 + _tmp27) + _tmp32); + const Scalar _tmp36 = _tmp3 * _tmp33; + const Scalar _tmp37 = _tmp17 * _tmp30; + const Scalar _tmp38 = -_tmp36 + _tmp37; + const Scalar _tmp39 = _tmp33 * _tmp9; + const Scalar _tmp40 = _tmp17 * _tmp28; + const Scalar _tmp41 = -_tmp39 + _tmp40; + const Scalar _tmp42 = -_tmp14 * _tmp33 + _tmp17 * _tmp31; + const Scalar _tmp43 = _tmp36 - _tmp37; + const Scalar _tmp44 = _tmp39 - _tmp40; + const Scalar _tmp45 = Scalar(1.0) / (math::max(epsilon, innov_var)); // Output terms (2) if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); - _h(0, 0) = _tmp20; - _h(1, 0) = _tmp26; - _h(2, 0) = _tmp28; - _h(3, 0) = _tmp29; - _h(4, 0) = _tmp32; - _h(5, 0) = _tmp35; - _h(6, 0) = _tmp36; - _h(22, 0) = _tmp37; - _h(23, 0) = _tmp38; + _h(0, 0) = _tmp24; + _h(1, 0) = -_tmp34; + _h(2, 0) = _tmp35; + _h(3, 0) = _tmp38; + _h(4, 0) = _tmp41; + _h(5, 0) = _tmp42; + _h(21, 0) = _tmp43; + _h(22, 0) = _tmp44; } if (K != nullptr) { - matrix::Matrix& _k = (*K); + matrix::Matrix& _k = (*K); - _k(0, 0) = _tmp39 * (P(0, 0) * _tmp20 + P(0, 1) * _tmp26 + P(0, 2) * _tmp28 + - P(0, 22) * _tmp37 + P(0, 23) * _tmp38 + P(0, 3) * _tmp29 + - P(0, 4) * _tmp32 + P(0, 5) * _tmp35 + P(0, 6) * _tmp36); - _k(1, 0) = _tmp39 * (P(1, 0) * _tmp20 + P(1, 1) * _tmp26 + P(1, 2) * _tmp28 + - P(1, 22) * _tmp37 + P(1, 23) * _tmp38 + P(1, 3) * _tmp29 + - P(1, 4) * _tmp32 + P(1, 5) * _tmp35 + P(1, 6) * _tmp36); - _k(2, 0) = _tmp39 * (P(2, 0) * _tmp20 + P(2, 1) * _tmp26 + P(2, 2) * _tmp28 + - P(2, 22) * _tmp37 + P(2, 23) * _tmp38 + P(2, 3) * _tmp29 + - P(2, 4) * _tmp32 + P(2, 5) * _tmp35 + P(2, 6) * _tmp36); - _k(3, 0) = _tmp39 * (P(3, 0) * _tmp20 + P(3, 1) * _tmp26 + P(3, 2) * _tmp28 + - P(3, 22) * _tmp37 + P(3, 23) * _tmp38 + P(3, 3) * _tmp29 + - P(3, 4) * _tmp32 + P(3, 5) * _tmp35 + P(3, 6) * _tmp36); - _k(4, 0) = _tmp39 * (P(4, 0) * _tmp20 + P(4, 1) * _tmp26 + P(4, 2) * _tmp28 + - P(4, 22) * _tmp37 + P(4, 23) * _tmp38 + P(4, 3) * _tmp29 + - P(4, 4) * _tmp32 + P(4, 5) * _tmp35 + P(4, 6) * _tmp36); - _k(5, 0) = _tmp39 * (P(5, 0) * _tmp20 + P(5, 1) * _tmp26 + P(5, 2) * _tmp28 + - P(5, 22) * _tmp37 + P(5, 23) * _tmp38 + P(5, 3) * _tmp29 + - P(5, 4) * _tmp32 + P(5, 5) * _tmp35 + P(5, 6) * _tmp36); - _k(6, 0) = _tmp39 * (P(6, 0) * _tmp20 + P(6, 1) * _tmp26 + P(6, 2) * _tmp28 + - P(6, 22) * _tmp37 + P(6, 23) * _tmp38 + P(6, 3) * _tmp29 + - P(6, 4) * _tmp32 + P(6, 5) * _tmp35 + P(6, 6) * _tmp36); - _k(7, 0) = _tmp39 * (P(7, 0) * _tmp20 + P(7, 1) * _tmp26 + P(7, 2) * _tmp28 + - P(7, 22) * _tmp37 + P(7, 23) * _tmp38 + P(7, 3) * _tmp29 + - P(7, 4) * _tmp32 + P(7, 5) * _tmp35 + P(7, 6) * _tmp36); - _k(8, 0) = _tmp39 * (P(8, 0) * _tmp20 + P(8, 1) * _tmp26 + P(8, 2) * _tmp28 + - P(8, 22) * _tmp37 + P(8, 23) * _tmp38 + P(8, 3) * _tmp29 + - P(8, 4) * _tmp32 + P(8, 5) * _tmp35 + P(8, 6) * _tmp36); - _k(9, 0) = _tmp39 * (P(9, 0) * _tmp20 + P(9, 1) * _tmp26 + P(9, 2) * _tmp28 + - P(9, 22) * _tmp37 + P(9, 23) * _tmp38 + P(9, 3) * _tmp29 + - P(9, 4) * _tmp32 + P(9, 5) * _tmp35 + P(9, 6) * _tmp36); - _k(10, 0) = _tmp39 * (P(10, 0) * _tmp20 + P(10, 1) * _tmp26 + P(10, 2) * _tmp28 + - P(10, 22) * _tmp37 + P(10, 23) * _tmp38 + P(10, 3) * _tmp29 + - P(10, 4) * _tmp32 + P(10, 5) * _tmp35 + P(10, 6) * _tmp36); - _k(11, 0) = _tmp39 * (P(11, 0) * _tmp20 + P(11, 1) * _tmp26 + P(11, 2) * _tmp28 + - P(11, 22) * _tmp37 + P(11, 23) * _tmp38 + P(11, 3) * _tmp29 + - P(11, 4) * _tmp32 + P(11, 5) * _tmp35 + P(11, 6) * _tmp36); - _k(12, 0) = _tmp39 * (P(12, 0) * _tmp20 + P(12, 1) * _tmp26 + P(12, 2) * _tmp28 + - P(12, 22) * _tmp37 + P(12, 23) * _tmp38 + P(12, 3) * _tmp29 + - P(12, 4) * _tmp32 + P(12, 5) * _tmp35 + P(12, 6) * _tmp36); - _k(13, 0) = _tmp39 * (P(13, 0) * _tmp20 + P(13, 1) * _tmp26 + P(13, 2) * _tmp28 + - P(13, 22) * _tmp37 + P(13, 23) * _tmp38 + P(13, 3) * _tmp29 + - P(13, 4) * _tmp32 + P(13, 5) * _tmp35 + P(13, 6) * _tmp36); - _k(14, 0) = _tmp39 * (P(14, 0) * _tmp20 + P(14, 1) * _tmp26 + P(14, 2) * _tmp28 + - P(14, 22) * _tmp37 + P(14, 23) * _tmp38 + P(14, 3) * _tmp29 + - P(14, 4) * _tmp32 + P(14, 5) * _tmp35 + P(14, 6) * _tmp36); - _k(15, 0) = _tmp39 * (P(15, 0) * _tmp20 + P(15, 1) * _tmp26 + P(15, 2) * _tmp28 + - P(15, 22) * _tmp37 + P(15, 23) * _tmp38 + P(15, 3) * _tmp29 + - P(15, 4) * _tmp32 + P(15, 5) * _tmp35 + P(15, 6) * _tmp36); - _k(16, 0) = _tmp39 * (P(16, 0) * _tmp20 + P(16, 1) * _tmp26 + P(16, 2) * _tmp28 + - P(16, 22) * _tmp37 + P(16, 23) * _tmp38 + P(16, 3) * _tmp29 + - P(16, 4) * _tmp32 + P(16, 5) * _tmp35 + P(16, 6) * _tmp36); - _k(17, 0) = _tmp39 * (P(17, 0) * _tmp20 + P(17, 1) * _tmp26 + P(17, 2) * _tmp28 + - P(17, 22) * _tmp37 + P(17, 23) * _tmp38 + P(17, 3) * _tmp29 + - P(17, 4) * _tmp32 + P(17, 5) * _tmp35 + P(17, 6) * _tmp36); - _k(18, 0) = _tmp39 * (P(18, 0) * _tmp20 + P(18, 1) * _tmp26 + P(18, 2) * _tmp28 + - P(18, 22) * _tmp37 + P(18, 23) * _tmp38 + P(18, 3) * _tmp29 + - P(18, 4) * _tmp32 + P(18, 5) * _tmp35 + P(18, 6) * _tmp36); - _k(19, 0) = _tmp39 * (P(19, 0) * _tmp20 + P(19, 1) * _tmp26 + P(19, 2) * _tmp28 + - P(19, 22) * _tmp37 + P(19, 23) * _tmp38 + P(19, 3) * _tmp29 + - P(19, 4) * _tmp32 + P(19, 5) * _tmp35 + P(19, 6) * _tmp36); - _k(20, 0) = _tmp39 * (P(20, 0) * _tmp20 + P(20, 1) * _tmp26 + P(20, 2) * _tmp28 + - P(20, 22) * _tmp37 + P(20, 23) * _tmp38 + P(20, 3) * _tmp29 + - P(20, 4) * _tmp32 + P(20, 5) * _tmp35 + P(20, 6) * _tmp36); - _k(21, 0) = _tmp39 * (P(21, 0) * _tmp20 + P(21, 1) * _tmp26 + P(21, 2) * _tmp28 + - P(21, 22) * _tmp37 + P(21, 23) * _tmp38 + P(21, 3) * _tmp29 + - P(21, 4) * _tmp32 + P(21, 5) * _tmp35 + P(21, 6) * _tmp36); - _k(22, 0) = _tmp39 * (P(22, 0) * _tmp20 + P(22, 1) * _tmp26 + P(22, 2) * _tmp28 + - P(22, 22) * _tmp37 + P(22, 23) * _tmp38 + P(22, 3) * _tmp29 + - P(22, 4) * _tmp32 + P(22, 5) * _tmp35 + P(22, 6) * _tmp36); - _k(23, 0) = _tmp39 * (P(23, 0) * _tmp20 + P(23, 1) * _tmp26 + P(23, 2) * _tmp28 + - P(23, 22) * _tmp37 + P(23, 23) * _tmp38 + P(23, 3) * _tmp29 + - P(23, 4) * _tmp32 + P(23, 5) * _tmp35 + P(23, 6) * _tmp36); + _k(0, 0) = + _tmp45 * (P(0, 0) * _tmp24 - P(0, 1) * _tmp34 + P(0, 2) * _tmp35 + P(0, 21) * _tmp43 + + P(0, 22) * _tmp44 + P(0, 3) * _tmp38 + P(0, 4) * _tmp41 + P(0, 5) * _tmp42); + _k(1, 0) = + _tmp45 * (P(1, 0) * _tmp24 - P(1, 1) * _tmp34 + P(1, 2) * _tmp35 + P(1, 21) * _tmp43 + + P(1, 22) * _tmp44 + P(1, 3) * _tmp38 + P(1, 4) * _tmp41 + P(1, 5) * _tmp42); + _k(2, 0) = + _tmp45 * (P(2, 0) * _tmp24 - P(2, 1) * _tmp34 + P(2, 2) * _tmp35 + P(2, 21) * _tmp43 + + P(2, 22) * _tmp44 + P(2, 3) * _tmp38 + P(2, 4) * _tmp41 + P(2, 5) * _tmp42); + _k(3, 0) = + _tmp45 * (P(3, 0) * _tmp24 - P(3, 1) * _tmp34 + P(3, 2) * _tmp35 + P(3, 21) * _tmp43 + + P(3, 22) * _tmp44 + P(3, 3) * _tmp38 + P(3, 4) * _tmp41 + P(3, 5) * _tmp42); + _k(4, 0) = + _tmp45 * (P(4, 0) * _tmp24 - P(4, 1) * _tmp34 + P(4, 2) * _tmp35 + P(4, 21) * _tmp43 + + P(4, 22) * _tmp44 + P(4, 3) * _tmp38 + P(4, 4) * _tmp41 + P(4, 5) * _tmp42); + _k(5, 0) = + _tmp45 * (P(5, 0) * _tmp24 - P(5, 1) * _tmp34 + P(5, 2) * _tmp35 + P(5, 21) * _tmp43 + + P(5, 22) * _tmp44 + P(5, 3) * _tmp38 + P(5, 4) * _tmp41 + P(5, 5) * _tmp42); + _k(6, 0) = + _tmp45 * (P(6, 0) * _tmp24 - P(6, 1) * _tmp34 + P(6, 2) * _tmp35 + P(6, 21) * _tmp43 + + P(6, 22) * _tmp44 + P(6, 3) * _tmp38 + P(6, 4) * _tmp41 + P(6, 5) * _tmp42); + _k(7, 0) = + _tmp45 * (P(7, 0) * _tmp24 - P(7, 1) * _tmp34 + P(7, 2) * _tmp35 + P(7, 21) * _tmp43 + + P(7, 22) * _tmp44 + P(7, 3) * _tmp38 + P(7, 4) * _tmp41 + P(7, 5) * _tmp42); + _k(8, 0) = + _tmp45 * (P(8, 0) * _tmp24 - P(8, 1) * _tmp34 + P(8, 2) * _tmp35 + P(8, 21) * _tmp43 + + P(8, 22) * _tmp44 + P(8, 3) * _tmp38 + P(8, 4) * _tmp41 + P(8, 5) * _tmp42); + _k(9, 0) = + _tmp45 * (P(9, 0) * _tmp24 - P(9, 1) * _tmp34 + P(9, 2) * _tmp35 + P(9, 21) * _tmp43 + + P(9, 22) * _tmp44 + P(9, 3) * _tmp38 + P(9, 4) * _tmp41 + P(9, 5) * _tmp42); + _k(10, 0) = + _tmp45 * (P(10, 0) * _tmp24 - P(10, 1) * _tmp34 + P(10, 2) * _tmp35 + P(10, 21) * _tmp43 + + P(10, 22) * _tmp44 + P(10, 3) * _tmp38 + P(10, 4) * _tmp41 + P(10, 5) * _tmp42); + _k(11, 0) = + _tmp45 * (P(11, 0) * _tmp24 - P(11, 1) * _tmp34 + P(11, 2) * _tmp35 + P(11, 21) * _tmp43 + + P(11, 22) * _tmp44 + P(11, 3) * _tmp38 + P(11, 4) * _tmp41 + P(11, 5) * _tmp42); + _k(12, 0) = + _tmp45 * (P(12, 0) * _tmp24 - P(12, 1) * _tmp34 + P(12, 2) * _tmp35 + P(12, 21) * _tmp43 + + P(12, 22) * _tmp44 + P(12, 3) * _tmp38 + P(12, 4) * _tmp41 + P(12, 5) * _tmp42); + _k(13, 0) = + _tmp45 * (P(13, 0) * _tmp24 - P(13, 1) * _tmp34 + P(13, 2) * _tmp35 + P(13, 21) * _tmp43 + + P(13, 22) * _tmp44 + P(13, 3) * _tmp38 + P(13, 4) * _tmp41 + P(13, 5) * _tmp42); + _k(14, 0) = + _tmp45 * (P(14, 0) * _tmp24 - P(14, 1) * _tmp34 + P(14, 2) * _tmp35 + P(14, 21) * _tmp43 + + P(14, 22) * _tmp44 + P(14, 3) * _tmp38 + P(14, 4) * _tmp41 + P(14, 5) * _tmp42); + _k(15, 0) = + _tmp45 * (P(15, 0) * _tmp24 - P(15, 1) * _tmp34 + P(15, 2) * _tmp35 + P(15, 21) * _tmp43 + + P(15, 22) * _tmp44 + P(15, 3) * _tmp38 + P(15, 4) * _tmp41 + P(15, 5) * _tmp42); + _k(16, 0) = + _tmp45 * (P(16, 0) * _tmp24 - P(16, 1) * _tmp34 + P(16, 2) * _tmp35 + P(16, 21) * _tmp43 + + P(16, 22) * _tmp44 + P(16, 3) * _tmp38 + P(16, 4) * _tmp41 + P(16, 5) * _tmp42); + _k(17, 0) = + _tmp45 * (P(17, 0) * _tmp24 - P(17, 1) * _tmp34 + P(17, 2) * _tmp35 + P(17, 21) * _tmp43 + + P(17, 22) * _tmp44 + P(17, 3) * _tmp38 + P(17, 4) * _tmp41 + P(17, 5) * _tmp42); + _k(18, 0) = + _tmp45 * (P(18, 0) * _tmp24 - P(18, 1) * _tmp34 + P(18, 2) * _tmp35 + P(18, 21) * _tmp43 + + P(18, 22) * _tmp44 + P(18, 3) * _tmp38 + P(18, 4) * _tmp41 + P(18, 5) * _tmp42); + _k(19, 0) = + _tmp45 * (P(19, 0) * _tmp24 - P(19, 1) * _tmp34 + P(19, 2) * _tmp35 + P(19, 21) * _tmp43 + + P(19, 22) * _tmp44 + P(19, 3) * _tmp38 + P(19, 4) * _tmp41 + P(19, 5) * _tmp42); + _k(20, 0) = + _tmp45 * (P(20, 0) * _tmp24 - P(20, 1) * _tmp34 + P(20, 2) * _tmp35 + P(20, 21) * _tmp43 + + P(20, 22) * _tmp44 + P(20, 3) * _tmp38 + P(20, 4) * _tmp41 + P(20, 5) * _tmp42); + _k(21, 0) = + _tmp45 * (P(21, 0) * _tmp24 - P(21, 1) * _tmp34 + P(21, 2) * _tmp35 + P(21, 21) * _tmp43 + + P(21, 22) * _tmp44 + P(21, 3) * _tmp38 + P(21, 4) * _tmp41 + P(21, 5) * _tmp42); + _k(22, 0) = + _tmp45 * (P(22, 0) * _tmp24 - P(22, 1) * _tmp34 + P(22, 2) * _tmp35 + P(22, 21) * _tmp43 + + P(22, 22) * _tmp44 + P(22, 3) * _tmp38 + P(22, 4) * _tmp41 + P(22, 5) * _tmp42); } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_innov_and_innov_var.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_innov_and_innov_var.h index 6c13cf39ac9d..48dd3e284f34 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_innov_and_innov_var.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_sideslip_innov_and_innov_var.h @@ -17,7 +17,7 @@ namespace sym { * * Args: * state: Matrix24_1 - * P: Matrix24_24 + * P: Matrix23_23 * R: Scalar * epsilon: Scalar * @@ -27,96 +27,95 @@ namespace sym { */ template void ComputeSideslipInnovAndInnovVar(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar R, + const matrix::Matrix& P, const Scalar R, const Scalar epsilon, Scalar* const innov = nullptr, Scalar* const innov_var = nullptr) { - // Total ops: 269 + // Total ops: 235 // Input arrays - // Intermediate terms (39) - const Scalar _tmp0 = 1 - 2 * std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp1 = _tmp0 - 2 * std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp2 = -state(22, 0) + state(4, 0); - const Scalar _tmp3 = 2 * state(3, 0); - const Scalar _tmp4 = _tmp3 * state(0, 0); - const Scalar _tmp5 = 2 * state(1, 0); - const Scalar _tmp6 = _tmp5 * state(2, 0); - const Scalar _tmp7 = _tmp4 + _tmp6; - const Scalar _tmp8 = -state(23, 0) + state(5, 0); - const Scalar _tmp9 = 2 * state(2, 0); - const Scalar _tmp10 = _tmp3 * state(1, 0) - _tmp9 * state(0, 0); - const Scalar _tmp11 = _tmp1 * _tmp2 + _tmp10 * state(6, 0) + _tmp7 * _tmp8; - const Scalar _tmp12 = - _tmp11 + epsilon * (2 * math::min(0, (((_tmp11) > 0) - ((_tmp11) < 0))) + 1); - const Scalar _tmp13 = Scalar(1.0) / (_tmp12); - const Scalar _tmp14 = _tmp0 - 2 * std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp15 = -_tmp4 + _tmp6; - const Scalar _tmp16 = _tmp3 * state(2, 0) + _tmp5 * state(0, 0); - const Scalar _tmp17 = _tmp14 * _tmp8 + _tmp15 * _tmp2 + _tmp16 * state(6, 0); - const Scalar _tmp18 = _tmp17 / std::pow(_tmp12, Scalar(2)); - const Scalar _tmp19 = _tmp1 * _tmp18; - const Scalar _tmp20 = _tmp13 * _tmp15; - const Scalar _tmp21 = -_tmp19 + _tmp20; - const Scalar _tmp22 = _tmp3 * state(6, 0); - const Scalar _tmp23 = 4 * _tmp8; - const Scalar _tmp24 = 2 * state(0, 0); - const Scalar _tmp25 = _tmp24 * state(6, 0); - const Scalar _tmp26 = - _tmp13 * (_tmp2 * _tmp9 - _tmp23 * state(1, 0) + _tmp25) - _tmp18 * (_tmp22 + _tmp8 * _tmp9); - const Scalar _tmp27 = -_tmp10 * _tmp18 + _tmp13 * _tmp16; - const Scalar _tmp28 = 4 * _tmp2; - const Scalar _tmp29 = - _tmp13 * (_tmp2 * _tmp5 + _tmp22) - _tmp18 * (-_tmp25 - _tmp28 * state(2, 0) + _tmp5 * _tmp8); - const Scalar _tmp30 = _tmp9 * state(6, 0); - const Scalar _tmp31 = _tmp5 * state(6, 0); - const Scalar _tmp32 = _tmp13 * (-_tmp2 * _tmp3 + _tmp31) - _tmp18 * (_tmp3 * _tmp8 - _tmp30); - const Scalar _tmp33 = _tmp19 - _tmp20; - const Scalar _tmp34 = _tmp18 * _tmp7; - const Scalar _tmp35 = _tmp13 * _tmp14; - const Scalar _tmp36 = -_tmp34 + _tmp35; - const Scalar _tmp37 = _tmp34 - _tmp35; - const Scalar _tmp38 = _tmp13 * (-_tmp2 * _tmp24 - _tmp23 * state(3, 0) + _tmp30) - - _tmp18 * (_tmp24 * _tmp8 - _tmp28 * state(3, 0) + _tmp31); + // Intermediate terms (46) + const Scalar _tmp0 = std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp1 = std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp2 = 1 - 2 * _tmp1; + const Scalar _tmp3 = -2 * _tmp0 + _tmp2; + const Scalar _tmp4 = -state(22, 0) + state(4, 0); + const Scalar _tmp5 = 2 * state(0, 0); + const Scalar _tmp6 = _tmp5 * state(3, 0); + const Scalar _tmp7 = 2 * state(1, 0); + const Scalar _tmp8 = _tmp7 * state(2, 0); + const Scalar _tmp9 = _tmp6 + _tmp8; + const Scalar _tmp10 = -state(23, 0) + state(5, 0); + const Scalar _tmp11 = _tmp5 * state(2, 0); + const Scalar _tmp12 = -_tmp11; + const Scalar _tmp13 = _tmp7 * state(3, 0); + const Scalar _tmp14 = _tmp12 + _tmp13; + const Scalar _tmp15 = _tmp10 * _tmp9 + _tmp14 * state(6, 0) + _tmp3 * _tmp4; + const Scalar _tmp16 = + _tmp15 + epsilon * (2 * math::min(0, (((_tmp15) > 0) - ((_tmp15) < 0))) + 1); + const Scalar _tmp17 = Scalar(1.0) / (_tmp16); + const Scalar _tmp18 = std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp19 = -2 * _tmp18 + _tmp2; + const Scalar _tmp20 = -_tmp6; + const Scalar _tmp21 = _tmp20 + _tmp8; + const Scalar _tmp22 = 2 * state(2, 0) * state(3, 0); + const Scalar _tmp23 = _tmp5 * state(1, 0); + const Scalar _tmp24 = _tmp22 + _tmp23; + const Scalar _tmp25 = _tmp21 * _tmp4 + _tmp24 * state(6, 0); + const Scalar _tmp26 = _tmp10 * _tmp19 + _tmp25; + const Scalar _tmp27 = _tmp26 / std::pow(_tmp16, Scalar(2)); + const Scalar _tmp28 = -_tmp14 * _tmp27 + _tmp17 * _tmp24; + const Scalar _tmp29 = _tmp27 * _tmp3; + const Scalar _tmp30 = _tmp17 * _tmp21; + const Scalar _tmp31 = -_tmp29 + _tmp30; + const Scalar _tmp32 = std::pow(state(0, 0), Scalar(2)); + const Scalar _tmp33 = -_tmp32; + const Scalar _tmp34 = -_tmp18; + const Scalar _tmp35 = -_tmp13; + const Scalar _tmp36 = _tmp0 - _tmp1; + const Scalar _tmp37 = _tmp32 + _tmp34; + const Scalar _tmp38 = + _tmp17 * (_tmp10 * (_tmp20 - _tmp8) + _tmp4 * (_tmp0 + _tmp1 + _tmp33 + _tmp34) + + state(6, 0) * (_tmp11 + _tmp35)) - + _tmp27 * (_tmp10 * (_tmp36 + _tmp37) + _tmp25); + const Scalar _tmp39 = _tmp29 - _tmp30; + const Scalar _tmp40 = _tmp27 * _tmp9; + const Scalar _tmp41 = _tmp17 * _tmp19; + const Scalar _tmp42 = -_tmp40 + _tmp41; + const Scalar _tmp43 = _tmp27 * (_tmp10 * (-_tmp22 + _tmp23) + _tmp4 * (_tmp12 + _tmp35) + + state(6, 0) * (_tmp18 + _tmp33 + _tmp36)); + const Scalar _tmp44 = _tmp40 - _tmp41; + const Scalar _tmp45 = _tmp17 * (_tmp10 * (_tmp22 - _tmp23) + _tmp4 * (_tmp11 + _tmp13) + + state(6, 0) * (-_tmp0 + _tmp1 + _tmp37)); // Output terms (2) if (innov != nullptr) { Scalar& _innov = (*innov); - _innov = _tmp13 * _tmp17; + _innov = _tmp17 * _tmp26; } if (innov_var != nullptr) { Scalar& _innov_var = (*innov_var); - _innov_var = R + - _tmp21 * (P(0, 4) * _tmp32 + P(1, 4) * _tmp26 + P(2, 4) * _tmp29 + - P(22, 4) * _tmp33 + P(23, 4) * _tmp37 + P(3, 4) * _tmp38 + - P(4, 4) * _tmp21 + P(5, 4) * _tmp36 + P(6, 4) * _tmp27) + - _tmp26 * (P(0, 1) * _tmp32 + P(1, 1) * _tmp26 + P(2, 1) * _tmp29 + - P(22, 1) * _tmp33 + P(23, 1) * _tmp37 + P(3, 1) * _tmp38 + - P(4, 1) * _tmp21 + P(5, 1) * _tmp36 + P(6, 1) * _tmp27) + - _tmp27 * (P(0, 6) * _tmp32 + P(1, 6) * _tmp26 + P(2, 6) * _tmp29 + - P(22, 6) * _tmp33 + P(23, 6) * _tmp37 + P(3, 6) * _tmp38 + - P(4, 6) * _tmp21 + P(5, 6) * _tmp36 + P(6, 6) * _tmp27) + - _tmp29 * (P(0, 2) * _tmp32 + P(1, 2) * _tmp26 + P(2, 2) * _tmp29 + - P(22, 2) * _tmp33 + P(23, 2) * _tmp37 + P(3, 2) * _tmp38 + - P(4, 2) * _tmp21 + P(5, 2) * _tmp36 + P(6, 2) * _tmp27) + - _tmp32 * (P(0, 0) * _tmp32 + P(1, 0) * _tmp26 + P(2, 0) * _tmp29 + - P(22, 0) * _tmp33 + P(23, 0) * _tmp37 + P(3, 0) * _tmp38 + - P(4, 0) * _tmp21 + P(5, 0) * _tmp36 + P(6, 0) * _tmp27) + - _tmp33 * (P(0, 22) * _tmp32 + P(1, 22) * _tmp26 + P(2, 22) * _tmp29 + - P(22, 22) * _tmp33 + P(23, 22) * _tmp37 + P(3, 22) * _tmp38 + - P(4, 22) * _tmp21 + P(5, 22) * _tmp36 + P(6, 22) * _tmp27) + - _tmp36 * (P(0, 5) * _tmp32 + P(1, 5) * _tmp26 + P(2, 5) * _tmp29 + - P(22, 5) * _tmp33 + P(23, 5) * _tmp37 + P(3, 5) * _tmp38 + - P(4, 5) * _tmp21 + P(5, 5) * _tmp36 + P(6, 5) * _tmp27) + - _tmp37 * (P(0, 23) * _tmp32 + P(1, 23) * _tmp26 + P(2, 23) * _tmp29 + - P(22, 23) * _tmp33 + P(23, 23) * _tmp37 + P(3, 23) * _tmp38 + - P(4, 23) * _tmp21 + P(5, 23) * _tmp36 + P(6, 23) * _tmp27) + - _tmp38 * (P(0, 3) * _tmp32 + P(1, 3) * _tmp26 + P(2, 3) * _tmp29 + - P(22, 3) * _tmp33 + P(23, 3) * _tmp37 + P(3, 3) * _tmp38 + - P(4, 3) * _tmp21 + P(5, 3) * _tmp36 + P(6, 3) * _tmp27); + _innov_var = + R + + _tmp28 * (P(0, 5) * _tmp45 - P(1, 5) * _tmp43 + P(2, 5) * _tmp38 + P(21, 5) * _tmp39 + + P(22, 5) * _tmp44 + P(3, 5) * _tmp31 + P(4, 5) * _tmp42 + P(5, 5) * _tmp28) + + _tmp31 * (P(0, 3) * _tmp45 - P(1, 3) * _tmp43 + P(2, 3) * _tmp38 + P(21, 3) * _tmp39 + + P(22, 3) * _tmp44 + P(3, 3) * _tmp31 + P(4, 3) * _tmp42 + P(5, 3) * _tmp28) + + _tmp38 * (P(0, 2) * _tmp45 - P(1, 2) * _tmp43 + P(2, 2) * _tmp38 + P(21, 2) * _tmp39 + + P(22, 2) * _tmp44 + P(3, 2) * _tmp31 + P(4, 2) * _tmp42 + P(5, 2) * _tmp28) + + _tmp39 * (P(0, 21) * _tmp45 - P(1, 21) * _tmp43 + P(2, 21) * _tmp38 + P(21, 21) * _tmp39 + + P(22, 21) * _tmp44 + P(3, 21) * _tmp31 + P(4, 21) * _tmp42 + P(5, 21) * _tmp28) + + _tmp42 * (P(0, 4) * _tmp45 - P(1, 4) * _tmp43 + P(2, 4) * _tmp38 + P(21, 4) * _tmp39 + + P(22, 4) * _tmp44 + P(3, 4) * _tmp31 + P(4, 4) * _tmp42 + P(5, 4) * _tmp28) - + _tmp43 * (P(0, 1) * _tmp45 - P(1, 1) * _tmp43 + P(2, 1) * _tmp38 + P(21, 1) * _tmp39 + + P(22, 1) * _tmp44 + P(3, 1) * _tmp31 + P(4, 1) * _tmp42 + P(5, 1) * _tmp28) + + _tmp44 * (P(0, 22) * _tmp45 - P(1, 22) * _tmp43 + P(2, 22) * _tmp38 + P(21, 22) * _tmp39 + + P(22, 22) * _tmp44 + P(3, 22) * _tmp31 + P(4, 22) * _tmp42 + P(5, 22) * _tmp28) + + _tmp45 * (P(0, 0) * _tmp45 - P(1, 0) * _tmp43 + P(2, 0) * _tmp38 + P(21, 0) * _tmp39 + + P(22, 0) * _tmp44 + P(3, 0) * _tmp31 + P(4, 0) * _tmp42 + P(5, 0) * _tmp28); } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_312_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_312_innov_var_and_h.h index 9a873898fde9..e6fd32157ef7 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_312_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_312_innov_var_and_h.h @@ -17,61 +17,58 @@ namespace sym { * * Args: * state: Matrix24_1 - * P: Matrix24_24 + * P: Matrix23_23 * R: Scalar * epsilon: Scalar * * Outputs: * innov_var: Scalar - * H: Matrix24_1 + * H: Matrix23_1 */ template void ComputeYaw312InnovVarAndH(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar R, + const matrix::Matrix& P, const Scalar R, const Scalar epsilon, Scalar* const innov_var = nullptr, - matrix::Matrix* const H = nullptr) { - // Total ops: 73 + matrix::Matrix* const H = nullptr) { + // Total ops: 53 // Input arrays // Intermediate terms (15) const Scalar _tmp0 = 2 * state(0, 0); - const Scalar _tmp1 = 2 * state(2, 0); - const Scalar _tmp2 = -_tmp0 * state(3, 0) + _tmp1 * state(1, 0); - const Scalar _tmp3 = - -2 * std::pow(state(1, 0), Scalar(2)) - 2 * std::pow(state(3, 0), Scalar(2)) + 1; - const Scalar _tmp4 = _tmp3 + epsilon * ((((_tmp3) > 0) - ((_tmp3) < 0)) + Scalar(0.5)); - const Scalar _tmp5 = std::pow(_tmp4, Scalar(2)); - const Scalar _tmp6 = 4 * _tmp2 / _tmp5; - const Scalar _tmp7 = Scalar(1.0) / (_tmp4); - const Scalar _tmp8 = Scalar(1.0) / (std::pow(_tmp2, Scalar(2)) + _tmp5); - const Scalar _tmp9 = _tmp5 * _tmp8; - const Scalar _tmp10 = _tmp9 * (-_tmp1 * _tmp7 - _tmp6 * state(1, 0)); - const Scalar _tmp11 = _tmp9 * (_tmp0 * _tmp7 - _tmp6 * state(3, 0)); - const Scalar _tmp12 = 2 * _tmp4 * _tmp8; - const Scalar _tmp13 = _tmp12 * state(3, 0); - const Scalar _tmp14 = _tmp12 * state(1, 0); + const Scalar _tmp1 = -_tmp0 * state(3, 0); + const Scalar _tmp2 = 2 * state(1, 0); + const Scalar _tmp3 = _tmp2 * state(2, 0); + const Scalar _tmp4 = _tmp1 + _tmp3; + const Scalar _tmp5 = std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp6 = std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp7 = -2 * _tmp5 - 2 * _tmp6 + 1; + const Scalar _tmp8 = _tmp7 + epsilon * ((((_tmp7) > 0) - ((_tmp7) < 0)) + Scalar(0.5)); + const Scalar _tmp9 = std::pow(_tmp8, Scalar(2)); + const Scalar _tmp10 = _tmp4 / _tmp9; + const Scalar _tmp11 = Scalar(1.0) / (_tmp8); + const Scalar _tmp12 = _tmp9 / (std::pow(_tmp4, Scalar(2)) + _tmp9); + const Scalar _tmp13 = _tmp12 * (_tmp10 * (_tmp1 - _tmp3) - + _tmp11 * (_tmp5 - _tmp6 - std::pow(state(0, 0), Scalar(2)) + + std::pow(state(2, 0), Scalar(2)))); + const Scalar _tmp14 = _tmp12 * (_tmp10 * (-_tmp2 * state(0, 0) + 2 * state(2, 0) * state(3, 0)) - + _tmp11 * (_tmp0 * state(2, 0) + _tmp2 * state(3, 0))); // Output terms (2) if (innov_var != nullptr) { Scalar& _innov_var = (*innov_var); - _innov_var = - R + _tmp10 * (P(0, 1) * _tmp13 + P(1, 1) * _tmp10 - P(2, 1) * _tmp14 + P(3, 1) * _tmp11) + - _tmp11 * (P(0, 3) * _tmp13 + P(1, 3) * _tmp10 - P(2, 3) * _tmp14 + P(3, 3) * _tmp11) + - _tmp13 * (P(0, 0) * _tmp13 + P(1, 0) * _tmp10 - P(2, 0) * _tmp14 + P(3, 0) * _tmp11) - - _tmp14 * (P(0, 2) * _tmp13 + P(1, 2) * _tmp10 - P(2, 2) * _tmp14 + P(3, 2) * _tmp11); + _innov_var = R + _tmp13 * (P(0, 2) * _tmp14 + P(2, 2) * _tmp13) + + _tmp14 * (P(0, 0) * _tmp14 + P(2, 0) * _tmp13); } if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); - _h(0, 0) = _tmp13; - _h(1, 0) = _tmp10; - _h(2, 0) = -_tmp14; - _h(3, 0) = _tmp11; + _h(0, 0) = _tmp14; + _h(2, 0) = _tmp13; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_312_innov_var_and_h_alternate.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_312_innov_var_and_h_alternate.h index 99e130f67651..07fd1091819a 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_312_innov_var_and_h_alternate.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_312_innov_var_and_h_alternate.h @@ -17,61 +17,58 @@ namespace sym { * * Args: * state: Matrix24_1 - * P: Matrix24_24 + * P: Matrix23_23 * R: Scalar * epsilon: Scalar * * Outputs: * innov_var: Scalar - * H: Matrix24_1 + * H: Matrix23_1 */ template void ComputeYaw312InnovVarAndHAlternate(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar R, + const matrix::Matrix& P, const Scalar R, const Scalar epsilon, Scalar* const innov_var = nullptr, - matrix::Matrix* const H = nullptr) { - // Total ops: 73 + matrix::Matrix* const H = nullptr) { + // Total ops: 57 // Input arrays // Intermediate terms (15) const Scalar _tmp0 = 2 * state(0, 0); - const Scalar _tmp1 = - -2 * std::pow(state(1, 0), Scalar(2)) - 2 * std::pow(state(3, 0), Scalar(2)) + 1; - const Scalar _tmp2 = 2 * state(2, 0); - const Scalar _tmp3 = -_tmp0 * state(3, 0) + _tmp2 * state(1, 0); - const Scalar _tmp4 = _tmp3 + epsilon * ((((_tmp3) > 0) - ((_tmp3) < 0)) + Scalar(0.5)); - const Scalar _tmp5 = std::pow(_tmp4, Scalar(2)); - const Scalar _tmp6 = _tmp1 / _tmp5; - const Scalar _tmp7 = 4 / _tmp4; - const Scalar _tmp8 = Scalar(1.0) / (std::pow(_tmp1, Scalar(2)) + _tmp5); - const Scalar _tmp9 = _tmp5 * _tmp8; - const Scalar _tmp10 = _tmp9 * (-_tmp0 * _tmp6 + _tmp7 * state(3, 0)); - const Scalar _tmp11 = 2 * _tmp1 * _tmp8; - const Scalar _tmp12 = _tmp11 * state(3, 0); - const Scalar _tmp13 = _tmp11 * state(1, 0); - const Scalar _tmp14 = _tmp9 * (_tmp2 * _tmp6 + _tmp7 * state(1, 0)); + const Scalar _tmp1 = 2 * state(1, 0); + const Scalar _tmp2 = std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp3 = std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp4 = -2 * _tmp2 - 2 * _tmp3 + 1; + const Scalar _tmp5 = -_tmp0 * state(3, 0); + const Scalar _tmp6 = _tmp1 * state(2, 0); + const Scalar _tmp7 = _tmp5 + _tmp6; + const Scalar _tmp8 = _tmp7 + epsilon * ((((_tmp7) > 0) - ((_tmp7) < 0)) + Scalar(0.5)); + const Scalar _tmp9 = std::pow(_tmp8, Scalar(2)); + const Scalar _tmp10 = _tmp4 / _tmp9; + const Scalar _tmp11 = Scalar(1.0) / (_tmp8); + const Scalar _tmp12 = _tmp9 / (std::pow(_tmp4, Scalar(2)) + _tmp9); + const Scalar _tmp13 = _tmp12 * (_tmp10 * (_tmp0 * state(2, 0) + _tmp1 * state(3, 0)) - + _tmp11 * (-_tmp1 * state(0, 0) + 2 * state(2, 0) * state(3, 0))); + const Scalar _tmp14 = _tmp12 * (_tmp10 * (_tmp2 - _tmp3 - std::pow(state(0, 0), Scalar(2)) + + std::pow(state(2, 0), Scalar(2))) - + _tmp11 * (_tmp5 - _tmp6)); // Output terms (2) if (innov_var != nullptr) { Scalar& _innov_var = (*innov_var); - _innov_var = - R - _tmp10 * (P(0, 3) * _tmp12 - P(1, 3) * _tmp14 - P(2, 3) * _tmp13 - P(3, 3) * _tmp10) + - _tmp12 * (P(0, 0) * _tmp12 - P(1, 0) * _tmp14 - P(2, 0) * _tmp13 - P(3, 0) * _tmp10) - - _tmp13 * (P(0, 2) * _tmp12 - P(1, 2) * _tmp14 - P(2, 2) * _tmp13 - P(3, 2) * _tmp10) - - _tmp14 * (P(0, 1) * _tmp12 - P(1, 1) * _tmp14 - P(2, 1) * _tmp13 - P(3, 1) * _tmp10); + _innov_var = R - _tmp13 * (-P(0, 0) * _tmp13 - P(2, 0) * _tmp14) - + _tmp14 * (-P(0, 2) * _tmp13 - P(2, 2) * _tmp14); } if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); - _h(0, 0) = _tmp12; - _h(1, 0) = -_tmp14; - _h(2, 0) = -_tmp13; - _h(3, 0) = -_tmp10; + _h(0, 0) = -_tmp13; + _h(2, 0) = -_tmp14; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_321_innov_var_and_h.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_321_innov_var_and_h.h index e7dad2479b46..3677dbac87c3 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_321_innov_var_and_h.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_321_innov_var_and_h.h @@ -17,61 +17,58 @@ namespace sym { * * Args: * state: Matrix24_1 - * P: Matrix24_24 + * P: Matrix23_23 * R: Scalar * epsilon: Scalar * * Outputs: * innov_var: Scalar - * H: Matrix24_1 + * H: Matrix23_1 */ template void ComputeYaw321InnovVarAndH(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar R, + const matrix::Matrix& P, const Scalar R, const Scalar epsilon, Scalar* const innov_var = nullptr, - matrix::Matrix* const H = nullptr) { - // Total ops: 70 + matrix::Matrix* const H = nullptr) { + // Total ops: 53 // Input arrays // Intermediate terms (15) - const Scalar _tmp0 = 2 * state(3, 0); - const Scalar _tmp1 = 2 * state(2, 0); - const Scalar _tmp2 = _tmp0 * state(0, 0) + _tmp1 * state(1, 0); - const Scalar _tmp3 = - -2 * std::pow(state(2, 0), Scalar(2)) - 2 * std::pow(state(3, 0), Scalar(2)) + 1; - const Scalar _tmp4 = _tmp3 + epsilon * ((((_tmp3) > 0) - ((_tmp3) < 0)) + Scalar(0.5)); - const Scalar _tmp5 = std::pow(_tmp4, Scalar(2)); - const Scalar _tmp6 = Scalar(1.0) / (std::pow(_tmp2, Scalar(2)) + _tmp5); - const Scalar _tmp7 = _tmp4 * _tmp6; - const Scalar _tmp8 = _tmp0 * _tmp7; - const Scalar _tmp9 = _tmp1 * _tmp7; - const Scalar _tmp10 = 4 * _tmp2 / _tmp5; - const Scalar _tmp11 = 2 / _tmp4; - const Scalar _tmp12 = _tmp5 * _tmp6; - const Scalar _tmp13 = _tmp12 * (_tmp10 * state(3, 0) + _tmp11 * state(0, 0)); - const Scalar _tmp14 = _tmp12 * (_tmp10 * state(2, 0) + _tmp11 * state(1, 0)); + const Scalar _tmp0 = 2 * state(0, 0); + const Scalar _tmp1 = _tmp0 * state(3, 0); + const Scalar _tmp2 = 2 * state(1, 0); + const Scalar _tmp3 = _tmp2 * state(2, 0); + const Scalar _tmp4 = _tmp1 + _tmp3; + const Scalar _tmp5 = std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp6 = std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp7 = -2 * _tmp5 - 2 * _tmp6 + 1; + const Scalar _tmp8 = _tmp7 + epsilon * ((((_tmp7) > 0) - ((_tmp7) < 0)) + Scalar(0.5)); + const Scalar _tmp9 = std::pow(_tmp8, Scalar(2)); + const Scalar _tmp10 = _tmp4 / _tmp9; + const Scalar _tmp11 = Scalar(1.0) / (_tmp8); + const Scalar _tmp12 = _tmp9 / (std::pow(_tmp4, Scalar(2)) + _tmp9); + const Scalar _tmp13 = _tmp12 * (-_tmp10 * (-_tmp1 + _tmp3) + + _tmp11 * (-_tmp5 + _tmp6 + std::pow(state(0, 0), Scalar(2)) - + std::pow(state(1, 0), Scalar(2)))); + const Scalar _tmp14 = _tmp12 * (-_tmp10 * (-_tmp0 * state(2, 0) - _tmp2 * state(3, 0)) + + _tmp11 * (_tmp2 * state(0, 0) - 2 * state(2, 0) * state(3, 0))); // Output terms (2) if (innov_var != nullptr) { Scalar& _innov_var = (*innov_var); - _innov_var = - R + _tmp13 * (P(0, 3) * _tmp8 + P(1, 3) * _tmp9 + P(2, 3) * _tmp14 + P(3, 3) * _tmp13) + - _tmp14 * (P(0, 2) * _tmp8 + P(1, 2) * _tmp9 + P(2, 2) * _tmp14 + P(3, 2) * _tmp13) + - _tmp8 * (P(0, 0) * _tmp8 + P(1, 0) * _tmp9 + P(2, 0) * _tmp14 + P(3, 0) * _tmp13) + - _tmp9 * (P(0, 1) * _tmp8 + P(1, 1) * _tmp9 + P(2, 1) * _tmp14 + P(3, 1) * _tmp13); + _innov_var = R + _tmp13 * (P(1, 2) * _tmp14 + P(2, 2) * _tmp13) + + _tmp14 * (P(1, 1) * _tmp14 + P(2, 1) * _tmp13); } if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); - _h(0, 0) = _tmp8; - _h(1, 0) = _tmp9; - _h(2, 0) = _tmp14; - _h(3, 0) = _tmp13; + _h(1, 0) = _tmp14; + _h(2, 0) = _tmp13; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_321_innov_var_and_h_alternate.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_321_innov_var_and_h_alternate.h index 0e588fdecf87..3f1876623740 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_321_innov_var_and_h_alternate.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/compute_yaw_321_innov_var_and_h_alternate.h @@ -17,61 +17,58 @@ namespace sym { * * Args: * state: Matrix24_1 - * P: Matrix24_24 + * P: Matrix23_23 * R: Scalar * epsilon: Scalar * * Outputs: * innov_var: Scalar - * H: Matrix24_1 + * H: Matrix23_1 */ template void ComputeYaw321InnovVarAndHAlternate(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar R, + const matrix::Matrix& P, const Scalar R, const Scalar epsilon, Scalar* const innov_var = nullptr, - matrix::Matrix* const H = nullptr) { - // Total ops: 75 + matrix::Matrix* const H = nullptr) { + // Total ops: 57 // Input arrays // Intermediate terms (15) const Scalar _tmp0 = 2 * state(2, 0); - const Scalar _tmp1 = - -2 * std::pow(state(2, 0), Scalar(2)) - 2 * std::pow(state(3, 0), Scalar(2)) + 1; - const Scalar _tmp2 = 2 * state(0, 0); - const Scalar _tmp3 = _tmp0 * state(1, 0) + _tmp2 * state(3, 0); - const Scalar _tmp4 = _tmp3 + epsilon * ((((_tmp3) > 0) - ((_tmp3) < 0)) + Scalar(0.5)); - const Scalar _tmp5 = std::pow(_tmp4, Scalar(2)); - const Scalar _tmp6 = Scalar(1.0) / (std::pow(_tmp1, Scalar(2)) + _tmp5); - const Scalar _tmp7 = _tmp1 * _tmp6; - const Scalar _tmp8 = _tmp0 * _tmp7; - const Scalar _tmp9 = 2 * _tmp7 * state(3, 0); - const Scalar _tmp10 = _tmp1 / _tmp5; - const Scalar _tmp11 = 4 / _tmp4; - const Scalar _tmp12 = _tmp5 * _tmp6; - const Scalar _tmp13 = _tmp12 * (-_tmp10 * _tmp2 - _tmp11 * state(3, 0)); - const Scalar _tmp14 = _tmp12 * (-2 * _tmp10 * state(1, 0) - _tmp11 * state(2, 0)); + const Scalar _tmp1 = 2 * state(1, 0); + const Scalar _tmp2 = 2 * state(0, 0) * state(3, 0); + const Scalar _tmp3 = _tmp1 * state(2, 0); + const Scalar _tmp4 = _tmp2 + _tmp3; + const Scalar _tmp5 = _tmp4 + epsilon * ((((_tmp4) > 0) - ((_tmp4) < 0)) + Scalar(0.5)); + const Scalar _tmp6 = Scalar(1.0) / (_tmp5); + const Scalar _tmp7 = std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp8 = std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp9 = -2 * _tmp7 - 2 * _tmp8 + 1; + const Scalar _tmp10 = std::pow(_tmp5, Scalar(2)); + const Scalar _tmp11 = _tmp9 / _tmp10; + const Scalar _tmp12 = _tmp10 / (_tmp10 + std::pow(_tmp9, Scalar(2))); + const Scalar _tmp13 = _tmp12 * (-_tmp11 * (-_tmp0 * state(3, 0) + _tmp1 * state(0, 0)) + + _tmp6 * (-_tmp0 * state(0, 0) - _tmp1 * state(3, 0))); + const Scalar _tmp14 = _tmp12 * (-_tmp11 * (-_tmp7 + _tmp8 + std::pow(state(0, 0), Scalar(2)) - + std::pow(state(1, 0), Scalar(2))) + + _tmp6 * (-_tmp2 + _tmp3)); // Output terms (2) if (innov_var != nullptr) { Scalar& _innov_var = (*innov_var); - _innov_var = - R - _tmp13 * (P(0, 3) * _tmp9 + P(1, 3) * _tmp8 - P(2, 3) * _tmp14 - P(3, 3) * _tmp13) - - _tmp14 * (P(0, 2) * _tmp9 + P(1, 2) * _tmp8 - P(2, 2) * _tmp14 - P(3, 2) * _tmp13) + - _tmp8 * (P(0, 1) * _tmp9 + P(1, 1) * _tmp8 - P(2, 1) * _tmp14 - P(3, 1) * _tmp13) + - _tmp9 * (P(0, 0) * _tmp9 + P(1, 0) * _tmp8 - P(2, 0) * _tmp14 - P(3, 0) * _tmp13); + _innov_var = R - _tmp13 * (-P(1, 1) * _tmp13 - P(2, 1) * _tmp14) - + _tmp14 * (-P(1, 2) * _tmp13 - P(2, 2) * _tmp14); } if (H != nullptr) { - matrix::Matrix& _h = (*H); + matrix::Matrix& _h = (*H); _h.setZero(); - _h(0, 0) = _tmp9; - _h(1, 0) = _tmp8; + _h(1, 0) = -_tmp13; _h(2, 0) = -_tmp14; - _h(3, 0) = -_tmp13; } } // NOLINT(readability/fn_size) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h index 3637c654a3fa..d5ab87e38eb7 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h @@ -17,7 +17,7 @@ namespace sym { * * Args: * state: Matrix24_1 - * P: Matrix24_24 + * P: Matrix23_23 * d_vel: Matrix31 * d_vel_dt: Scalar * d_vel_var: Matrix31 @@ -26,298 +26,335 @@ namespace sym { * d_ang_var: Scalar * * Outputs: - * res: Matrix24_24 + * res: Matrix23_23 */ template -matrix::Matrix PredictCovariance(const matrix::Matrix& state, - const matrix::Matrix& P, +matrix::Matrix PredictCovariance(const matrix::Matrix& state, + const matrix::Matrix& P, const matrix::Matrix& d_vel, const Scalar d_vel_dt, const matrix::Matrix& d_vel_var, const matrix::Matrix& d_ang, const Scalar d_ang_dt, const Scalar d_ang_var) { - // Total ops: 2882 + // Total ops: 2445 // Input arrays - // Intermediate terms (173) - const Scalar _tmp0 = Scalar(0.5) * d_ang(1, 0); - const Scalar _tmp1 = Scalar(0.5) * d_ang_dt; - const Scalar _tmp2 = _tmp1 * state(11, 0); - const Scalar _tmp3 = -_tmp0 + _tmp2; - const Scalar _tmp4 = Scalar(0.5) * d_ang(2, 0); - const Scalar _tmp5 = _tmp1 * state(12, 0); - const Scalar _tmp6 = -_tmp4 + _tmp5; - const Scalar _tmp7 = Scalar(0.5) * d_ang(0, 0); - const Scalar _tmp8 = _tmp1 * state(10, 0); - const Scalar _tmp9 = -_tmp7 + _tmp8; - const Scalar _tmp10 = _tmp1 * state(1, 0); - const Scalar _tmp11 = _tmp1 * state(3, 0); - const Scalar _tmp12 = _tmp1 * state(2, 0); - const Scalar _tmp13 = P(0, 10) + P(1, 10) * _tmp9 + P(10, 10) * _tmp10 + P(11, 10) * _tmp12 + - P(12, 10) * _tmp11 + P(2, 10) * _tmp3 + P(3, 10) * _tmp6; - const Scalar _tmp14 = P(0, 11) + P(1, 11) * _tmp9 + P(10, 11) * _tmp10 + P(11, 11) * _tmp12 + - P(12, 11) * _tmp11 + P(2, 11) * _tmp3 + P(3, 11) * _tmp6; - const Scalar _tmp15 = P(0, 12) + P(1, 12) * _tmp9 + P(10, 12) * _tmp10 + P(11, 12) * _tmp12 + - P(12, 12) * _tmp11 + P(2, 12) * _tmp3 + P(3, 12) * _tmp6; - const Scalar _tmp16 = P(0, 2) + P(1, 2) * _tmp9 + P(10, 2) * _tmp10 + P(11, 2) * _tmp12 + - P(12, 2) * _tmp11 + P(2, 2) * _tmp3 + P(3, 2) * _tmp6; - const Scalar _tmp17 = P(0, 3) + P(1, 3) * _tmp9 + P(10, 3) * _tmp10 + P(11, 3) * _tmp12 + - P(12, 3) * _tmp11 + P(2, 3) * _tmp3 + P(3, 3) * _tmp6; - const Scalar _tmp18 = P(11, 1) * _tmp1; - const Scalar _tmp19 = P(0, 1) + P(1, 1) * _tmp9 + P(10, 1) * _tmp10 + P(12, 1) * _tmp11 + - P(2, 1) * _tmp3 + P(3, 1) * _tmp6 + _tmp18 * state(2, 0); - const Scalar _tmp20 = std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp21 = Scalar(0.25) * d_ang_var; - const Scalar _tmp22 = _tmp20 * _tmp21; - const Scalar _tmp23 = P(0, 0) + P(1, 0) * _tmp9 + P(10, 0) * _tmp10 + P(11, 0) * _tmp12 + - P(12, 0) * _tmp11 + P(2, 0) * _tmp3 + P(3, 0) * _tmp6; - const Scalar _tmp24 = std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp25 = _tmp21 * _tmp24; - const Scalar _tmp26 = std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp27 = _tmp21 * _tmp26; - const Scalar _tmp28 = _tmp25 + _tmp27; - const Scalar _tmp29 = _tmp1 * state(0, 0); - const Scalar _tmp30 = _tmp21 * state(1, 0); - const Scalar _tmp31 = _tmp7 - _tmp8; - const Scalar _tmp32 = _tmp4 - _tmp5; - const Scalar _tmp33 = P(0, 12) * _tmp31 + P(1, 12) - P(10, 12) * _tmp29 + P(11, 12) * _tmp11 - - P(12, 12) * _tmp12 + P(2, 12) * _tmp32 + P(3, 12) * _tmp3; - const Scalar _tmp34 = P(0, 10) * _tmp31 + P(1, 10) - P(10, 10) * _tmp29 + P(11, 10) * _tmp11 - - P(12, 10) * _tmp12 + P(2, 10) * _tmp32 + P(3, 10) * _tmp3; - const Scalar _tmp35 = P(0, 11) * _tmp31 + P(1, 11) - P(10, 11) * _tmp29 + P(11, 11) * _tmp11 - - P(12, 11) * _tmp12 + P(2, 11) * _tmp32 + P(3, 11) * _tmp3; - const Scalar _tmp36 = P(0, 2) * _tmp31 + P(1, 2) - P(10, 2) * _tmp29 + P(11, 2) * _tmp11 - - P(12, 2) * _tmp12 + P(2, 2) * _tmp32 + P(3, 2) * _tmp3; - const Scalar _tmp37 = P(0, 3) * _tmp31 + P(1, 3) - P(10, 3) * _tmp29 + P(11, 3) * _tmp11 - - P(12, 3) * _tmp12 + P(2, 3) * _tmp32 + P(3, 3) * _tmp3; - const Scalar _tmp38 = P(0, 0) * _tmp31 + P(1, 0) - P(10, 0) * _tmp29 + P(11, 0) * _tmp11 - - P(12, 0) * _tmp12 + P(2, 0) * _tmp32 + P(3, 0) * _tmp3; - const Scalar _tmp39 = P(0, 1) * _tmp31 + P(1, 1) - P(10, 1) * _tmp29 - P(12, 1) * _tmp12 + - P(2, 1) * _tmp32 + P(3, 1) * _tmp3 + _tmp18 * state(3, 0); - const Scalar _tmp40 = _tmp21 * std::pow(state(0, 0), Scalar(2)); - const Scalar _tmp41 = _tmp22 + _tmp40; - const Scalar _tmp42 = _tmp21 * state(0, 0); - const Scalar _tmp43 = _tmp0 - _tmp2; - const Scalar _tmp44 = P(0, 0) * _tmp43 + P(1, 0) * _tmp6 - P(10, 0) * _tmp11 - P(11, 0) * _tmp29 + - P(12, 0) * _tmp10 + P(2, 0) + P(3, 0) * _tmp31; - const Scalar _tmp45 = P(0, 1) * _tmp43 + P(1, 1) * _tmp6 - P(10, 1) * _tmp11 + P(12, 1) * _tmp10 + - P(2, 1) + P(3, 1) * _tmp31 - _tmp18 * state(0, 0); - const Scalar _tmp46 = P(0, 3) * _tmp43 + P(1, 3) * _tmp6 - P(10, 3) * _tmp11 - P(11, 3) * _tmp29 + - P(12, 3) * _tmp10 + P(2, 3) + P(3, 3) * _tmp31; - const Scalar _tmp47 = P(0, 11) * _tmp43 + P(1, 11) * _tmp6 - P(10, 11) * _tmp11 - - P(11, 11) * _tmp29 + P(12, 11) * _tmp10 + P(2, 11) + P(3, 11) * _tmp31; - const Scalar _tmp48 = P(0, 10) * _tmp43 + P(1, 10) * _tmp6 - P(10, 10) * _tmp11 - - P(11, 10) * _tmp29 + P(12, 10) * _tmp10 + P(2, 10) + P(3, 10) * _tmp31; - const Scalar _tmp49 = P(0, 12) * _tmp43 + P(1, 12) * _tmp6 - P(10, 12) * _tmp11 - - P(11, 12) * _tmp29 + P(12, 12) * _tmp10 + P(2, 12) + P(3, 12) * _tmp31; - const Scalar _tmp50 = P(0, 2) * _tmp43 + P(1, 2) * _tmp6 - P(10, 2) * _tmp11 - P(11, 2) * _tmp29 + - P(12, 2) * _tmp10 + P(2, 2) + P(3, 2) * _tmp31; - const Scalar _tmp51 = P(0, 2) * _tmp32 + P(1, 2) * _tmp43 + P(10, 2) * _tmp12 - - P(11, 2) * _tmp10 - P(12, 2) * _tmp29 + P(2, 2) * _tmp9 + P(3, 2); - const Scalar _tmp52 = P(0, 1) * _tmp32 + P(1, 1) * _tmp43 + P(10, 1) * _tmp12 - - P(11, 1) * _tmp10 - P(12, 1) * _tmp29 + P(2, 1) * _tmp9 + P(3, 1); - const Scalar _tmp53 = P(0, 0) * _tmp32 + P(1, 0) * _tmp43 + P(10, 0) * _tmp12 - - P(11, 0) * _tmp10 - P(12, 0) * _tmp29 + P(2, 0) * _tmp9 + P(3, 0); - const Scalar _tmp54 = P(0, 11) * _tmp32 + P(1, 11) * _tmp43 + P(10, 11) * _tmp12 - - P(11, 11) * _tmp10 - P(12, 11) * _tmp29 + P(2, 11) * _tmp9 + P(3, 11); - const Scalar _tmp55 = P(0, 12) * _tmp32 + P(1, 12) * _tmp43 + P(10, 12) * _tmp12 - - P(11, 12) * _tmp10 - P(12, 12) * _tmp29 + P(2, 12) * _tmp9 + P(3, 12); - const Scalar _tmp56 = P(0, 10) * _tmp32 + P(1, 10) * _tmp43 + P(10, 10) * _tmp12 - - P(11, 10) * _tmp10 - P(12, 10) * _tmp29 + P(2, 10) * _tmp9 + P(3, 10); - const Scalar _tmp57 = P(0, 3) * _tmp32 + P(1, 3) * _tmp43 + P(10, 3) * _tmp12 - - P(11, 3) * _tmp10 - P(12, 3) * _tmp29 + P(2, 3) * _tmp9 + P(3, 3); - const Scalar _tmp58 = d_vel(2, 0) - d_vel_dt * state(15, 0); - const Scalar _tmp59 = 2 * state(2, 0); - const Scalar _tmp60 = _tmp58 * _tmp59; - const Scalar _tmp61 = d_vel(1, 0) - d_vel_dt * state(14, 0); - const Scalar _tmp62 = 2 * _tmp61; - const Scalar _tmp63 = _tmp62 * state(3, 0); - const Scalar _tmp64 = _tmp60 - _tmp63; - const Scalar _tmp65 = P(0, 13) + P(1, 13) * _tmp9 + P(10, 13) * _tmp10 + P(11, 13) * _tmp12 + - P(12, 13) * _tmp11 + P(2, 13) * _tmp3 + P(3, 13) * _tmp6; - const Scalar _tmp66 = -2 * _tmp20; - const Scalar _tmp67 = 1 - 2 * _tmp24; - const Scalar _tmp68 = _tmp66 + _tmp67; - const Scalar _tmp69 = _tmp68 * d_vel_dt; - const Scalar _tmp70 = P(0, 15) + P(1, 15) * _tmp9 + P(10, 15) * _tmp10 + P(11, 15) * _tmp12 + - P(12, 15) * _tmp11 + P(2, 15) * _tmp3 + P(3, 15) * _tmp6; - const Scalar _tmp71 = _tmp59 * state(0, 0); - const Scalar _tmp72 = 2 * state(1, 0); - const Scalar _tmp73 = _tmp72 * state(3, 0); - const Scalar _tmp74 = _tmp71 + _tmp73; - const Scalar _tmp75 = _tmp74 * d_vel_dt; - const Scalar _tmp76 = P(0, 14) + P(1, 14) * _tmp9 + P(10, 14) * _tmp10 + P(11, 14) * _tmp12 + - P(12, 14) * _tmp11 + P(2, 14) * _tmp3 + P(3, 14) * _tmp6; - const Scalar _tmp77 = 2 * state(0, 0); - const Scalar _tmp78 = _tmp77 * state(3, 0); - const Scalar _tmp79 = _tmp59 * state(1, 0); - const Scalar _tmp80 = -_tmp78 + _tmp79; - const Scalar _tmp81 = _tmp80 * d_vel_dt; - const Scalar _tmp82 = 2 * _tmp58; - const Scalar _tmp83 = _tmp82 * state(3, 0); - const Scalar _tmp84 = _tmp59 * _tmp61; - const Scalar _tmp85 = _tmp83 + _tmp84; - const Scalar _tmp86 = d_vel(0, 0) - d_vel_dt * state(13, 0); - const Scalar _tmp87 = 4 * _tmp86; - const Scalar _tmp88 = _tmp82 * state(0, 0); - const Scalar _tmp89 = _tmp62 * state(1, 0); - const Scalar _tmp90 = -_tmp87 * state(2, 0) + _tmp88 + _tmp89; - const Scalar _tmp91 = _tmp82 * state(1, 0); - const Scalar _tmp92 = _tmp62 * state(0, 0); - const Scalar _tmp93 = -_tmp87 * state(3, 0) + _tmp91 - _tmp92; - const Scalar _tmp94 = P(11, 4) * _tmp1; - const Scalar _tmp95 = P(0, 4) + P(1, 4) * _tmp9 + P(10, 4) * _tmp10 + P(12, 4) * _tmp11 + - P(2, 4) * _tmp3 + P(3, 4) * _tmp6 + _tmp94 * state(2, 0); - const Scalar _tmp96 = P(0, 13) * _tmp31 + P(1, 13) - P(10, 13) * _tmp29 + P(11, 13) * _tmp11 - - P(12, 13) * _tmp12 + P(2, 13) * _tmp32 + P(3, 13) * _tmp3; - const Scalar _tmp97 = P(0, 14) * _tmp31 + P(1, 14) - P(10, 14) * _tmp29 + P(11, 14) * _tmp11 - - P(12, 14) * _tmp12 + P(2, 14) * _tmp32 + P(3, 14) * _tmp3; - const Scalar _tmp98 = P(0, 15) * _tmp31 + P(1, 15) - P(10, 15) * _tmp29 + P(11, 15) * _tmp11 - - P(12, 15) * _tmp12 + P(2, 15) * _tmp32 + P(3, 15) * _tmp3; - const Scalar _tmp99 = P(0, 4) * _tmp31 + P(1, 4) - P(10, 4) * _tmp29 - P(12, 4) * _tmp12 + - P(2, 4) * _tmp32 + P(3, 4) * _tmp3 + _tmp94 * state(3, 0); - const Scalar _tmp100 = P(0, 13) * _tmp43 + P(1, 13) * _tmp6 - P(10, 13) * _tmp11 - - P(11, 13) * _tmp29 + P(12, 13) * _tmp10 + P(2, 13) + P(3, 13) * _tmp31; - const Scalar _tmp101 = P(0, 14) * _tmp43 + P(1, 14) * _tmp6 - P(10, 14) * _tmp11 - - P(11, 14) * _tmp29 + P(12, 14) * _tmp10 + P(2, 14) + P(3, 14) * _tmp31; - const Scalar _tmp102 = P(0, 15) * _tmp43 + P(1, 15) * _tmp6 - P(10, 15) * _tmp11 - - P(11, 15) * _tmp29 + P(12, 15) * _tmp10 + P(2, 15) + P(3, 15) * _tmp31; - const Scalar _tmp103 = P(0, 4) * _tmp43 + P(1, 4) * _tmp6 - P(10, 4) * _tmp11 + - P(12, 4) * _tmp10 + P(2, 4) + P(3, 4) * _tmp31 - _tmp94 * state(0, 0); - const Scalar _tmp104 = P(0, 13) * _tmp32 + P(1, 13) * _tmp43 + P(10, 13) * _tmp12 - - P(11, 13) * _tmp10 - P(12, 13) * _tmp29 + P(2, 13) * _tmp9 + P(3, 13); - const Scalar _tmp105 = P(0, 14) * _tmp32 + P(1, 14) * _tmp43 + P(10, 14) * _tmp12 - - P(11, 14) * _tmp10 - P(12, 14) * _tmp29 + P(2, 14) * _tmp9 + P(3, 14); - const Scalar _tmp106 = P(0, 15) * _tmp32 + P(1, 15) * _tmp43 + P(10, 15) * _tmp12 - - P(11, 15) * _tmp10 - P(12, 15) * _tmp29 + P(2, 15) * _tmp9 + P(3, 15); - const Scalar _tmp107 = P(0, 4) * _tmp32 + P(1, 4) * _tmp43 + P(10, 4) * _tmp12 - - P(12, 4) * _tmp29 + P(2, 4) * _tmp9 + P(3, 4) - _tmp94 * state(1, 0); - const Scalar _tmp108 = P(0, 13) * _tmp64 + P(1, 13) * _tmp85 - P(13, 13) * _tmp69 - - P(14, 13) * _tmp81 - P(15, 13) * _tmp75 + P(2, 13) * _tmp90 + - P(3, 13) * _tmp93 + P(4, 13); - const Scalar _tmp109 = P(0, 14) * _tmp64 + P(1, 14) * _tmp85 - P(13, 14) * _tmp69 - - P(14, 14) * _tmp81 - P(15, 14) * _tmp75 + P(2, 14) * _tmp90 + - P(3, 14) * _tmp93 + P(4, 14); - const Scalar _tmp110 = P(0, 15) * _tmp64 + P(1, 15) * _tmp85 - P(13, 15) * _tmp69 - - P(14, 15) * _tmp81 - P(15, 15) * _tmp75 + P(2, 15) * _tmp90 + - P(3, 15) * _tmp93 + P(4, 15); - const Scalar _tmp111 = P(0, 1) * _tmp64 + P(1, 1) * _tmp85 - P(13, 1) * _tmp69 - - P(14, 1) * _tmp81 - P(15, 1) * _tmp75 + P(2, 1) * _tmp90 + - P(3, 1) * _tmp93 + P(4, 1); - const Scalar _tmp112 = P(0, 0) * _tmp64 + P(1, 0) * _tmp85 - P(13, 0) * _tmp69 - - P(14, 0) * _tmp81 - P(15, 0) * _tmp75 + P(2, 0) * _tmp90 + - P(3, 0) * _tmp93 + P(4, 0); - const Scalar _tmp113 = P(0, 3) * _tmp64 + P(1, 3) * _tmp85 - P(13, 3) * _tmp69 - - P(14, 3) * _tmp81 - P(15, 3) * _tmp75 + P(2, 3) * _tmp90 + - P(3, 3) * _tmp93 + P(4, 3); - const Scalar _tmp114 = P(0, 2) * _tmp64 + P(1, 2) * _tmp85 - P(13, 2) * _tmp69 - - P(14, 2) * _tmp81 - P(15, 2) * _tmp75 + P(2, 2) * _tmp90 + - P(3, 2) * _tmp93 + P(4, 2); - const Scalar _tmp115 = P(0, 4) * _tmp64 + P(1, 4) * _tmp85 - P(13, 4) * _tmp69 - - P(14, 4) * _tmp81 - P(15, 4) * _tmp75 + P(2, 4) * _tmp90 + - P(3, 4) * _tmp93 + P(4, 4); - const Scalar _tmp116 = _tmp59 * state(3, 0); - const Scalar _tmp117 = _tmp72 * state(0, 0); - const Scalar _tmp118 = _tmp116 - _tmp117; - const Scalar _tmp119 = _tmp118 * d_vel_dt; - const Scalar _tmp120 = -2 * _tmp26; - const Scalar _tmp121 = _tmp120 + _tmp67; - const Scalar _tmp122 = _tmp121 * d_vel_dt; - const Scalar _tmp123 = _tmp78 + _tmp79; - const Scalar _tmp124 = _tmp123 * d_vel_dt; - const Scalar _tmp125 = _tmp59 * _tmp86; - const Scalar _tmp126 = 4 * _tmp61; - const Scalar _tmp127 = _tmp125 - _tmp126 * state(1, 0) - _tmp88; - const Scalar _tmp128 = _tmp77 * _tmp86; - const Scalar _tmp129 = -_tmp126 * state(3, 0) + _tmp128 + _tmp60; - const Scalar _tmp130 = 2 * _tmp86 * state(3, 0); - const Scalar _tmp131 = _tmp130 - _tmp91; - const Scalar _tmp132 = _tmp72 * _tmp86; - const Scalar _tmp133 = _tmp132 + _tmp83; - const Scalar _tmp134 = P(0, 5) + P(1, 5) * _tmp9 + P(10, 5) * _tmp10 + P(11, 5) * _tmp12 + - P(12, 5) * _tmp11 + P(2, 5) * _tmp3 + P(3, 5) * _tmp6; - const Scalar _tmp135 = P(0, 5) * _tmp31 + P(1, 5) - P(10, 5) * _tmp29 + P(11, 5) * _tmp11 - - P(12, 5) * _tmp12 + P(2, 5) * _tmp32 + P(3, 5) * _tmp3; - const Scalar _tmp136 = P(0, 5) * _tmp43 + P(1, 5) * _tmp6 - P(10, 5) * _tmp11 - - P(11, 5) * _tmp29 + P(12, 5) * _tmp10 + P(2, 5) + P(3, 5) * _tmp31; - const Scalar _tmp137 = P(0, 5) * _tmp32 + P(1, 5) * _tmp43 + P(10, 5) * _tmp12 - - P(11, 5) * _tmp10 - P(12, 5) * _tmp29 + P(2, 5) * _tmp9 + P(3, 5); - const Scalar _tmp138 = _tmp123 * d_vel_var(0, 0); - const Scalar _tmp139 = _tmp80 * d_vel_var(1, 0); - const Scalar _tmp140 = P(0, 5) * _tmp64 + P(1, 5) * _tmp85 - P(13, 5) * _tmp69 - - P(14, 5) * _tmp81 - P(15, 5) * _tmp75 + P(2, 5) * _tmp90 + - P(3, 5) * _tmp93 + P(4, 5); - const Scalar _tmp141 = P(0, 13) * _tmp131 + P(1, 13) * _tmp127 - P(13, 13) * _tmp124 - - P(14, 13) * _tmp122 - P(15, 13) * _tmp119 + P(2, 13) * _tmp133 + - P(3, 13) * _tmp129 + P(5, 13); - const Scalar _tmp142 = P(0, 14) * _tmp131 + P(1, 14) * _tmp127 - P(13, 14) * _tmp124 - - P(14, 14) * _tmp122 - P(15, 14) * _tmp119 + P(2, 14) * _tmp133 + - P(3, 14) * _tmp129 + P(5, 14); - const Scalar _tmp143 = P(0, 15) * _tmp131 + P(1, 15) * _tmp127 - P(13, 15) * _tmp124 - - P(14, 15) * _tmp122 - P(15, 15) * _tmp119 + P(2, 15) * _tmp133 + - P(3, 15) * _tmp129 + P(5, 15); - const Scalar _tmp144 = P(0, 2) * _tmp131 + P(1, 2) * _tmp127 - P(13, 2) * _tmp124 - - P(14, 2) * _tmp122 - P(15, 2) * _tmp119 + P(2, 2) * _tmp133 + - P(3, 2) * _tmp129 + P(5, 2); - const Scalar _tmp145 = P(0, 0) * _tmp131 + P(1, 0) * _tmp127 - P(13, 0) * _tmp124 - - P(14, 0) * _tmp122 - P(15, 0) * _tmp119 + P(2, 0) * _tmp133 + - P(3, 0) * _tmp129 + P(5, 0); - const Scalar _tmp146 = P(0, 3) * _tmp131 + P(1, 3) * _tmp127 - P(13, 3) * _tmp124 - - P(14, 3) * _tmp122 - P(15, 3) * _tmp119 + P(2, 3) * _tmp133 + - P(3, 3) * _tmp129 + P(5, 3); - const Scalar _tmp147 = P(0, 1) * _tmp131 + P(1, 1) * _tmp127 - P(13, 1) * _tmp124 - - P(14, 1) * _tmp122 - P(15, 1) * _tmp119 + P(2, 1) * _tmp133 + - P(3, 1) * _tmp129 + P(5, 1); - const Scalar _tmp148 = P(0, 5) * _tmp131 + P(1, 5) * _tmp127 - P(13, 5) * _tmp124 - - P(14, 5) * _tmp122 - P(15, 5) * _tmp119 + P(2, 5) * _tmp133 + - P(3, 5) * _tmp129 + P(5, 5); - const Scalar _tmp149 = _tmp116 + _tmp117; - const Scalar _tmp150 = _tmp149 * d_vel_dt; - const Scalar _tmp151 = _tmp120 + _tmp66 + 1; - const Scalar _tmp152 = _tmp151 * d_vel_dt; - const Scalar _tmp153 = -_tmp71 + _tmp73; - const Scalar _tmp154 = _tmp153 * d_vel_dt; - const Scalar _tmp155 = 4 * _tmp58; - const Scalar _tmp156 = _tmp130 - _tmp155 * state(1, 0) + _tmp92; - const Scalar _tmp157 = -_tmp128 - _tmp155 * state(2, 0) + _tmp63; - const Scalar _tmp158 = -_tmp125 + _tmp89; - const Scalar _tmp159 = _tmp132 + _tmp84; - const Scalar _tmp160 = P(11, 6) * _tmp1; - const Scalar _tmp161 = P(0, 6) + P(1, 6) * _tmp9 + P(10, 6) * _tmp10 + P(12, 6) * _tmp11 + - P(2, 6) * _tmp3 + P(3, 6) * _tmp6 + _tmp160 * state(2, 0); - const Scalar _tmp162 = P(0, 6) * _tmp31 + P(1, 6) - P(10, 6) * _tmp29 - P(12, 6) * _tmp12 + - P(2, 6) * _tmp32 + P(3, 6) * _tmp3 + _tmp160 * state(3, 0); - const Scalar _tmp163 = P(0, 6) * _tmp43 + P(1, 6) * _tmp6 - P(10, 6) * _tmp11 + - P(12, 6) * _tmp10 + P(2, 6) + P(3, 6) * _tmp31 - _tmp160 * state(0, 0); - const Scalar _tmp164 = P(0, 6) * _tmp32 + P(1, 6) * _tmp43 + P(10, 6) * _tmp12 - - P(11, 6) * _tmp10 - P(12, 6) * _tmp29 + P(2, 6) * _tmp9 + P(3, 6); - const Scalar _tmp165 = _tmp151 * d_vel_var(2, 0); - const Scalar _tmp166 = P(0, 6) * _tmp64 + P(1, 6) * _tmp85 - P(13, 6) * _tmp69 - - P(14, 6) * _tmp81 - P(15, 6) * _tmp75 + P(2, 6) * _tmp90 + - P(3, 6) * _tmp93 + P(4, 6); - const Scalar _tmp167 = P(0, 6) * _tmp131 + P(1, 6) * _tmp127 - P(13, 6) * _tmp124 - - P(14, 6) * _tmp122 - P(15, 6) * _tmp119 + P(2, 6) * _tmp133 + - P(3, 6) * _tmp129 + P(5, 6); - const Scalar _tmp168 = P(0, 13) * _tmp158 + P(1, 13) * _tmp156 - P(13, 13) * _tmp154 - - P(14, 13) * _tmp150 - P(15, 13) * _tmp152 + P(2, 13) * _tmp157 + - P(3, 13) * _tmp159 + P(6, 13); - const Scalar _tmp169 = P(0, 14) * _tmp158 + P(1, 14) * _tmp156 - P(13, 14) * _tmp154 - - P(14, 14) * _tmp150 - P(15, 14) * _tmp152 + P(2, 14) * _tmp157 + - P(3, 14) * _tmp159 + P(6, 14); - const Scalar _tmp170 = P(0, 15) * _tmp158 + P(1, 15) * _tmp156 - P(13, 15) * _tmp154 - - P(14, 15) * _tmp150 - P(15, 15) * _tmp152 + P(2, 15) * _tmp157 + - P(3, 15) * _tmp159 + P(6, 15); - const Scalar _tmp171 = P(0, 6) * _tmp158 + P(1, 6) * _tmp156 - P(13, 6) * _tmp154 - - P(14, 6) * _tmp150 - P(15, 6) * _tmp152 + P(2, 6) * _tmp157 + - P(3, 6) * _tmp159 + P(6, 6); - const Scalar _tmp172 = P(11, 8) * _tmp1; + // Intermediate terms (247) + const Scalar _tmp0 = d_ang(1, 0) - d_ang_dt * state(11, 0); + const Scalar _tmp1 = Scalar(0.5) * state(2, 0); + const Scalar _tmp2 = d_ang(0, 0) - d_ang_dt * state(10, 0); + const Scalar _tmp3 = Scalar(0.5) * state(1, 0); + const Scalar _tmp4 = d_ang(2, 0) - d_ang_dt * state(12, 0); + const Scalar _tmp5 = Scalar(0.5) * state(3, 0); + const Scalar _tmp6 = -_tmp0 * _tmp1 - _tmp2 * _tmp3 - _tmp4 * _tmp5 + state(0, 0); + const Scalar _tmp7 = Scalar(1.0) * _tmp6; + const Scalar _tmp8 = _tmp7 * state(0, 0); + const Scalar _tmp9 = Scalar(0.5) * state(0, 0); + const Scalar _tmp10 = _tmp0 * _tmp3 - _tmp1 * _tmp2 + _tmp4 * _tmp9 + state(3, 0); + const Scalar _tmp11 = Scalar(1.0) * _tmp10; + const Scalar _tmp12 = _tmp11 * state(3, 0); + const Scalar _tmp13 = _tmp0 * _tmp9 + _tmp2 * _tmp5 - _tmp3 * _tmp4 + state(2, 0); + const Scalar _tmp14 = Scalar(1.0) * state(2, 0); + const Scalar _tmp15 = _tmp13 * _tmp14; + const Scalar _tmp16 = -_tmp0 * _tmp5 + _tmp1 * _tmp4 + _tmp2 * _tmp9 + state(1, 0); + const Scalar _tmp17 = Scalar(1.0) * _tmp16; + const Scalar _tmp18 = _tmp17 * state(1, 0); + const Scalar _tmp19 = + -_tmp12 * d_ang_dt - _tmp15 * d_ang_dt - _tmp18 * d_ang_dt - _tmp8 * d_ang_dt; + const Scalar _tmp20 = -_tmp5; + const Scalar _tmp21 = Scalar(0.25) * _tmp4; + const Scalar _tmp22 = _tmp21 * state(0, 0); + const Scalar _tmp23 = Scalar(0.25) * _tmp0; + const Scalar _tmp24 = _tmp23 * state(1, 0); + const Scalar _tmp25 = Scalar(0.25) * _tmp2; + const Scalar _tmp26 = -_tmp25 * state(2, 0); + const Scalar _tmp27 = -_tmp24 + _tmp26; + const Scalar _tmp28 = _tmp20 + _tmp22 + _tmp27; + const Scalar _tmp29 = 2 * _tmp6; + const Scalar _tmp30 = _tmp25 * state(0, 0); + const Scalar _tmp31 = -_tmp30; + const Scalar _tmp32 = -_tmp23 * state(3, 0); + const Scalar _tmp33 = _tmp21 * state(2, 0); + const Scalar _tmp34 = _tmp32 - _tmp33; + const Scalar _tmp35 = _tmp3 + _tmp31 + _tmp34; + const Scalar _tmp36 = 2 * _tmp13; + const Scalar _tmp37 = _tmp23 * state(2, 0); + const Scalar _tmp38 = _tmp25 * state(1, 0); + const Scalar _tmp39 = _tmp21 * state(3, 0); + const Scalar _tmp40 = -_tmp37 + _tmp38 + _tmp39 + _tmp9; + const Scalar _tmp41 = 2 * _tmp10; + const Scalar _tmp42 = _tmp23 * state(0, 0); + const Scalar _tmp43 = -_tmp42; + const Scalar _tmp44 = _tmp25 * state(3, 0); + const Scalar _tmp45 = -_tmp21 * state(1, 0); + const Scalar _tmp46 = -_tmp1 + _tmp45; + const Scalar _tmp47 = _tmp43 + _tmp44 + _tmp46; + const Scalar _tmp48 = 2 * _tmp16; + const Scalar _tmp49 = _tmp28 * _tmp29 - _tmp35 * _tmp36 + _tmp40 * _tmp41 - _tmp47 * _tmp48; + const Scalar _tmp50 = -_tmp44; + const Scalar _tmp51 = _tmp1 + _tmp43 + _tmp45 + _tmp50; + const Scalar _tmp52 = _tmp37 + _tmp9; + const Scalar _tmp53 = _tmp38 - _tmp39 + _tmp52; + const Scalar _tmp54 = -_tmp3; + const Scalar _tmp55 = _tmp30 + _tmp34 + _tmp54; + const Scalar _tmp56 = -_tmp22; + const Scalar _tmp57 = _tmp20 + _tmp24 + _tmp26 + _tmp56; + const Scalar _tmp58 = _tmp29 * _tmp51 - _tmp36 * _tmp53 + _tmp41 * _tmp55 - _tmp48 * _tmp57; + const Scalar _tmp59 = -_tmp38 + _tmp39 + _tmp52; + const Scalar _tmp60 = _tmp42 + _tmp46 + _tmp50; + const Scalar _tmp61 = _tmp27 + _tmp5 + _tmp56; + const Scalar _tmp62 = _tmp31 + _tmp32 + _tmp33 + _tmp54; + const Scalar _tmp63 = _tmp29 * _tmp59 - _tmp36 * _tmp60 + _tmp41 * _tmp61 - _tmp48 * _tmp62; + const Scalar _tmp64 = _tmp14 * _tmp6; + const Scalar _tmp65 = _tmp64 * d_ang_dt; + const Scalar _tmp66 = _tmp11 * state(1, 0); + const Scalar _tmp67 = _tmp66 * d_ang_dt; + const Scalar _tmp68 = Scalar(1.0) * _tmp13; + const Scalar _tmp69 = _tmp68 * state(0, 0); + const Scalar _tmp70 = _tmp69 * d_ang_dt; + const Scalar _tmp71 = _tmp17 * state(3, 0); + const Scalar _tmp72 = _tmp71 * d_ang_dt; + const Scalar _tmp73 = -_tmp65 + _tmp67 + _tmp70 - _tmp72; + const Scalar _tmp74 = _tmp7 * state(3, 0); + const Scalar _tmp75 = _tmp74 * d_ang_dt; + const Scalar _tmp76 = _tmp14 * _tmp16; + const Scalar _tmp77 = _tmp76 * d_ang_dt; + const Scalar _tmp78 = _tmp11 * state(0, 0); + const Scalar _tmp79 = _tmp78 * d_ang_dt; + const Scalar _tmp80 = _tmp68 * state(1, 0); + const Scalar _tmp81 = _tmp80 * d_ang_dt; + const Scalar _tmp82 = _tmp75 - _tmp77 - _tmp79 + _tmp81; + const Scalar _tmp83 = P(0, 9) * _tmp63 + P(1, 9) * _tmp49 + P(10, 9) * _tmp82 + + P(11, 9) * _tmp73 + P(2, 9) * _tmp58 + P(9, 9) * _tmp19; + const Scalar _tmp84 = -_tmp64 + _tmp66 + _tmp69 - _tmp71; + const Scalar _tmp85 = _tmp74 - _tmp76 - _tmp78 + _tmp80; + const Scalar _tmp86 = -_tmp12 - _tmp15 - _tmp18 - _tmp8; + const Scalar _tmp87 = std::pow(_tmp86, Scalar(2)) * d_ang_var; + const Scalar _tmp88 = P(0, 0) * _tmp63 + P(1, 0) * _tmp49 + P(10, 0) * _tmp82 + + P(11, 0) * _tmp73 + P(2, 0) * _tmp58 + P(9, 0) * _tmp19; + const Scalar _tmp89 = P(0, 1) * _tmp63 + P(1, 1) * _tmp49 + P(10, 1) * _tmp82 + + P(11, 1) * _tmp73 + P(2, 1) * _tmp58 + P(9, 1) * _tmp19; + const Scalar _tmp90 = P(0, 2) * _tmp63 + P(1, 2) * _tmp49 + P(10, 2) * _tmp82 + + P(11, 2) * _tmp73 + P(2, 2) * _tmp58 + P(9, 2) * _tmp19; + const Scalar _tmp91 = P(0, 11) * _tmp63 + P(1, 11) * _tmp49 + P(10, 11) * _tmp82 + + P(11, 11) * _tmp73 + P(2, 11) * _tmp58 + P(9, 11) * _tmp19; + const Scalar _tmp92 = P(0, 10) * _tmp63 + P(1, 10) * _tmp49 + P(10, 10) * _tmp82 + + P(11, 10) * _tmp73 + P(2, 10) * _tmp58 + P(9, 10) * _tmp19; + const Scalar _tmp93 = _tmp17 * state(0, 0); + const Scalar _tmp94 = _tmp10 * _tmp14; + const Scalar _tmp95 = _tmp68 * state(3, 0); + const Scalar _tmp96 = _tmp7 * state(1, 0); + const Scalar _tmp97 = -_tmp93 + _tmp94 - _tmp95 + _tmp96; + const Scalar _tmp98 = _tmp97 * d_ang_var; + const Scalar _tmp99 = _tmp86 * d_ang_var; + const Scalar _tmp100 = -_tmp74 + _tmp76 + _tmp78 - _tmp80; + const Scalar _tmp101 = -_tmp75 + _tmp77 + _tmp79 - _tmp81; + const Scalar _tmp102 = -_tmp28 * _tmp41 + _tmp29 * _tmp40 + _tmp35 * _tmp48 - _tmp36 * _tmp47; + const Scalar _tmp103 = _tmp29 * _tmp55 - _tmp36 * _tmp57 - _tmp41 * _tmp51 + _tmp48 * _tmp53; + const Scalar _tmp104 = 2 * _tmp62; + const Scalar _tmp105 = -_tmp104 * _tmp13 + _tmp29 * _tmp61 - _tmp41 * _tmp59 + _tmp48 * _tmp60; + const Scalar _tmp106 = _tmp96 * d_ang_dt; + const Scalar _tmp107 = _tmp95 * d_ang_dt; + const Scalar _tmp108 = _tmp94 * d_ang_dt; + const Scalar _tmp109 = _tmp93 * d_ang_dt; + const Scalar _tmp110 = _tmp106 - _tmp107 + _tmp108 - _tmp109; + const Scalar _tmp111 = P(0, 9) * _tmp105 + P(1, 9) * _tmp102 + P(10, 9) * _tmp19 + + P(11, 9) * _tmp110 + P(2, 9) * _tmp103 + P(9, 9) * _tmp101; + const Scalar _tmp112 = P(0, 2) * _tmp105 + P(1, 2) * _tmp102 + P(10, 2) * _tmp19 + + P(11, 2) * _tmp110 + P(2, 2) * _tmp103 + P(9, 2) * _tmp101; + const Scalar _tmp113 = P(0, 1) * _tmp105 + P(1, 1) * _tmp102 + P(10, 1) * _tmp19 + + P(11, 1) * _tmp110 + P(2, 1) * _tmp103 + P(9, 1) * _tmp101; + const Scalar _tmp114 = P(0, 0) * _tmp105 + P(1, 0) * _tmp102 + P(10, 0) * _tmp19 + + P(11, 0) * _tmp110 + P(2, 0) * _tmp103 + P(9, 0) * _tmp101; + const Scalar _tmp115 = P(0, 10) * _tmp105 + P(1, 10) * _tmp102 + P(10, 10) * _tmp19 + + P(11, 10) * _tmp110 + P(2, 10) * _tmp103 + P(9, 10) * _tmp101; + const Scalar _tmp116 = P(0, 11) * _tmp105 + P(1, 11) * _tmp102 + P(10, 11) * _tmp19 + + P(11, 11) * _tmp110 + P(2, 11) * _tmp103 + P(9, 11) * _tmp101; + const Scalar _tmp117 = _tmp93 - _tmp94 + _tmp95 - _tmp96; + const Scalar _tmp118 = _tmp117 * d_ang_var; + const Scalar _tmp119 = _tmp64 - _tmp66 - _tmp69 + _tmp71; + const Scalar _tmp120 = _tmp119 * d_ang_var; + const Scalar _tmp121 = _tmp65 - _tmp67 - _tmp70 + _tmp72; + const Scalar _tmp122 = _tmp29 * _tmp53 + _tmp36 * _tmp51 - _tmp41 * _tmp57 - _tmp48 * _tmp55; + const Scalar _tmp123 = _tmp28 * _tmp36 + _tmp29 * _tmp35 - _tmp40 * _tmp48 - _tmp41 * _tmp47; + const Scalar _tmp124 = -_tmp10 * _tmp104 + _tmp29 * _tmp60 + _tmp36 * _tmp59 - _tmp48 * _tmp61; + const Scalar _tmp125 = -_tmp106 + _tmp107 - _tmp108 + _tmp109; + const Scalar _tmp126 = P(0, 2) * _tmp124 + P(1, 2) * _tmp123 + P(10, 2) * _tmp125 + + P(11, 2) * _tmp19 + P(2, 2) * _tmp122 + P(9, 2) * _tmp121; + const Scalar _tmp127 = P(0, 9) * _tmp124 + P(1, 9) * _tmp123 + P(10, 9) * _tmp125 + + P(11, 9) * _tmp19 + P(2, 9) * _tmp122 + P(9, 9) * _tmp121; + const Scalar _tmp128 = P(0, 11) * _tmp124 + P(1, 11) * _tmp123 + P(10, 11) * _tmp125 + + P(11, 11) * _tmp19 + P(2, 11) * _tmp122 + P(9, 11) * _tmp121; + const Scalar _tmp129 = P(0, 10) * _tmp124 + P(1, 10) * _tmp123 + P(10, 10) * _tmp125 + + P(11, 10) * _tmp19 + P(2, 10) * _tmp122 + P(9, 10) * _tmp121; + const Scalar _tmp130 = P(0, 0) * _tmp124 + P(1, 0) * _tmp123 + P(10, 0) * _tmp125 + + P(11, 0) * _tmp19 + P(2, 0) * _tmp122 + P(9, 0) * _tmp121; + const Scalar _tmp131 = P(0, 1) * _tmp124 + P(1, 1) * _tmp123 + P(10, 1) * _tmp125 + + P(11, 1) * _tmp19 + P(2, 1) * _tmp122 + P(9, 1) * _tmp121; + const Scalar _tmp132 = P(0, 13) * _tmp63 + P(1, 13) * _tmp49 + P(10, 13) * _tmp82 + + P(11, 13) * _tmp73 + P(2, 13) * _tmp58 + P(9, 13) * _tmp19; + const Scalar _tmp133 = 2 * state(0, 0); + const Scalar _tmp134 = _tmp133 * state(3, 0); + const Scalar _tmp135 = 2 * state(2, 0); + const Scalar _tmp136 = _tmp135 * state(1, 0); + const Scalar _tmp137 = -_tmp134 + _tmp136; + const Scalar _tmp138 = _tmp137 * d_vel_dt; + const Scalar _tmp139 = P(0, 14) * _tmp63 + P(1, 14) * _tmp49 + P(10, 14) * _tmp82 + + P(11, 14) * _tmp73 + P(2, 14) * _tmp58 + P(9, 14) * _tmp19; + const Scalar _tmp140 = _tmp135 * state(0, 0); + const Scalar _tmp141 = state(1, 0) * state(3, 0); + const Scalar _tmp142 = 2 * _tmp141; + const Scalar _tmp143 = _tmp140 + _tmp142; + const Scalar _tmp144 = _tmp143 * d_vel_dt; + const Scalar _tmp145 = Scalar(2.0) * state(0, 0); + const Scalar _tmp146 = _tmp145 * state(2, 0); + const Scalar _tmp147 = Scalar(2.0) * _tmp141; + const Scalar _tmp148 = d_vel(1, 0) - d_vel_dt * state(14, 0); + const Scalar _tmp149 = d_vel(2, 0) - d_vel_dt * state(15, 0); + const Scalar _tmp150 = _tmp145 * state(3, 0); + const Scalar _tmp151 = Scalar(2.0) * state(2, 0); + const Scalar _tmp152 = _tmp151 * state(1, 0); + const Scalar _tmp153 = -_tmp152; + const Scalar _tmp154 = _tmp148 * (_tmp146 + _tmp147) + _tmp149 * (_tmp150 + _tmp153); + const Scalar _tmp155 = Scalar(1.0) * std::pow(state(0, 0), Scalar(2)); + const Scalar _tmp156 = std::pow(state(2, 0), Scalar(2)); + const Scalar _tmp157 = Scalar(1.0) * _tmp156; + const Scalar _tmp158 = -_tmp157; + const Scalar _tmp159 = _tmp155 + _tmp158; + const Scalar _tmp160 = std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp161 = Scalar(1.0) * _tmp160; + const Scalar _tmp162 = std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp163 = Scalar(1.0) * _tmp162; + const Scalar _tmp164 = -_tmp163; + const Scalar _tmp165 = _tmp161 + _tmp164; + const Scalar _tmp166 = -_tmp146; + const Scalar _tmp167 = -_tmp147; + const Scalar _tmp168 = d_vel(0, 0) - d_vel_dt * state(13, 0); + const Scalar _tmp169 = _tmp149 * (_tmp159 + _tmp165) + _tmp168 * (_tmp166 + _tmp167); + const Scalar _tmp170 = -_tmp150; + const Scalar _tmp171 = -_tmp161; + const Scalar _tmp172 = _tmp163 + _tmp171; + const Scalar _tmp173 = -_tmp155; + const Scalar _tmp174 = _tmp157 + _tmp173; + const Scalar _tmp175 = _tmp148 * (_tmp172 + _tmp174) + _tmp168 * (_tmp152 + _tmp170); + const Scalar _tmp176 = P(0, 12) * _tmp63 + P(1, 12) * _tmp49 + P(10, 12) * _tmp82 + + P(11, 12) * _tmp73 + P(2, 12) * _tmp58 + P(9, 12) * _tmp19; + const Scalar _tmp177 = -2 * _tmp162; + const Scalar _tmp178 = 1 - 2 * _tmp156; + const Scalar _tmp179 = _tmp177 + _tmp178; + const Scalar _tmp180 = _tmp179 * d_vel_dt; + const Scalar _tmp181 = P(0, 3) * _tmp63 + P(1, 3) * _tmp49 + P(10, 3) * _tmp82 + + P(11, 3) * _tmp73 + P(2, 3) * _tmp58 + P(9, 3) * _tmp19; + const Scalar _tmp182 = P(0, 12) * _tmp105 + P(1, 12) * _tmp102 + P(10, 12) * _tmp19 + + P(11, 12) * _tmp110 + P(2, 12) * _tmp103 + P(9, 12) * _tmp101; + const Scalar _tmp183 = P(0, 14) * _tmp105 + P(1, 14) * _tmp102 + P(10, 14) * _tmp19 + + P(11, 14) * _tmp110 + P(2, 14) * _tmp103 + P(9, 14) * _tmp101; + const Scalar _tmp184 = P(0, 13) * _tmp105 + P(1, 13) * _tmp102 + P(10, 13) * _tmp19 + + P(11, 13) * _tmp110 + P(2, 13) * _tmp103 + P(9, 13) * _tmp101; + const Scalar _tmp185 = P(0, 3) * _tmp105 + P(1, 3) * _tmp102 + P(10, 3) * _tmp19 + + P(11, 3) * _tmp110 + P(2, 3) * _tmp103 + P(9, 3) * _tmp101; + const Scalar _tmp186 = P(0, 14) * _tmp124 + P(1, 14) * _tmp123 + P(10, 14) * _tmp125 + + P(11, 14) * _tmp19 + P(2, 14) * _tmp122 + P(9, 14) * _tmp121; + const Scalar _tmp187 = P(0, 13) * _tmp124 + P(1, 13) * _tmp123 + P(10, 13) * _tmp125 + + P(11, 13) * _tmp19 + P(2, 13) * _tmp122 + P(9, 13) * _tmp121; + const Scalar _tmp188 = P(0, 12) * _tmp124 + P(1, 12) * _tmp123 + P(10, 12) * _tmp125 + + P(11, 12) * _tmp19 + P(2, 12) * _tmp122 + P(9, 12) * _tmp121; + const Scalar _tmp189 = P(0, 3) * _tmp124 + P(1, 3) * _tmp123 + P(10, 3) * _tmp125 + + P(11, 3) * _tmp19 + P(2, 3) * _tmp122 + P(9, 3) * _tmp121; + const Scalar _tmp190 = P(0, 2) * _tmp154 + P(1, 2) * _tmp169 - P(12, 2) * _tmp180 - + P(13, 2) * _tmp138 - P(14, 2) * _tmp144 + P(2, 2) * _tmp175 + P(3, 2); + const Scalar _tmp191 = P(0, 1) * _tmp154 + P(1, 1) * _tmp169 - P(12, 1) * _tmp180 - + P(13, 1) * _tmp138 - P(14, 1) * _tmp144 + P(2, 1) * _tmp175 + P(3, 1); + const Scalar _tmp192 = P(0, 0) * _tmp154 + P(1, 0) * _tmp169 - P(12, 0) * _tmp180 - + P(13, 0) * _tmp138 - P(14, 0) * _tmp144 + P(2, 0) * _tmp175 + P(3, 0); + const Scalar _tmp193 = P(0, 12) * _tmp154 + P(1, 12) * _tmp169 - P(12, 12) * _tmp180 - + P(13, 12) * _tmp138 - P(14, 12) * _tmp144 + P(2, 12) * _tmp175 + P(3, 12); + const Scalar _tmp194 = P(0, 13) * _tmp154 + P(1, 13) * _tmp169 - P(12, 13) * _tmp180 - + P(13, 13) * _tmp138 - P(14, 13) * _tmp144 + P(2, 13) * _tmp175 + P(3, 13); + const Scalar _tmp195 = _tmp194 * d_vel_dt; + const Scalar _tmp196 = P(0, 14) * _tmp154 + P(1, 14) * _tmp169 - P(12, 14) * _tmp180 - + P(13, 14) * _tmp138 - P(14, 14) * _tmp144 + P(2, 14) * _tmp175 + P(3, 14); + const Scalar _tmp197 = P(0, 3) * _tmp154 + P(1, 3) * _tmp169 - P(12, 3) * _tmp180 - + P(13, 3) * _tmp138 - P(14, 3) * _tmp144 + P(2, 3) * _tmp175 + P(3, 3); + const Scalar _tmp198 = _tmp135 * state(3, 0); + const Scalar _tmp199 = _tmp133 * state(1, 0); + const Scalar _tmp200 = _tmp198 - _tmp199; + const Scalar _tmp201 = _tmp200 * d_vel_dt; + const Scalar _tmp202 = _tmp151 * state(3, 0); + const Scalar _tmp203 = _tmp145 * state(1, 0); + const Scalar _tmp204 = -_tmp203; + const Scalar _tmp205 = + _tmp148 * (_tmp202 + _tmp204) + _tmp149 * (_tmp158 + _tmp161 + _tmp163 + _tmp173); + const Scalar _tmp206 = _tmp134 + _tmp136; + const Scalar _tmp207 = _tmp206 * d_vel_dt; + const Scalar _tmp208 = + _tmp148 * (_tmp153 + _tmp170) + _tmp168 * (_tmp155 + _tmp157 + _tmp164 + _tmp171); + const Scalar _tmp209 = -_tmp202; + const Scalar _tmp210 = _tmp149 * (_tmp150 + _tmp152) + _tmp168 * (_tmp203 + _tmp209); + const Scalar _tmp211 = -2 * _tmp160; + const Scalar _tmp212 = _tmp177 + _tmp211 + 1; + const Scalar _tmp213 = _tmp212 * d_vel_dt; + const Scalar _tmp214 = P(0, 4) * _tmp63 + P(1, 4) * _tmp49 + P(10, 4) * _tmp82 + + P(11, 4) * _tmp73 + P(2, 4) * _tmp58 + P(9, 4) * _tmp19; + const Scalar _tmp215 = P(0, 4) * _tmp105 + P(1, 4) * _tmp102 + P(10, 4) * _tmp19 + + P(11, 4) * _tmp110 + P(2, 4) * _tmp103 + P(9, 4) * _tmp101; + const Scalar _tmp216 = P(0, 4) * _tmp124 + P(1, 4) * _tmp123 + P(10, 4) * _tmp125 + + P(11, 4) * _tmp19 + P(2, 4) * _tmp122 + P(9, 4) * _tmp121; + const Scalar _tmp217 = _tmp212 * d_vel_var(1, 0); + const Scalar _tmp218 = _tmp193 * d_vel_dt; + const Scalar _tmp219 = P(0, 4) * _tmp154 + P(1, 4) * _tmp169 - P(12, 4) * _tmp180 - + P(13, 4) * _tmp138 - P(14, 4) * _tmp144 + P(2, 4) * _tmp175 + P(3, 4); + const Scalar _tmp220 = P(0, 1) * _tmp205 + P(1, 1) * _tmp210 - P(12, 1) * _tmp207 - + P(13, 1) * _tmp213 - P(14, 1) * _tmp201 + P(2, 1) * _tmp208 + P(4, 1); + const Scalar _tmp221 = P(0, 12) * _tmp205 + P(1, 12) * _tmp210 - P(12, 12) * _tmp207 - + P(13, 12) * _tmp213 - P(14, 12) * _tmp201 + P(2, 12) * _tmp208 + P(4, 12); + const Scalar _tmp222 = P(0, 13) * _tmp205 + P(1, 13) * _tmp210 - P(12, 13) * _tmp207 - + P(13, 13) * _tmp213 - P(14, 13) * _tmp201 + P(2, 13) * _tmp208 + P(4, 13); + const Scalar _tmp223 = P(0, 2) * _tmp205 + P(1, 2) * _tmp210 - P(12, 2) * _tmp207 - + P(13, 2) * _tmp213 - P(14, 2) * _tmp201 + P(2, 2) * _tmp208 + P(4, 2); + const Scalar _tmp224 = P(0, 14) * _tmp205 + P(1, 14) * _tmp210 - P(12, 14) * _tmp207 - + P(13, 14) * _tmp213 - P(14, 14) * _tmp201 + P(2, 14) * _tmp208 + P(4, 14); + const Scalar _tmp225 = P(0, 0) * _tmp205 + P(1, 0) * _tmp210 - P(12, 0) * _tmp207 - + P(13, 0) * _tmp213 - P(14, 0) * _tmp201 + P(2, 0) * _tmp208 + P(4, 0); + const Scalar _tmp226 = P(0, 4) * _tmp205 + P(1, 4) * _tmp210 - P(12, 4) * _tmp207 - + P(13, 4) * _tmp213 - P(14, 4) * _tmp201 + P(2, 4) * _tmp208 + P(4, 4); + const Scalar _tmp227 = _tmp198 + _tmp199; + const Scalar _tmp228 = _tmp227 * d_vel_dt; + const Scalar _tmp229 = -_tmp140 + _tmp142; + const Scalar _tmp230 = _tmp229 * d_vel_dt; + const Scalar _tmp231 = _tmp148 * (_tmp146 + _tmp167) + _tmp168 * (_tmp202 + _tmp203); + const Scalar _tmp232 = _tmp149 * (_tmp147 + _tmp166) + _tmp168 * (_tmp165 + _tmp174); + const Scalar _tmp233 = _tmp148 * (_tmp159 + _tmp172) + _tmp149 * (_tmp204 + _tmp209); + const Scalar _tmp234 = _tmp178 + _tmp211; + const Scalar _tmp235 = _tmp234 * d_vel_dt; + const Scalar _tmp236 = P(0, 5) * _tmp63 + P(1, 5) * _tmp49 + P(10, 5) * _tmp82 + + P(11, 5) * _tmp73 + P(2, 5) * _tmp58 + P(9, 5) * _tmp19; + const Scalar _tmp237 = P(0, 5) * _tmp105 + P(1, 5) * _tmp102 + P(10, 5) * _tmp19 + + P(11, 5) * _tmp110 + P(2, 5) * _tmp103 + P(9, 5) * _tmp101; + const Scalar _tmp238 = P(0, 5) * _tmp124 + P(1, 5) * _tmp123 + P(10, 5) * _tmp125 + + P(11, 5) * _tmp19 + P(2, 5) * _tmp122 + P(9, 5) * _tmp121; + const Scalar _tmp239 = _tmp229 * d_vel_var(0, 0); + const Scalar _tmp240 = _tmp234 * d_vel_var(2, 0); + const Scalar _tmp241 = P(0, 5) * _tmp154 + P(1, 5) * _tmp169 - P(12, 5) * _tmp180 - + P(13, 5) * _tmp138 - P(14, 5) * _tmp144 + P(2, 5) * _tmp175 + P(3, 5); + const Scalar _tmp242 = P(0, 5) * _tmp205 + P(1, 5) * _tmp210 - P(12, 5) * _tmp207 - + P(13, 5) * _tmp213 - P(14, 5) * _tmp201 + P(2, 5) * _tmp208 + P(4, 5); + const Scalar _tmp243 = P(0, 14) * _tmp233 + P(1, 14) * _tmp232 - P(12, 14) * _tmp230 - + P(13, 14) * _tmp228 - P(14, 14) * _tmp235 + P(2, 14) * _tmp231 + P(5, 14); + const Scalar _tmp244 = P(0, 12) * _tmp233 + P(1, 12) * _tmp232 - P(12, 12) * _tmp230 - + P(13, 12) * _tmp228 - P(14, 12) * _tmp235 + P(2, 12) * _tmp231 + P(5, 12); + const Scalar _tmp245 = P(0, 13) * _tmp233 + P(1, 13) * _tmp232 - P(12, 13) * _tmp230 - + P(13, 13) * _tmp228 - P(14, 13) * _tmp235 + P(2, 13) * _tmp231 + P(5, 13); + const Scalar _tmp246 = P(0, 5) * _tmp233 + P(1, 5) * _tmp232 - P(12, 5) * _tmp230 - + P(13, 5) * _tmp228 - P(14, 5) * _tmp235 + P(2, 5) * _tmp231 + P(5, 5); // Output terms (1) - matrix::Matrix _res; + matrix::Matrix _res; - _res(0, 0) = _tmp10 * _tmp13 + _tmp11 * _tmp15 + _tmp12 * _tmp14 + _tmp16 * _tmp3 + - _tmp17 * _tmp6 + _tmp19 * _tmp9 + _tmp22 + _tmp23 + _tmp28; + _res(0, 0) = _tmp19 * _tmp83 + _tmp49 * _tmp89 + _tmp58 * _tmp90 + _tmp63 * _tmp88 + + _tmp73 * _tmp91 + _tmp82 * _tmp92 + std::pow(_tmp84, Scalar(2)) * d_ang_var + + std::pow(_tmp85, Scalar(2)) * d_ang_var + _tmp87; _res(1, 0) = 0; _res(2, 0) = 0; _res(3, 0) = 0; @@ -340,11 +377,12 @@ matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix - -namespace sym { - -/** - * This function was autogenerated from a symbolic function. Do not modify by hand. - * - * Symbolic function: quat_var_to_rot_var - * - * Args: - * state: Matrix24_1 - * P: Matrix24_24 - * epsilon: Scalar - * - * Outputs: - * rot_var: Matrix31 - */ -template -void QuatVarToRotVar(const matrix::Matrix& state, - const matrix::Matrix& P, const Scalar epsilon, - matrix::Matrix* const rot_var = nullptr) { - // Total ops: 61 - - // Input arrays - - // Intermediate terms (17) - const Scalar _tmp0 = std::fabs(state(0, 0)); - const Scalar _tmp1 = 1 - epsilon; - const Scalar _tmp2 = math::min(_tmp0, _tmp1); - const Scalar _tmp3 = 1 - std::pow(_tmp2, Scalar(2)); - const Scalar _tmp4 = (((state(0, 0)) > 0) - ((state(0, 0)) < 0)); - const Scalar _tmp5 = 2 * math::min(0, _tmp4) + 1; - const Scalar _tmp6 = _tmp5 * std::acos(_tmp2); - const Scalar _tmp7 = 2 * _tmp6 / std::sqrt(_tmp3); - const Scalar _tmp8 = _tmp4 * ((((-_tmp0 + _tmp1) > 0) - ((-_tmp0 + _tmp1) < 0)) + 1); - const Scalar _tmp9 = _tmp8 * state(1, 0); - const Scalar _tmp10 = _tmp2 * _tmp6 / (_tmp3 * std::sqrt(_tmp3)); - const Scalar _tmp11 = _tmp5 / _tmp3; - const Scalar _tmp12 = _tmp10 * _tmp9 - _tmp11 * _tmp9; - const Scalar _tmp13 = _tmp10 * _tmp8; - const Scalar _tmp14 = _tmp11 * _tmp8; - const Scalar _tmp15 = _tmp13 * state(2, 0) - _tmp14 * state(2, 0); - const Scalar _tmp16 = _tmp13 * state(3, 0) - _tmp14 * state(3, 0); - - // Output terms (1) - if (rot_var != nullptr) { - matrix::Matrix& _rot_var = (*rot_var); - - _rot_var(0, 0) = _tmp12 * (P(0, 0) * _tmp12 + P(1, 0) * _tmp7) + - _tmp7 * (P(0, 1) * _tmp12 + P(1, 1) * _tmp7); - _rot_var(1, 0) = _tmp15 * (P(0, 0) * _tmp15 + P(2, 0) * _tmp7) + - _tmp7 * (P(0, 2) * _tmp15 + P(2, 2) * _tmp7); - _rot_var(2, 0) = _tmp16 * (P(0, 0) * _tmp16 + P(3, 0) * _tmp7) + - _tmp7 * (P(0, 3) * _tmp16 + P(3, 3) * _tmp7); - } -} // NOLINT(readability/fn_size) - -// NOLINTNEXTLINE(readability/fn_size) -} // namespace sym diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/rot_var_ned_to_lower_triangular_quat_cov.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/rot_var_ned_to_lower_triangular_quat_cov.h deleted file mode 100644 index 8b2166f22369..000000000000 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/rot_var_ned_to_lower_triangular_quat_cov.h +++ /dev/null @@ -1,123 +0,0 @@ -// ----------------------------------------------------------------------------- -// This file was autogenerated by symforce from template: -// function/FUNCTION.h.jinja -// Do NOT modify by hand. -// ----------------------------------------------------------------------------- - -#pragma once - -#include - -namespace sym { - -/** - * This function was autogenerated from a symbolic function. Do not modify by hand. - * - * Symbolic function: rot_var_ned_to_lower_triangular_quat_cov - * - * Args: - * state: Matrix24_1 - * rot_var_ned: Matrix31 - * - * Outputs: - * q_cov_lower_triangle: Matrix44 - */ -template -void RotVarNedToLowerTriangularQuatCov( - const matrix::Matrix& state, const matrix::Matrix& rot_var_ned, - matrix::Matrix* const q_cov_lower_triangle = nullptr) { - // Total ops: 185 - - // Input arrays - - // Intermediate terms (54) - const Scalar _tmp0 = 2 * state(0, 0) * state(2, 0); - const Scalar _tmp1 = 2 * state(3, 0); - const Scalar _tmp2 = _tmp1 * state(1, 0); - const Scalar _tmp3 = _tmp0 + _tmp2; - const Scalar _tmp4 = _tmp1 * state(0, 0); - const Scalar _tmp5 = 2 * state(1, 0); - const Scalar _tmp6 = _tmp5 * state(2, 0); - const Scalar _tmp7 = -_tmp4 + _tmp6; - const Scalar _tmp8 = -2 * std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp9 = -2 * std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp10 = _tmp8 + _tmp9 + 1; - const Scalar _tmp11 = _tmp1 * state(2, 0); - const Scalar _tmp12 = _tmp5 * state(0, 0); - const Scalar _tmp13 = _tmp11 - _tmp12; - const Scalar _tmp14 = _tmp13 * rot_var_ned(1, 0); - const Scalar _tmp15 = 1 - 2 * std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp16 = _tmp15 + _tmp9; - const Scalar _tmp17 = _tmp11 + _tmp12; - const Scalar _tmp18 = _tmp17 * rot_var_ned(2, 0); - const Scalar _tmp19 = _tmp10 * _tmp14 + _tmp16 * _tmp18 + _tmp3 * _tmp7 * rot_var_ned(0, 0); - const Scalar _tmp20 = (Scalar(1) / Scalar(2)) * state(3, 0); - const Scalar _tmp21 = -_tmp19 * _tmp20; - const Scalar _tmp22 = std::pow(_tmp10, Scalar(2)) * rot_var_ned(1, 0) + - std::pow(_tmp17, Scalar(2)) * rot_var_ned(2, 0) + - std::pow(_tmp7, Scalar(2)) * rot_var_ned(0, 0); - const Scalar _tmp23 = (Scalar(1) / Scalar(2)) * state(2, 0); - const Scalar _tmp24 = _tmp15 + _tmp8; - const Scalar _tmp25 = _tmp24 * rot_var_ned(0, 0); - const Scalar _tmp26 = _tmp4 + _tmp6; - const Scalar _tmp27 = -_tmp0 + _tmp2; - const Scalar _tmp28 = (Scalar(1) / Scalar(2)) * _tmp10 * _tmp26 * rot_var_ned(1, 0) + - (Scalar(1) / Scalar(2)) * _tmp18 * _tmp27 + - (Scalar(1) / Scalar(2)) * _tmp25 * _tmp7; - const Scalar _tmp29 = _tmp28 * state(1, 0); - const Scalar _tmp30 = std::pow(_tmp24, Scalar(2)) * rot_var_ned(0, 0) + - std::pow(_tmp26, Scalar(2)) * rot_var_ned(1, 0) + - std::pow(_tmp27, Scalar(2)) * rot_var_ned(2, 0); - const Scalar _tmp31 = (Scalar(1) / Scalar(2)) * state(1, 0); - const Scalar _tmp32 = _tmp14 * _tmp26 + _tmp16 * _tmp27 * rot_var_ned(2, 0) + _tmp25 * _tmp3; - const Scalar _tmp33 = _tmp20 * _tmp32; - const Scalar _tmp34 = -_tmp28 * state(2, 0); - const Scalar _tmp35 = _tmp19 * _tmp23; - const Scalar _tmp36 = std::pow(_tmp13, Scalar(2)) * rot_var_ned(1, 0) + - std::pow(_tmp16, Scalar(2)) * rot_var_ned(2, 0) + - std::pow(_tmp3, Scalar(2)) * rot_var_ned(0, 0); - const Scalar _tmp37 = -_tmp31 * _tmp32; - const Scalar _tmp38 = _tmp28 * state(0, 0); - const Scalar _tmp39 = -_tmp20 * _tmp22 + _tmp35 + _tmp38; - const Scalar _tmp40 = (Scalar(1) / Scalar(2)) * state(0, 0); - const Scalar _tmp41 = _tmp23 * _tmp32; - const Scalar _tmp42 = _tmp28 * state(3, 0); - const Scalar _tmp43 = _tmp30 * _tmp40 + _tmp41 - _tmp42; - const Scalar _tmp44 = _tmp32 * _tmp40; - const Scalar _tmp45 = _tmp21 + _tmp23 * _tmp36 + _tmp44; - const Scalar _tmp46 = _tmp19 * _tmp31; - const Scalar _tmp47 = _tmp22 * _tmp40 + _tmp42 - _tmp46; - const Scalar _tmp48 = _tmp20 * _tmp30 + _tmp37 + _tmp38; - const Scalar _tmp49 = _tmp19 * _tmp40; - const Scalar _tmp50 = -_tmp31 * _tmp36 + _tmp33 + _tmp49; - const Scalar _tmp51 = _tmp22 * _tmp31 + _tmp34 + _tmp49; - const Scalar _tmp52 = -_tmp23 * _tmp30 + _tmp29 + _tmp44; - const Scalar _tmp53 = _tmp36 * _tmp40 - _tmp41 + _tmp46; - - // Output terms (1) - if (q_cov_lower_triangle != nullptr) { - matrix::Matrix& _q_cov_lower_triangle = (*q_cov_lower_triangle); - - _q_cov_lower_triangle(0, 0) = -_tmp20 * (-_tmp20 * _tmp36 - _tmp35 + _tmp37) - - _tmp23 * (_tmp21 - _tmp22 * _tmp23 - _tmp29) - - _tmp31 * (-_tmp30 * _tmp31 - _tmp33 + _tmp34); - _q_cov_lower_triangle(1, 0) = -_tmp20 * _tmp45 - _tmp23 * _tmp39 - _tmp31 * _tmp43; - _q_cov_lower_triangle(2, 0) = -_tmp20 * _tmp50 - _tmp23 * _tmp47 - _tmp31 * _tmp48; - _q_cov_lower_triangle(3, 0) = -_tmp20 * _tmp53 - _tmp23 * _tmp51 - _tmp31 * _tmp52; - _q_cov_lower_triangle(0, 1) = 0; - _q_cov_lower_triangle(1, 1) = -_tmp20 * _tmp39 + _tmp23 * _tmp45 + _tmp40 * _tmp43; - _q_cov_lower_triangle(2, 1) = -_tmp20 * _tmp47 + _tmp23 * _tmp50 + _tmp40 * _tmp48; - _q_cov_lower_triangle(3, 1) = -_tmp20 * _tmp51 + _tmp23 * _tmp53 + _tmp40 * _tmp52; - _q_cov_lower_triangle(0, 2) = 0; - _q_cov_lower_triangle(1, 2) = 0; - _q_cov_lower_triangle(2, 2) = _tmp20 * _tmp48 - _tmp31 * _tmp50 + _tmp40 * _tmp47; - _q_cov_lower_triangle(3, 2) = _tmp20 * _tmp52 - _tmp31 * _tmp53 + _tmp40 * _tmp51; - _q_cov_lower_triangle(0, 3) = 0; - _q_cov_lower_triangle(1, 3) = 0; - _q_cov_lower_triangle(2, 3) = 0; - _q_cov_lower_triangle(3, 3) = -_tmp23 * _tmp52 + _tmp31 * _tmp51 + _tmp40 * _tmp53; - } -} // NOLINT(readability/fn_size) - -// NOLINTNEXTLINE(readability/fn_size) -} // namespace sym diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/state.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/state.h index 200af9c0e43b..edba795dfb4a 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/state.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/state.h @@ -41,15 +41,15 @@ static_assert(sizeof(matrix::Vector) == sizeof(StateSample), "state v struct IdxDof { unsigned idx; unsigned dof; }; namespace State { - static constexpr IdxDof quat_nominal{0, 4}; - static constexpr IdxDof vel{4, 3}; - static constexpr IdxDof pos{7, 3}; - static constexpr IdxDof gyro_bias{10, 3}; - static constexpr IdxDof accel_bias{13, 3}; - static constexpr IdxDof mag_I{16, 3}; - static constexpr IdxDof mag_B{19, 3}; - static constexpr IdxDof wind_vel{22, 2}; - static constexpr uint8_t size{24}; + static constexpr IdxDof quat_nominal{0, 3}; + static constexpr IdxDof vel{3, 3}; + static constexpr IdxDof pos{6, 3}; + static constexpr IdxDof gyro_bias{9, 3}; + static constexpr IdxDof accel_bias{12, 3}; + static constexpr IdxDof mag_I{15, 3}; + static constexpr IdxDof mag_B{18, 3}; + static constexpr IdxDof wind_vel{21, 2}; + static constexpr uint8_t size{23}; }; } #endif // !EKF_STATE_H diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 18b5e5b3cb4a..71c0076710ab 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1862,7 +1862,7 @@ void EKF2::PublishOdometry(const hrt_abstime ×tamp, const imuSample &imu_sa _ekf.getPositionVariance().copyTo(odom.position_variance); // orientation covariance - _ekf.calcRotVecVariances().copyTo(odom.orientation_variance); + _ekf.getQuaternionVariance().copyTo(odom.orientation_variance); odom.reset_counter = _ekf.get_quat_reset_count() + _ekf.get_velNE_reset_count() + _ekf.get_velD_reset_count() @@ -1949,8 +1949,9 @@ void EKF2::PublishStates(const hrt_abstime ×tamp) // publish estimator states estimator_states_s states; states.timestamp_sample = _ekf.time_delayed_us(); - states.n_states = Ekf::getNumberOfStates(); - _ekf.getStateAtFusionHorizonAsVector().copyTo(states.states); + const auto state_vector = _ekf.state().vector(); + state_vector.copyTo(states.states); + states.n_states = state_vector.size(); _ekf.covariances_diagonal().copyTo(states.covariances); states.timestamp = _replay_mode ? timestamp : hrt_absolute_time(); _estimator_states_pub.publish(states); diff --git a/src/modules/ekf2/test/CMakeLists.txt b/src/modules/ekf2/test/CMakeLists.txt index 7d0af8e502cd..539ea0798ffc 100644 --- a/src/modules/ekf2/test/CMakeLists.txt +++ b/src/modules/ekf2/test/CMakeLists.txt @@ -37,14 +37,11 @@ add_subdirectory(sensor_simulator) add_subdirectory(test_helper) px4_add_unit_gtest(SRC test_EKF_accelerometer.cpp LINKLIBS ecl_EKF ecl_sensor_sim) -px4_add_unit_gtest(SRC test_EKF_attitude_variance.cpp LINKLIBS ecl_EKF ecl_test_helper) -px4_add_unit_gtest(SRC test_EKF_airspeed_fusion_generated.cpp LINKLIBS ecl_EKF ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_airspeed.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_basics.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_externalVision.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_flow.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_gyroscope.cpp LINKLIBS ecl_EKF ecl_sensor_sim) -px4_add_unit_gtest(SRC test_EKF_opt_flow_fusion_generated.cpp LINKLIBS ecl_EKF ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_fusionLogic.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_gps.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_gps_yaw.cpp LINKLIBS ecl_EKF ecl_sensor_sim) @@ -53,11 +50,9 @@ px4_add_unit_gtest(SRC test_EKF_height_fusion.cpp LINKLIBS ecl_EKF ecl_sensor_si px4_add_unit_gtest(SRC test_EKF_imuSampling.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_initialization.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_mag.cpp LINKLIBS ecl_EKF ecl_sensor_sim) -px4_add_unit_gtest(SRC test_EKF_mag_3d_fusion_generated.cpp LINKLIBS ecl_EKF ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_mag_declination_generated.cpp LINKLIBS ecl_EKF ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_measurementSampling.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_ringbuffer.cpp LINKLIBS ecl_EKF ecl_sensor_sim) -px4_add_unit_gtest(SRC test_EKF_sideslip_fusion_generated.cpp LINKLIBS ecl_EKF ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_terrain_estimator.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_utils.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_withReplayData.cpp LINKLIBS ecl_EKF ecl_sensor_sim) 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 08ff126f620d..9ee0d501951a 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -1,391 +1,391 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23] -10000,1,-0.0094,-0.01,-3.2e-06,0.00023,7.3e-05,-0.011,7.1e-06,2.2e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,4.9e-07,0.0025,0.0025,4.3e-05,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -90000,1,-0.0094,-0.011,6.9e-05,-0.00047,0.0026,-0.026,-1.6e-05,0.00011,-0.0023,0,0,0,0,0,0,0,0,0,0,0,0,0,0,5.2e-07,0.0026,0.0026,0.00011,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -190000,1,-0.0094,-0.011,2.9e-05,6.9e-05,0.0039,-0.041,-5.9e-06,0.00043,-0.0044,-3e-11,-2.7e-12,5.9e-13,0,0,-2e-09,0,0,0,0,0,0,0,0,5.6e-07,0.0027,0.0027,0.00023,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -290000,1,-0.0094,-0.011,6.4e-05,0.001,0.0064,-0.053,3.8e-05,0.00036,-0.007,9.1e-10,1e-10,-2.8e-11,0,0,-4.8e-07,0,0,0,0,0,0,0,0,6.1e-07,0.0029,0.0029,0.00019,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -390000,1,-0.0095,-0.011,7.2e-05,0.0024,0.0083,-0.059,0.00021,0.0011,-0.0094,-1.1e-08,2.8e-09,7.6e-11,0,0,-4.5e-06,0,0,0,0,0,0,0,0,6.8e-07,0.0031,0.0031,0.0003,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -490000,1,-0.0095,-0.012,2.2e-05,0.0039,0.0048,-0.06,0.00024,0.00048,-0.011,1.6e-06,-3.7e-07,1.4e-08,0,0,-1.6e-05,0,0,0,0,0,0,0,0,7.7e-07,0.0034,0.0033,0.00018,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -590000,1,-0.0095,-0.012,2.9e-05,0.006,0.0073,-0.059,0.00074,0.0011,-0.012,1.6e-06,-3.4e-07,1.4e-08,0,0,-3.4e-05,0,0,0,0,0,0,0,0,8.7e-07,0.0037,0.0037,0.00025,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -690000,1,-0.0097,-0.012,8.9e-05,0.0063,0.0051,-0.06,0.0005,0.00054,-0.013,5.5e-06,-3.2e-06,1.2e-07,0,0,-6.3e-05,0,0,0,0,0,0,0,0,9.9e-07,0.004,0.004,0.00015,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -790000,1,-0.0098,-0.013,0.0001,0.0086,0.0072,-0.063,0.0012,0.0011,-0.014,5.4e-06,-3.1e-06,1.1e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,1.1e-06,0.0044,0.0044,0.0002,2.8,2.8,2,0.42,0.42,0.28,0.01,0.01,0.0012,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -890000,1,-0.0099,-0.013,0.00012,0.01,0.0059,-0.077,0.00096,0.00071,-0.021,1.6e-05,-1.5e-05,3.4e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,1.3e-06,0.0048,0.0048,0.00013,1.3,1.3,2,0.2,0.2,0.43,0.0099,0.01,0.00068,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -990000,1,-0.0099,-0.013,0.00013,0.015,0.0062,-0.092,0.0022,0.0013,-0.029,1.6e-05,-1.5e-05,3.4e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,1.5e-06,0.0053,0.0053,0.00016,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.00068,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1090000,1,-0.01,-0.014,0.00013,0.016,0.0048,-0.11,0.0018,0.00084,-0.039,4.1e-05,-6.2e-05,9.6e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,1.6e-06,0.0057,0.0057,0.00011,0.92,0.92,2,0.17,0.17,0.84,0.0098,0.0098,0.00042,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1190000,1,-0.01,-0.014,0.0001,0.02,0.005,-0.12,0.0035,0.0013,-0.051,4.1e-05,-6.2e-05,9.6e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,1.8e-06,0.0063,0.0063,0.00013,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00042,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1290000,1,-0.01,-0.014,0.00016,0.02,0.0041,-0.14,0.0027,0.00085,-0.064,8.2e-05,-0.00019,2.3e-06,0,0,-9.6e-05,0,0,0,0,0,0,0,0,1.9e-06,0.0064,0.0064,9.9e-05,0.88,0.88,2,0.15,0.15,1.4,0.0095,0.0095,0.00028,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1390000,1,-0.01,-0.014,0.00017,0.026,0.0038,-0.15,0.0051,0.0013,-0.078,8.2e-05,-0.00019,2.3e-06,0,0,-9.6e-05,0,0,0,0,0,0,0,0,2.2e-06,0.0071,0.0071,0.00011,1.1,1.1,2,0.21,0.21,1.7,0.0095,0.0095,0.00028,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1490000,1,-0.01,-0.014,0.00015,0.024,0.0026,-0.16,0.0038,0.00078,-0.093,0.00014,-0.00046,4.8e-06,0,0,-9.8e-05,0,0,0,0,0,0,0,0,2.2e-06,0.0067,0.0067,8.8e-05,0.95,0.95,2,0.14,0.14,2.1,0.0088,0.0088,0.0002,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1590000,1,-0.011,-0.014,0.00014,0.031,0.003,-0.18,0.0065,0.0011,-0.11,0.00014,-0.00046,4.8e-06,0,0,-9.8e-05,0,0,0,0,0,0,0,0,2.4e-06,0.0074,0.0074,0.0001,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.0002,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1690000,1,-0.011,-0.014,0.0001,0.028,-0.00047,-0.19,0.0045,0.00057,-0.13,0.00019,-0.00088,8.2e-06,0,0,-0.0001,0,0,0,0,0,0,0,0,2.2e-06,0.0064,0.0064,7.9e-05,1,1,2,0.14,0.14,3,0.0078,0.0078,0.00015,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1790000,1,-0.011,-0.014,7.5e-05,0.035,-0.0024,-0.2,0.0076,0.00044,-0.15,0.00019,-0.00088,8.2e-06,0,0,-0.0001,0,0,0,0,0,0,0,0,2.4e-06,0.007,0.007,8.9e-05,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.00015,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1890000,1,-0.011,-0.015,5.4e-05,0.043,-0.0037,-0.22,0.011,0.00014,-0.17,0.00019,-0.00088,8.2e-06,0,0,-0.0001,0,0,0,0,0,0,0,0,2.7e-06,0.0076,0.0076,0.0001,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.00015,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1990000,1,-0.011,-0.014,4.7e-05,0.036,-0.0051,-0.23,0.0082,-0.00038,-0.19,0.0002,-0.0014,1.3e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,2.2e-06,0.0061,0.0061,8e-05,1.3,1.3,2,0.2,0.2,4.7,0.0066,0.0066,0.00011,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2090000,1,-0.011,-0.014,6.8e-06,0.041,-0.0077,-0.24,0.012,-0.001,-0.22,0.0002,-0.0014,1.3e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,2.4e-06,0.0066,0.0066,8.9e-05,1.7,1.7,2.1,0.31,0.31,5.3,0.0066,0.0066,0.00011,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2190000,1,-0.011,-0.014,-1.2e-06,0.033,-0.0072,-0.26,0.0079,-0.0011,-0.24,0.00015,-0.002,1.8e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,1.8e-06,0.005,0.005,7.2e-05,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,8.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2290000,1,-0.011,-0.014,-1.7e-05,0.039,-0.0098,-0.27,0.011,-0.0019,-0.27,0.00015,-0.002,1.8e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,2e-06,0.0054,0.0054,8e-05,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,8.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2390000,1,-0.011,-0.013,-1.9e-05,0.03,-0.009,-0.29,0.0074,-0.0016,-0.3,5.8e-05,-0.0025,2.2e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,1.5e-06,0.004,0.004,6.6e-05,1,1,2.1,0.19,0.19,7.4,0.0045,0.0045,7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2490000,1,-0.011,-0.013,-4e-05,0.034,-0.011,-0.3,0.011,-0.0025,-0.32,5.8e-05,-0.0025,2.2e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,1.6e-06,0.0044,0.0044,7.2e-05,1.3,1.3,2.1,0.28,0.28,8.2,0.0045,0.0045,7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2590000,1,-0.011,-0.013,-4.3e-05,0.026,-0.0093,-0.31,0.0068,-0.0018,-0.36,-5.2e-05,-0.003,2.6e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,1.2e-06,0.0032,0.0032,6.1e-05,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,5.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2690000,1,-0.011,-0.013,-5e-05,0.03,-0.011,-0.33,0.0096,-0.0029,-0.39,-5.2e-05,-0.003,2.6e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,1.3e-06,0.0035,0.0035,6.6e-05,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,5.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2790000,1,-0.011,-0.013,-7.1e-05,0.023,-0.0096,-0.34,0.0061,-0.002,-0.42,-0.00017,-0.0033,3e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,1e-06,0.0027,0.0027,5.6e-05,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,4.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2890000,1,-0.011,-0.013,-0.00012,0.027,-0.011,-0.35,0.0086,-0.003,-0.46,-0.00017,-0.0033,3e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,1.1e-06,0.0029,0.0029,6.1e-05,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,4.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2990000,1,-0.011,-0.013,-9.1e-05,0.022,-0.0097,-0.36,0.0056,-0.0021,-0.49,-0.00028,-0.0036,3.2e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,8.4e-07,0.0023,0.0023,5.3e-05,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,3.9e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3090000,1,-0.011,-0.013,-9.2e-05,0.024,-0.011,-0.38,0.0079,-0.0032,-0.53,-0.00028,-0.0036,3.2e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,9.3e-07,0.0025,0.0025,5.7e-05,0.82,0.82,2.2,0.22,0.22,14,0.0027,0.0027,3.9e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3190000,1,-0.011,-0.013,-0.00016,0.019,-0.0088,-0.39,0.0052,-0.0022,-0.57,-0.00039,-0.0039,3.4e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,7.2e-07,0.002,0.002,4.9e-05,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,3.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3290000,1,-0.011,-0.013,-0.00013,0.023,-0.011,-0.4,0.0073,-0.0031,-0.61,-0.00039,-0.0039,3.4e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,7.9e-07,0.0022,0.0022,5.3e-05,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,3.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3390000,1,-0.011,-0.012,-0.00017,0.018,-0.0094,-0.42,0.0049,-0.0022,-0.65,-0.00049,-0.0041,3.6e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,6.2e-07,0.0017,0.0017,4.6e-05,0.53,0.53,2.3,0.14,0.14,17,0.0019,0.0019,2.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3490000,1,-0.011,-0.013,-0.00018,0.021,-0.012,-0.43,0.0068,-0.0032,-0.69,-0.00049,-0.0041,3.6e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,6.8e-07,0.0019,0.0019,5e-05,0.65,0.65,2.3,0.19,0.19,19,0.0019,0.0019,2.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3590000,1,-0.011,-0.012,-0.00017,0.016,-0.011,-0.44,0.0046,-0.0023,-0.73,-0.0006,-0.0044,3.8e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,5.3e-07,0.0015,0.0015,4.4e-05,0.48,0.48,2.4,0.13,0.13,20,0.0016,0.0016,2.4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3690000,1,-0.011,-0.012,-4.8e-05,0.019,-0.014,-0.46,0.0064,-0.0036,-0.78,-0.0006,-0.0044,3.8e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,5.9e-07,0.0017,0.0017,4.7e-05,0.59,0.59,2.4,0.18,0.18,21,0.0016,0.0016,2.4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3790000,1,-0.011,-0.012,-1.3e-05,0.015,-0.014,-0.47,0.0043,-0.0026,-0.83,-0.00072,-0.0045,4e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,4.7e-07,0.0014,0.0014,4.1e-05,0.44,0.45,2.4,0.12,0.12,23,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3890000,1,-0.011,-0.012,-5.1e-05,0.017,-0.015,-0.48,0.006,-0.004,-0.87,-0.00072,-0.0045,4e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,5.1e-07,0.0015,0.0015,4.4e-05,0.54,0.54,2.4,0.17,0.17,24,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3990000,1,-0.011,-0.012,-5.2e-05,0.02,-0.016,-0.5,0.0078,-0.0056,-0.92,-0.00072,-0.0045,4e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,5.5e-07,0.0016,0.0016,4.7e-05,0.66,0.66,2.5,0.22,0.23,26,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4090000,1,-0.011,-0.012,-6.7e-05,0.017,-0.014,-0.51,0.0056,-0.0042,-0.97,-0.00084,-0.0047,4.2e-05,0,0,-9.6e-05,0,0,0,0,0,0,0,0,4.3e-07,0.0013,0.0013,4.2e-05,0.5,0.5,2.5,0.16,0.16,27,0.0012,0.0011,1.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4190000,1,-0.011,-0.012,-9.6e-05,0.02,-0.017,-0.53,0.0075,-0.0057,-1,-0.00084,-0.0047,4.2e-05,0,0,-9.6e-05,0,0,0,0,0,0,0,0,4.7e-07,0.0015,0.0015,4.4e-05,0.6,0.61,2.5,0.21,0.21,29,0.0012,0.0011,1.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4290000,1,-0.01,-0.012,-0.00015,0.017,-0.012,-0.54,0.0054,-0.0042,-1.1,-0.00097,-0.0049,4.4e-05,0,0,-9.1e-05,0,0,0,0,0,0,0,0,3.7e-07,0.0012,0.0012,4e-05,0.46,0.46,2.6,0.15,0.15,31,0.00095,0.00095,1.6e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4390000,1,-0.01,-0.012,-0.00014,0.018,-0.013,-0.55,0.0072,-0.0055,-1.1,-0.00097,-0.0049,4.4e-05,0,0,-9.1e-05,0,0,0,0,0,0,0,0,4e-07,0.0013,0.0013,4.2e-05,0.56,0.56,2.6,0.2,0.2,33,0.00095,0.00095,1.6e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4490000,1,-0.01,-0.012,-8.5e-05,0.015,-0.01,-0.57,0.0051,-0.0038,-1.2,-0.0011,-0.005,4.6e-05,0,0,-8.7e-05,0,0,0,0,0,0,0,0,3.2e-07,0.001,0.001,3.8e-05,0.43,0.43,2.6,0.14,0.14,34,0.00078,0.00078,1.4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4590000,1,-0.01,-0.012,-6.1e-05,0.018,-0.012,-0.58,0.0068,-0.0049,-1.2,-0.0011,-0.005,4.6e-05,0,0,-8.7e-05,0,0,0,0,0,0,0,0,3.4e-07,0.0011,0.0011,4e-05,0.51,0.51,2.7,0.19,0.19,36,0.00078,0.00078,1.4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4690000,1,-0.01,-0.012,-6.8e-05,0.014,-0.01,-0.6,0.0049,-0.0035,-1.3,-0.0012,-0.0052,4.7e-05,0,0,-8.2e-05,0,0,0,0,0,0,0,0,2.7e-07,0.00091,0.00091,3.6e-05,0.39,0.39,2.7,0.14,0.14,38,0.00064,0.00064,1.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4790000,1,-0.01,-0.012,-8.2e-05,0.016,-0.012,-0.61,0.0064,-0.0045,-1.4,-0.0012,-0.0052,4.7e-05,0,0,-8.2e-05,0,0,0,0,0,0,0,0,2.9e-07,0.00099,0.00099,3.8e-05,0.47,0.47,2.7,0.18,0.18,40,0.00064,0.00064,1.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4890000,1,-0.01,-0.012,-0.0001,0.013,-0.01,-0.63,0.0046,-0.0033,-1.4,-0.0013,-0.0053,4.8e-05,0,0,-7.7e-05,0,0,0,0,0,0,0,0,2.3e-07,0.0008,0.00079,3.5e-05,0.36,0.36,2.8,0.13,0.13,42,0.00052,0.00052,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4990000,1,-0.01,-0.012,-0.00013,0.015,-0.011,-0.64,0.006,-0.0043,-1.5,-0.0013,-0.0053,4.8e-05,0,0,-7.7e-05,0,0,0,0,0,0,0,0,2.4e-07,0.00086,0.00086,3.7e-05,0.43,0.43,2.8,0.17,0.17,44,0.00052,0.00052,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5090000,1,-0.01,-0.011,-9.4e-05,0.012,-0.0086,-0.66,0.0043,-0.0031,-1.6,-0.0013,-0.0054,4.9e-05,0,0,-7.3e-05,0,0,0,0,0,0,0,0,1.9e-07,0.00069,0.00069,3.3e-05,0.33,0.33,2.8,0.12,0.12,46,0.00042,0.00042,1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5190000,1,-0.01,-0.011,-7.3e-05,0.013,-0.01,-0.67,0.0056,-0.004,-1.6,-0.0013,-0.0054,4.9e-05,0,0,-7.3e-05,0,0,0,0,0,0,0,0,2e-07,0.00075,0.00074,3.5e-05,0.39,0.39,2.9,0.16,0.16,49,0.00042,0.00042,1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5290000,1,-0.01,-0.011,-9.2e-05,0.0093,-0.0074,-0.68,0.0039,-0.0029,-1.7,-0.0014,-0.0055,5e-05,0,0,-6.9e-05,0,0,0,0,0,0,0,0,1.6e-07,0.0006,0.0006,3.2e-05,0.3,0.3,2.9,0.12,0.12,51,0.00034,0.00034,9.1e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5390000,1,-0.0099,-0.011,-3.9e-05,0.0089,-0.0083,-0.7,0.0048,-0.0037,-1.8,-0.0014,-0.0055,5e-05,0,0,-6.9e-05,0,0,0,0,0,0,0,0,1.7e-07,0.00064,0.00064,3.4e-05,0.36,0.36,2.9,0.16,0.16,53,0.00034,0.00034,9.1e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5490000,1,-0.0098,-0.011,-3.6e-05,0.0062,-0.0064,-0.71,0.0033,-0.0026,-1.8,-0.0014,-0.0055,5.1e-05,0,0,-6.6e-05,0,0,0,0,0,0,0,0,1.3e-07,0.00052,0.00051,3.1e-05,0.28,0.28,3,0.11,0.11,56,0.00028,0.00027,8.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5590000,1,-0.0098,-0.011,-6.1e-05,0.0069,-0.0068,-0.73,0.0039,-0.0032,-1.9,-0.0014,-0.0055,5.1e-05,0,0,-6.6e-05,0,0,0,0,0,0,0,0,1.4e-07,0.00055,0.00055,3.2e-05,0.33,0.33,3,0.15,0.15,58,0.00028,0.00027,8.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5690000,1,-0.0096,-0.011,4.4e-06,0.0049,-0.004,-0.74,0.0027,-0.0022,-2,-0.0015,-0.0056,5.2e-05,0,0,-6.3e-05,0,0,0,0,0,0,0,0,1.1e-07,0.00045,0.00044,3e-05,0.25,0.25,3.1,0.11,0.11,61,0.00022,0.00022,7.5e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5790000,1,-0.0096,-0.011,-3.9e-06,0.0053,-0.003,-0.75,0.0031,-0.0026,-2,-0.0015,-0.0056,5.2e-05,0,0,-6.3e-05,0,0,0,0,0,0,0,0,1.2e-07,0.00048,0.00048,3.1e-05,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,7.5e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5890000,1,-0.0095,-0.011,-3.4e-05,0.0045,-0.0011,0.0028,0.0022,-0.0017,-3.7e+02,-0.0015,-0.0056,5.2e-05,0,0,-6.4e-05,0,0,0,0,0,0,0,0,9e-08,0.00038,0.00038,2.9e-05,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5990000,1,-0.0095,-0.011,-1.6e-05,0.0049,0.00031,0.015,0.0026,-0.0017,-3.7e+02,-0.0015,-0.0056,5.2e-05,0,0,-7.3e-05,0,0,0,0,0,0,0,0,9.6e-08,0.00041,0.00041,3e-05,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6090000,1,-0.0094,-0.011,-3.6e-05,0.006,0.0015,-0.011,0.0032,-0.0016,-3.7e+02,-0.0015,-0.0056,5.2e-05,0,0,-6.4e-05,0,0,0,0,0,0,0,0,1e-07,0.00044,0.00044,3.1e-05,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6190000,0.71,0.0013,-0.015,0.71,0.0035,0.003,-0.005,0.0023,-0.00066,-3.7e+02,-0.0015,-0.0057,5.2e-05,0,0,-8.8e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.00034,0.00034,0.0028,0.22,0.22,4.9,0.13,0.13,0.32,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6290000,0.71,0.0013,-0.015,0.71,0.0035,0.0043,-0.012,0.0026,-0.00028,-3.7e+02,-0.0015,-0.0057,5.2e-05,0,0,-9.5e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.00034,0.00034,0.0028,0.22,0.22,3.2,0.16,0.16,0.3,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6390000,0.71,0.0013,-0.014,0.71,0.0024,0.0048,-0.05,0.0029,0.00018,-3.7e+02,-0.0015,-0.0057,5.2e-05,0,0,-3.6e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.00034,0.00034,0.0028,0.23,0.23,2.3,0.19,0.19,0.29,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6490000,0.71,0.0014,-0.014,0.71,0.0022,0.0056,-0.052,0.0031,0.00072,-3.7e+02,-0.0015,-0.0057,5.2e-05,0,0,-8.5e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.00034,0.00034,0.0028,0.24,0.24,1.5,0.23,0.23,0.26,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6590000,0.71,0.0014,-0.014,0.71,0.0017,0.0057,-0.099,0.0034,0.0013,-3.7e+02,-0.0015,-0.0057,5.2e-05,0,0,9.5e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.00035,0.00034,0.0028,0.25,0.25,1.1,0.28,0.28,0.23,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6690000,0.71,0.0014,-0.014,0.71,0.0021,0.0068,-0.076,0.0036,0.0019,-3.7e+02,-0.0015,-0.0057,5.2e-05,0,0,-0.00022,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.00035,0.00035,0.0028,0.26,0.26,0.78,0.33,0.33,0.21,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6790000,0.71,0.0014,-0.014,0.71,0.00081,0.0068,-0.11,0.0037,0.0026,-3.7e+02,-0.0015,-0.0057,5.2e-05,0,0,8.4e-06,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.00035,0.00035,0.0028,0.28,0.28,0.6,0.38,0.38,0.2,0.00015,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6890000,0.71,0.0014,-0.014,0.71,-0.0012,0.0073,-0.12,0.0037,0.0033,-3.7e+02,-0.0015,-0.0057,5.2e-05,0,0,-4.3e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.00036,0.00036,0.0028,0.3,0.3,0.46,0.44,0.44,0.18,0.00015,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6990000,0.71,0.0015,-0.014,0.71,-0.0013,0.0082,-0.12,0.0035,0.0041,-3.7e+02,-0.0015,-0.0057,5.2e-05,0,0,-0.00034,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.00036,0.00036,0.0028,0.32,0.32,0.36,0.51,0.51,0.16,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -7090000,0.71,0.0015,-0.014,0.71,-0.0018,0.0079,-0.13,0.0034,0.0049,-3.7e+02,-0.0015,-0.0057,5.2e-05,0,0,-0.0007,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.00037,0.00037,0.0028,0.35,0.35,0.29,0.58,0.58,0.16,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -7190000,0.71,0.0015,-0.014,0.71,-0.0035,0.0081,-0.15,0.0031,0.0057,-3.7e+02,-0.0015,-0.0057,5.2e-05,0,0,-0.00049,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.00038,0.00038,0.0028,0.37,0.37,0.24,0.66,0.66,0.15,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -7290000,0.71,0.0015,-0.014,0.71,-0.005,0.0084,-0.15,0.0026,0.0065,-3.7e+02,-0.0015,-0.0057,5.2e-05,0,0,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.00039,0.00039,0.0028,0.41,0.41,0.2,0.76,0.76,0.14,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -7390000,0.71,0.0015,-0.014,0.71,-0.0051,0.0099,-0.16,0.0021,0.0074,-3.7e+02,-0.0015,-0.0057,5.2e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.0004,0.00039,0.0028,0.44,0.44,0.18,0.85,0.85,0.13,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7490000,0.71,0.0016,-0.014,0.71,-0.0067,0.01,-0.16,0.0015,0.0084,-3.7e+02,-0.0015,-0.0057,5.2e-05,0,0,-0.0021,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.0004,0.0004,0.0028,0.48,0.48,0.15,0.96,0.96,0.12,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7590000,0.71,0.0016,-0.014,0.71,-0.0086,0.012,-0.17,0.00073,0.0093,-3.7e+02,-0.0015,-0.0057,5.2e-05,0,0,-0.003,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.00041,0.00041,0.0028,0.51,0.52,0.14,1.1,1.1,0.12,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7690000,0.7,0.0017,-0.014,0.71,-0.011,0.012,-0.16,-0.00031,0.01,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.005,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00042,0.00042,0.0022,0.56,0.56,0.13,1.2,1.2,0.11,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7790000,0.7,0.0017,-0.014,0.71,-0.012,0.013,-0.16,-0.0014,0.011,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.007,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00043,0.00043,0.0022,0.6,0.6,0.12,1.3,1.3,0.11,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7890000,0.7,0.0017,-0.014,0.71,-0.015,0.015,-0.16,-0.0028,0.013,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0096,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00045,0.00045,0.0022,0.66,0.66,0.11,1.5,1.5,0.1,0.00014,0.00014,6.3e-06,0.04,0.04,0.038,0,0,0,0,0,0,0,0 -7990000,0.7,0.0018,-0.014,0.71,-0.017,0.016,-0.16,-0.0043,0.014,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00046,0.00046,0.0022,0.7,0.7,0.1,1.7,1.7,0.099,0.00014,0.00014,6.3e-06,0.04,0.04,0.038,0,0,0,0,0,0,0,0 -8090000,0.7,0.0018,-0.014,0.71,-0.018,0.018,-0.17,-0.0061,0.016,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00047,0.00047,0.0022,0.76,0.76,0.1,1.9,1.9,0.097,0.00014,0.00014,6.3e-06,0.04,0.04,0.037,0,0,0,0,0,0,0,0 -8190000,0.7,0.0018,-0.014,0.71,-0.021,0.019,-0.18,-0.0081,0.017,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.013,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00049,0.00048,0.0022,0.83,0.83,0.099,2.1,2.1,0.094,0.00014,0.00014,6.3e-06,0.04,0.04,0.037,0,0,0,0,0,0,0,0 -8290000,0.7,0.0018,-0.014,0.71,-0.022,0.02,-0.17,-0.01,0.019,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.017,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0005,0.0005,0.0022,0.88,0.88,0.097,2.3,2.3,0.091,0.00014,0.00014,6.3e-06,0.04,0.04,0.036,0,0,0,0,0,0,0,0 -8390000,0.7,0.0019,-0.014,0.71,-0.025,0.021,-0.17,-0.013,0.021,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.021,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00051,0.00051,0.0022,0.95,0.95,0.097,2.5,2.5,0.091,0.00014,0.00014,6.3e-06,0.04,0.04,0.035,0,0,0,0,0,0,0,0 -8490000,0.7,0.0018,-0.014,0.71,-0.027,0.022,-0.17,-0.015,0.022,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.025,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00052,0.00052,0.0022,1,1,0.096,2.8,2.8,0.089,0.00014,0.00014,6.3e-06,0.04,0.04,0.034,0,0,0,0,0,0,0,0 -8590000,0.7,0.0019,-0.014,0.71,-0.029,0.025,-0.17,-0.018,0.024,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.029,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00054,0.00054,0.0022,1.1,1.1,0.095,3.1,3.1,0.088,0.00014,0.00014,6.3e-06,0.04,0.04,0.034,0,0,0,0,0,0,0,0 -8690000,0.7,0.0019,-0.014,0.71,-0.032,0.025,-0.16,-0.021,0.026,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.035,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00055,0.00055,0.0022,1.1,1.1,0.096,3.3,3.3,0.088,0.00014,0.00014,6.3e-06,0.04,0.04,0.033,0,0,0,0,0,0,0,0 -8790000,0.7,0.0019,-0.014,0.71,-0.034,0.027,-0.15,-0.024,0.028,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.041,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00056,0.00056,0.0022,1.2,1.2,0.095,3.7,3.7,0.087,0.00014,0.00014,6.3e-06,0.04,0.04,0.032,0,0,0,0,0,0,0,0 -8890000,0.7,0.0019,-0.014,0.71,-0.036,0.028,-0.15,-0.027,0.029,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.045,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00057,0.00057,0.0022,1.3,1.3,0.095,3.9,3.9,0.086,0.00013,0.00013,6.3e-06,0.04,0.04,0.03,0,0,0,0,0,0,0,0 -8990000,0.7,0.002,-0.014,0.71,-0.038,0.028,-0.14,-0.031,0.032,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.051,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00059,0.00059,0.0022,1.4,1.4,0.096,4.3,4.3,0.087,0.00013,0.00013,6.3e-06,0.04,0.04,0.029,0,0,0,0,0,0,0,0 -9090000,0.7,0.002,-0.014,0.71,-0.04,0.029,-0.14,-0.034,0.033,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.053,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0006,0.00059,0.0022,1.4,1.4,0.095,4.6,4.6,0.086,0.00013,0.00013,6.3e-06,0.04,0.04,0.028,0,0,0,0,0,0,0,0 -9190000,0.7,0.002,-0.014,0.71,-0.042,0.03,-0.14,-0.038,0.036,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.057,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00062,0.00061,0.0022,1.5,1.5,0.094,5.1,5.1,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.027,0,0,0,0,0,0,0,0 -9290000,0.7,0.002,-0.014,0.71,-0.043,0.03,-0.14,-0.041,0.037,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.061,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00062,0.00062,0.0022,1.6,1.6,0.093,5.3,5.3,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.025,0,0,0,0,0,0,0,0 -9390000,0.7,0.002,-0.014,0.71,-0.044,0.033,-0.14,-0.046,0.039,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.065,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00064,0.00064,0.0023,1.7,1.7,0.093,5.8,5.9,0.086,0.00013,0.00013,6.3e-06,0.04,0.04,0.024,0,0,0,0,0,0,0,0 -9490000,0.7,0.002,-0.014,0.71,-0.045,0.032,-0.13,-0.047,0.04,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.068,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00064,0.00064,0.0023,1.7,1.7,0.091,6.1,6.1,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.023,0,0,0,0,0,0,0,0 -9590000,0.7,0.002,-0.014,0.71,-0.048,0.034,-0.13,-0.052,0.043,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.072,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00066,0.00066,0.0023,1.8,1.8,0.09,6.7,6.7,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.021,0,0,0,0,0,0,0,0 -9690000,0.7,0.0021,-0.014,0.71,-0.048,0.035,-0.12,-0.054,0.043,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.077,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00065,0.00065,0.0023,1.9,1.9,0.089,6.8,6.8,0.086,0.00012,0.00012,6.3e-06,0.04,0.04,0.02,0,0,0,0,0,0,0,0 -9790000,0.7,0.0021,-0.014,0.71,-0.049,0.037,-0.11,-0.059,0.046,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.082,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00067,0.00067,0.0023,2,2,0.087,7.5,7.5,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.019,0,0,0,0,0,0,0,0 -9890000,0.7,0.002,-0.014,0.71,-0.049,0.037,-0.11,-0.06,0.046,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.085,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00067,0.00067,0.0023,2,2,0.084,7.6,7.6,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.018,0,0,0,0,0,0,0,0 -9990000,0.7,0.0021,-0.014,0.71,-0.051,0.038,-0.1,-0.065,0.05,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.089,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00069,0.00069,0.0023,2.1,2.1,0.083,8.4,8.4,0.086,0.00012,0.00012,6.3e-06,0.04,0.04,0.017,0,0,0,0,0,0,0,0 -10090000,0.7,0.0021,-0.014,0.71,-0.049,0.037,-0.096,-0.065,0.049,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.091,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00068,0.00068,0.0023,2.1,2.1,0.08,8.4,8.4,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.016,0,0,0,0,0,0,0,0 -10190000,0.7,0.0021,-0.014,0.71,-0.051,0.04,-0.096,-0.07,0.053,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0007,0.0007,0.0023,2.2,2.2,0.078,9.2,9.2,0.084,0.00012,0.00012,6.3e-06,0.04,0.04,0.014,0,0,0,0,0,0,0,0 -10290000,0.7,0.0021,-0.014,0.71,-0.053,0.04,-0.084,-0.076,0.056,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00072,0.00072,0.0023,2.4,2.4,0.076,10,10,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.014,0,0,0,0,0,0,0,0 -10390000,0.7,0.0021,-0.014,0.71,0.0095,-0.019,0.0096,0.00087,-0.0017,-3.7e+02,-0.0015,-0.0056,4.8e-05,-6.6e-08,4.9e-08,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00075,0.00075,0.0023,0.25,0.25,0.56,0.25,0.25,0.078,0.00012,0.00012,6.3e-06,0.04,0.04,0.013,0,0,0,0,0,0,0,0 -10490000,0.7,0.0021,-0.014,0.71,0.0082,-0.017,0.023,0.0017,-0.0035,-3.7e+02,-0.0015,-0.0056,4.8e-05,-1.7e-06,1.3e-06,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00077,0.00077,0.0023,0.26,0.26,0.55,0.26,0.26,0.08,0.00012,0.00012,6.3e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0 -10590000,0.7,0.0022,-0.014,0.71,0.0078,-0.0065,0.026,0.0018,-0.00081,-3.7e+02,-0.0015,-0.0056,4.9e-05,-0.00027,3.1e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00078,0.00078,0.0023,0.14,0.14,0.27,0.13,0.13,0.073,0.00012,0.00012,6.3e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0 -10690000,0.7,0.0023,-0.014,0.71,0.0057,-0.0058,0.03,0.0025,-0.0014,-3.7e+02,-0.0015,-0.0056,4.9e-05,-0.00027,3.2e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0008,0.0008,0.0023,0.15,0.15,0.26,0.14,0.14,0.078,0.00012,0.00012,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0 -10790000,0.7,0.0023,-0.014,0.71,0.0052,-0.003,0.024,0.0027,-0.00072,-3.7e+02,-0.0014,-0.0056,4.8e-05,-0.00042,0.00016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00077,0.00077,0.0023,0.11,0.11,0.17,0.091,0.091,0.072,0.00011,0.00011,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0 -10890000,0.7,0.0022,-0.014,0.71,0.0039,-0.0017,0.02,0.0031,-0.00093,-3.7e+02,-0.0014,-0.0056,4.8e-05,-0.00042,0.00016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0008,0.0008,0.0023,0.13,0.13,0.16,0.098,0.098,0.075,0.00011,0.00011,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0 -10990000,0.7,0.0022,-0.014,0.71,0.0067,0.0033,0.014,0.0047,-0.0022,-3.7e+02,-0.0014,-0.0055,4.6e-05,-0.00082,0.00076,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00073,0.00073,0.0023,0.1,0.1,0.12,0.073,0.073,0.071,0.0001,0.0001,6.3e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0 -11090000,0.7,0.0022,-0.014,0.71,0.0055,0.0059,0.019,0.0053,-0.0018,-3.7e+02,-0.0014,-0.0055,4.6e-05,-0.00082,0.00076,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00075,0.00075,0.0023,0.13,0.13,0.11,0.08,0.08,0.074,0.0001,0.0001,6.3e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0 -11190000,0.7,0.0021,-0.014,0.71,0.01,0.0083,0.0077,0.0067,-0.0028,-3.7e+02,-0.0013,-0.0055,4.5e-05,-0.00092,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00065,0.00065,0.0023,0.1,0.1,0.084,0.063,0.063,0.069,9.3e-05,9.3e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 -11290000,0.7,0.0021,-0.014,0.71,0.01,0.011,0.0074,0.0078,-0.0018,-3.7e+02,-0.0013,-0.0055,4.5e-05,-0.00093,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00067,0.00067,0.0023,0.13,0.13,0.078,0.071,0.071,0.072,9.3e-05,9.3e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 -11390000,0.7,0.0022,-0.014,0.71,0.0053,0.0092,0.0017,0.0055,-0.0019,-3.7e+02,-0.0013,-0.0056,4.6e-05,-0.0005,0.00089,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00055,0.00055,0.0023,0.1,0.1,0.063,0.058,0.058,0.068,8.2e-05,8.2e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 -11490000,0.7,0.0022,-0.014,0.71,0.0028,0.012,0.0025,0.0059,-0.00089,-3.7e+02,-0.0013,-0.0056,4.6e-05,-0.00051,0.00089,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00057,0.00057,0.0023,0.13,0.13,0.058,0.066,0.066,0.069,8.2e-05,8.2e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 -11590000,0.7,0.0021,-0.014,0.71,-0.0016,0.01,-0.0034,0.0045,-0.0014,-3.7e+02,-0.0014,-0.0056,4.6e-05,-8.7e-05,0.00077,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00047,0.00047,0.0023,0.1,0.1,0.049,0.054,0.054,0.066,7.2e-05,7.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -11690000,0.7,0.0021,-0.014,0.71,-0.0044,0.013,-0.0079,0.0042,-0.00027,-3.7e+02,-0.0014,-0.0056,4.6e-05,-7.8e-05,0.00076,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00048,0.00048,0.0023,0.12,0.12,0.046,0.063,0.063,0.066,7.2e-05,7.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -11790000,0.7,0.0021,-0.014,0.71,-0.01,0.013,-0.0098,0.0018,0.00056,-3.7e+02,-0.0014,-0.0056,4.6e-05,2.9e-05,0.00057,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0004,0.0004,0.0023,0.097,0.097,0.039,0.053,0.053,0.063,6.3e-05,6.3e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -11890000,0.7,0.0021,-0.014,0.71,-0.012,0.014,-0.011,0.00076,0.0019,-3.7e+02,-0.0014,-0.0056,4.6e-05,2.4e-05,0.00057,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00041,0.00041,0.0023,0.12,0.12,0.037,0.061,0.061,0.063,6.3e-05,6.3e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -11990000,0.7,0.0021,-0.014,0.71,-0.013,0.014,-0.016,-0.0003,0.0023,-3.7e+02,-0.0014,-0.0057,4.6e-05,0.00016,0.00059,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00034,0.00034,0.0023,0.091,0.091,0.033,0.051,0.051,0.061,5.7e-05,5.7e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -12090000,0.7,0.0021,-0.014,0.71,-0.015,0.016,-0.022,-0.0017,0.0038,-3.7e+02,-0.0014,-0.0057,4.6e-05,0.00018,0.00058,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00035,0.00035,0.0023,0.11,0.11,0.031,0.06,0.06,0.061,5.7e-05,5.7e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -12190000,0.7,0.0018,-0.014,0.71,-0.008,0.013,-0.017,0.0015,0.0019,-3.7e+02,-0.0013,-0.0057,4.3e-05,0.00043,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0003,0.0003,0.0023,0.085,0.085,0.028,0.051,0.051,0.059,5.2e-05,5.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -12290000,0.7,0.0017,-0.014,0.71,-0.011,0.015,-0.016,0.00055,0.0033,-3.7e+02,-0.0013,-0.0057,4.3e-05,0.00041,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00031,0.00031,0.0023,0.1,0.1,0.028,0.06,0.06,0.059,5.2e-05,5.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -12390000,0.7,0.0014,-0.014,0.71,-0.0051,0.011,-0.015,0.003,0.0016,-3.7e+02,-0.0012,-0.0058,4.1e-05,0.00057,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00027,0.00027,0.0023,0.079,0.079,0.026,0.05,0.05,0.057,4.8e-05,4.8e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -12490000,0.7,0.0014,-0.014,0.71,-0.0063,0.013,-0.018,0.0025,0.0029,-3.7e+02,-0.0012,-0.0058,4.1e-05,0.00057,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00028,0.00028,0.0023,0.093,0.093,0.026,0.059,0.059,0.057,4.8e-05,4.8e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -12590000,0.7,0.0015,-0.014,0.71,-0.014,0.011,-0.023,-0.0028,0.0014,-3.7e+02,-0.0013,-0.0058,4.3e-05,0.0007,0.0012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00025,0.00025,0.0023,0.074,0.074,0.025,0.05,0.05,0.055,4.5e-05,4.5e-05,6.3e-06,0.037,0.037,0.0099,0,0,0,0,0,0,0,0 -12690000,0.7,0.0015,-0.014,0.71,-0.014,0.012,-0.027,-0.0042,0.0026,-3.7e+02,-0.0013,-0.0058,4.3e-05,0.00073,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00026,0.00026,0.0023,0.085,0.085,0.025,0.058,0.058,0.055,4.5e-05,4.5e-05,6.3e-06,0.037,0.037,0.0098,0,0,0,0,0,0,0,0 -12790000,0.7,0.0016,-0.013,0.71,-0.02,0.0091,-0.03,-0.0076,0.0013,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.00077,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00023,0.00023,0.0023,0.068,0.068,0.024,0.049,0.049,0.053,4.2e-05,4.2e-05,6.3e-06,0.037,0.037,0.0097,0,0,0,0,0,0,0,0 -12890000,0.7,0.0015,-0.013,0.71,-0.021,0.0091,-0.029,-0.0096,0.0022,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.0007,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00024,0.00024,0.0023,0.079,0.079,0.025,0.058,0.058,0.054,4.2e-05,4.2e-05,6.3e-06,0.037,0.037,0.0096,0,0,0,0,0,0,0,0 -12990000,0.71,0.0012,-0.014,0.71,-0.0084,0.0066,-0.03,-0.001,0.0012,-3.7e+02,-0.0012,-0.0059,4e-05,0.00068,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00022,0.00022,0.0023,0.064,0.064,0.025,0.049,0.049,0.052,4e-05,4e-05,6.3e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0 -13090000,0.7,0.0012,-0.014,0.71,-0.0091,0.0067,-0.03,-0.0019,0.0018,-3.7e+02,-0.0012,-0.0059,4e-05,0.00065,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00023,0.00023,0.0023,0.073,0.073,0.025,0.058,0.058,0.052,4e-05,4e-05,6.3e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0 -13190000,0.7,0.00093,-0.014,0.71,1.1e-05,0.0061,-0.027,0.0044,0.0012,-3.7e+02,-0.0012,-0.0059,3.8e-05,0.0005,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00021,0.00021,0.0023,0.06,0.06,0.025,0.049,0.049,0.051,3.8e-05,3.8e-05,6.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0 -13290000,0.71,0.00094,-0.014,0.71,-0.00023,0.0069,-0.024,0.0044,0.0018,-3.7e+02,-0.0012,-0.0059,3.8e-05,0.00037,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00022,0.00022,0.0023,0.068,0.068,0.027,0.057,0.057,0.051,3.8e-05,3.8e-05,6.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0 -13390000,0.71,0.00079,-0.014,0.71,0.00059,0.0059,-0.02,0.0033,0.0011,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.0002,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00021,0.00021,0.0023,0.056,0.056,0.026,0.049,0.049,0.05,3.6e-05,3.6e-05,6.3e-06,0.037,0.037,0.0088,0,0,0,0,0,0,0,0 -13490000,0.71,0.00082,-0.014,0.71,9.8e-05,0.0058,-0.019,0.0034,0.0016,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.00011,0.0016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00021,0.00021,0.0023,0.064,0.064,0.028,0.057,0.057,0.05,3.6e-05,3.6e-05,6.3e-06,0.037,0.037,0.0087,0,0,0,0,0,0,0,0 -13590000,0.71,0.00076,-0.014,0.71,0.00035,0.0061,-0.021,0.0024,0.001,-3.7e+02,-0.0012,-0.006,3.7e-05,8.6e-05,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0002,0.0002,0.0023,0.053,0.053,0.028,0.049,0.049,0.05,3.4e-05,3.4e-05,6.3e-06,0.036,0.036,0.0084,0,0,0,0,0,0,0,0 -13690000,0.71,0.00074,-0.014,0.71,0.001,0.0078,-0.025,0.0025,0.0017,-3.7e+02,-0.0012,-0.006,3.7e-05,0.00011,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00021,0.00021,0.0023,0.06,0.06,0.029,0.056,0.056,0.05,3.4e-05,3.4e-05,6.3e-06,0.036,0.036,0.0083,0,0,0,0,0,0,0,0 -13790000,0.71,0.00062,-0.014,0.71,0.0016,0.0036,-0.027,0.0035,-0.00064,-3.7e+02,-0.0011,-0.006,3.6e-05,-0.0001,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0002,0.0002,0.0023,0.051,0.051,0.029,0.048,0.048,0.049,3.3e-05,3.3e-05,6.3e-06,0.036,0.036,0.0079,0,0,0,0,0,0,0,0 -13890000,0.71,0.00059,-0.014,0.71,0.0021,0.0035,-0.031,0.0037,-0.0003,-3.7e+02,-0.0011,-0.006,3.6e-05,-7.6e-05,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00021,0.00021,0.0023,0.057,0.057,0.03,0.056,0.056,0.05,3.3e-05,3.3e-05,6.3e-06,0.036,0.036,0.0078,0,0,0,0,0,0,0,0 -13990000,0.71,0.00052,-0.014,0.71,0.0024,0.001,-0.03,0.0045,-0.002,-3.7e+02,-0.0011,-0.006,3.5e-05,-0.00034,0.0012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0002,0.0002,0.0023,0.048,0.048,0.03,0.048,0.048,0.05,3.1e-05,3.1e-05,6.3e-06,0.036,0.036,0.0074,0,0,0,0,0,0,0,0 -14090000,0.71,0.0005,-0.014,0.71,0.0025,0.0012,-0.031,0.0047,-0.0019,-3.7e+02,-0.0011,-0.006,3.5e-05,-0.00033,0.0012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0002,0.0002,0.0023,0.055,0.055,0.031,0.055,0.055,0.05,3.1e-05,3.1e-05,6.3e-06,0.036,0.036,0.0073,0,0,0,0,0,0,0,0 -14190000,0.71,0.0004,-0.014,0.71,0.0058,0.00063,-0.033,0.0068,-0.0017,-3.7e+02,-0.0011,-0.006,3.5e-05,-0.00032,0.00089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0002,0.0002,0.0023,0.046,0.046,0.031,0.048,0.048,0.05,2.9e-05,2.9e-05,6.3e-06,0.036,0.036,0.0069,0,0,0,0,0,0,0,0 -14290000,0.71,0.00041,-0.014,0.71,0.0066,0.0014,-0.032,0.0074,-0.0016,-3.7e+02,-0.0011,-0.006,3.5e-05,-0.00039,0.00094,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0002,0.0002,0.0023,0.052,0.052,0.032,0.055,0.055,0.051,2.9e-05,2.9e-05,6.3e-06,0.036,0.036,0.0067,0,0,0,0,0,0,0,0 -14390000,0.71,0.00033,-0.014,0.71,0.0084,0.0023,-0.034,0.0088,-0.0013,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.0004,0.00069,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00019,0.00019,0.0023,0.045,0.045,0.031,0.048,0.048,0.05,2.8e-05,2.8e-05,6.3e-06,0.036,0.036,0.0063,0,0,0,0,0,0,0,0 -14490000,0.71,0.00031,-0.013,0.71,0.0084,0.0035,-0.037,0.0096,-0.0011,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00034,0.00064,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0002,0.0002,0.0023,0.05,0.05,0.032,0.055,0.055,0.051,2.8e-05,2.8e-05,6.3e-06,0.036,0.036,0.0062,0,0,0,0,0,0,0,0 -14590000,0.71,0.0003,-0.013,0.71,0.0049,0.0019,-0.037,0.006,-0.0025,-3.7e+02,-0.0011,-0.0061,3.5e-05,-0.00072,0.0011,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00019,0.00019,0.0023,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-05,2.6e-05,6.3e-06,0.036,0.036,0.0058,0,0,0,0,0,0,0,0 -14690000,0.71,0.00026,-0.013,0.71,0.0063,-0.001,-0.034,0.0066,-0.0024,-3.7e+02,-0.0011,-0.0061,3.5e-05,-0.00082,0.0011,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0002,0.0002,0.0023,0.049,0.049,0.032,0.054,0.054,0.051,2.6e-05,2.6e-05,6.3e-06,0.036,0.036,0.0056,0,0,0,0,0,0,0,0 -14790000,0.71,0.00029,-0.013,0.71,0.0031,-0.0026,-0.03,0.0037,-0.0034,-3.7e+02,-0.0011,-0.0061,3.6e-05,-0.0012,0.0016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00019,0.00019,0.0023,0.042,0.042,0.031,0.047,0.047,0.051,2.5e-05,2.5e-05,6.3e-06,0.036,0.036,0.0053,0,0,0,0,0,0,0,0 -14890000,0.71,0.00028,-0.013,0.71,0.0046,-0.0017,-0.033,0.0041,-0.0036,-3.7e+02,-0.0011,-0.0061,3.6e-05,-0.0012,0.0016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0002,0.00019,0.0023,0.047,0.047,0.031,0.054,0.054,0.052,2.5e-05,2.5e-05,6.3e-06,0.036,0.036,0.0051,0,0,0,0,0,0,0,0 -14990000,0.71,0.00028,-0.013,0.71,0.0034,-0.0018,-0.029,0.0032,-0.0029,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0013,0.0019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00019,0.00019,0.0023,0.041,0.041,0.03,0.047,0.047,0.051,2.3e-05,2.3e-05,6.3e-06,0.036,0.036,0.0048,0,0,0,0,0,0,0,0 -15090000,0.71,0.0002,-0.013,0.71,0.0038,-0.002,-0.032,0.0035,-0.0031,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0012,0.0018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00019,0.00019,0.0023,0.046,0.046,0.031,0.054,0.054,0.052,2.3e-05,2.3e-05,6.3e-06,0.036,0.036,0.0046,0,0,0,0,0,0,0,0 -15190000,0.71,0.00022,-0.013,0.71,0.0032,-0.00079,-0.029,0.0028,-0.0024,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0012,0.002,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00019,0.00019,0.0023,0.04,0.04,0.03,0.047,0.047,0.052,2.2e-05,2.2e-05,6.3e-06,0.035,0.035,0.0043,0,0,0,0,0,0,0,0 -15290000,0.71,0.00018,-0.013,0.71,0.0038,-0.00063,-0.027,0.0031,-0.0025,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0013,0.0021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00019,0.00019,0.0023,0.045,0.045,0.03,0.054,0.054,0.052,2.2e-05,2.2e-05,6.3e-06,0.035,0.035,0.0042,0,0,0,0,0,0,0,0 -15390000,0.71,0.00019,-0.013,0.71,0.003,-0.00028,-0.024,0.00057,-0.002,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0014,0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00018,0.00018,0.0023,0.04,0.04,0.029,0.047,0.047,0.051,2e-05,2e-05,6.3e-06,0.035,0.035,0.0039,0,0,0,0,0,0,0,0 -15490000,0.71,0.0002,-0.013,0.71,0.0043,-0.00067,-0.024,0.00095,-0.0021,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00019,0.00019,0.0023,0.045,0.045,0.029,0.053,0.053,0.053,2e-05,2e-05,6.3e-06,0.035,0.035,0.0037,0,0,0,0,0,0,0,0 -15590000,0.71,0.00022,-0.013,0.71,0.0024,-0.00066,-0.023,-0.0013,-0.0017,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00018,0.00018,0.0023,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-05,1.9e-05,6.3e-06,0.035,0.035,0.0035,0,0,0,0,0,0,0,0 -15690000,0.71,0.00022,-0.013,0.71,0.0027,-0.00083,-0.023,-0.0011,-0.0018,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00019,0.00018,0.0023,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-05,1.9e-05,6.3e-06,0.035,0.035,0.0033,0,0,0,0,0,0,0,0 -15790000,0.71,0.00018,-0.013,0.71,0.0032,-0.0025,-0.026,-0.00095,-0.0028,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0016,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00018,0.00018,0.0023,0.038,0.038,0.027,0.046,0.046,0.051,1.7e-05,1.7e-05,6.3e-06,0.035,0.035,0.0031,0,0,0,0,0,0,0,0 -15890000,0.71,0.00014,-0.013,0.71,0.0041,-0.003,-0.024,-0.00056,-0.0031,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0016,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00018,0.00018,0.0023,0.043,0.043,0.027,0.053,0.053,0.052,1.7e-05,1.7e-05,6.3e-06,0.035,0.035,0.003,0,0,0,0,0,0,0,0 -15990000,0.71,8e-05,-0.013,0.71,0.004,-0.0039,-0.019,-0.00063,-0.0039,-3.7e+02,-0.0012,-0.0061,3.8e-05,-0.0019,0.0027,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00017,0.00017,0.0023,0.038,0.038,0.026,0.046,0.046,0.051,1.6e-05,1.6e-05,6.3e-06,0.034,0.034,0.0028,0,0,0,0,0,0,0,0 -16090000,0.71,8.2e-05,-0.013,0.71,0.0057,-0.0041,-0.016,-0.00016,-0.0043,-3.7e+02,-0.0012,-0.0061,3.8e-05,-0.002,0.0028,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00018,0.00018,0.0023,0.043,0.043,0.025,0.053,0.053,0.052,1.6e-05,1.6e-05,6.3e-06,0.034,0.034,0.0027,0,0,0,0,0,0,0,0 -16190000,0.71,0.00011,-0.013,0.71,0.0057,-0.0033,-0.014,-0.00037,-0.0035,-3.7e+02,-0.0012,-0.0061,3.8e-05,-0.0019,0.003,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00017,0.00017,0.0023,0.037,0.037,0.025,0.046,0.046,0.051,1.5e-05,1.5e-05,6.3e-06,0.034,0.034,0.0025,0,0,0,0,0,0,0,0 -16290000,0.71,0.00013,-0.013,0.71,0.0073,-0.0041,-0.016,0.00029,-0.0038,-3.7e+02,-0.0012,-0.0061,3.8e-05,-0.0018,0.003,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00017,0.00017,0.0023,0.042,0.042,0.024,0.053,0.053,0.052,1.5e-05,1.5e-05,6.3e-06,0.034,0.034,0.0024,0,0,0,0,0,0,0,0 -16390000,0.71,0.00012,-0.013,0.71,0.0062,-0.0044,-0.015,-4.3e-05,-0.0031,-3.7e+02,-0.0013,-0.0061,3.8e-05,-0.0017,0.0033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00017,0.00017,0.0023,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-05,1.4e-05,6.3e-06,0.034,0.034,0.0022,0,0,0,0,0,0,0,0 -16490000,0.71,0.00013,-0.013,0.71,0.0054,-0.0039,-0.018,0.00051,-0.0035,-3.7e+02,-0.0012,-0.0061,3.8e-05,-0.0017,0.0032,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00017,0.00017,0.0023,0.041,0.041,0.023,0.052,0.052,0.052,1.4e-05,1.4e-05,6.3e-06,0.034,0.034,0.0021,0,0,0,0,0,0,0,0 -16590000,0.71,0.00039,-0.013,0.71,0.0018,-0.0012,-0.018,-0.0024,-8.3e-05,-3.7e+02,-0.0013,-0.006,4e-05,-0.001,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00016,0.00016,0.0023,0.036,0.036,0.022,0.046,0.046,0.051,1.2e-05,1.2e-05,6.3e-06,0.033,0.033,0.002,0,0,0,0,0,0,0,0 -16690000,0.71,0.00038,-0.013,0.71,0.002,-0.00073,-0.015,-0.0022,-0.00018,-3.7e+02,-0.0013,-0.006,4e-05,-0.0011,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00017,0.00016,0.0023,0.041,0.041,0.022,0.052,0.052,0.051,1.2e-05,1.2e-05,6.3e-06,0.033,0.033,0.0019,0,0,0,0,0,0,0,0 -16790000,0.71,0.00053,-0.013,0.71,-0.0013,0.0015,-0.014,-0.0046,0.0025,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0005,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00016,0.00016,0.0023,0.036,0.036,0.021,0.046,0.046,0.05,1.1e-05,1.1e-05,6.3e-06,0.033,0.033,0.0018,0,0,0,0,0,0,0,0 -16890000,0.71,0.00054,-0.013,0.71,-0.0016,0.0023,-0.011,-0.0047,0.0027,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.00054,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00016,0.00016,0.0023,0.04,0.04,0.021,0.052,0.052,0.051,1.1e-05,1.1e-05,6.3e-06,0.033,0.033,0.0017,0,0,0,0,0,0,0,0 -16990000,0.71,0.00048,-0.013,0.71,-0.0016,0.00033,-0.01,-0.0052,0.00085,-3.7e+02,-0.0013,-0.006,4.2e-05,-0.00095,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00015,0.00015,0.0023,0.035,0.035,0.02,0.046,0.046,0.05,1e-05,1e-05,6.3e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0 -17090000,0.71,0.00045,-0.013,0.71,-0.0008,0.0013,-0.01,-0.0053,0.0009,-3.7e+02,-0.0013,-0.006,4.2e-05,-0.00094,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00016,0.00016,0.0023,0.039,0.039,0.02,0.052,0.052,0.05,1e-05,1e-05,6.3e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0 -17190000,0.71,0.00044,-0.013,0.71,-0.00035,0.0013,-0.011,-0.0056,-0.00053,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0013,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00015,0.00015,0.0023,0.035,0.035,0.019,0.046,0.046,0.049,9.4e-06,9.4e-06,6.3e-06,0.032,0.032,0.0015,0,0,0,0,0,0,0,0 -17290000,0.71,0.00041,-0.013,0.71,0.0017,0.0023,-0.0066,-0.0056,-0.00037,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0013,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00015,0.00015,0.0023,0.039,0.039,0.019,0.052,0.052,0.049,9.4e-06,9.4e-06,6.3e-06,0.032,0.032,0.0014,0,0,0,0,0,0,0,0 -17390000,0.71,0.00038,-0.013,0.71,0.0024,0.0015,-0.0047,-0.0046,-0.0016,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0017,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00015,0.00015,0.0023,0.034,0.034,0.018,0.046,0.046,0.048,8.5e-06,8.5e-06,6.3e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0 -17490000,0.71,0.00037,-0.013,0.71,0.0029,0.0011,-0.003,-0.0044,-0.0015,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0017,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00015,0.00015,0.0023,0.038,0.038,0.018,0.052,0.052,0.049,8.5e-06,8.5e-06,6.3e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0 -17590000,0.71,0.00029,-0.013,0.71,0.0042,-0.0001,0.0025,-0.0037,-0.0026,-3.7e+02,-0.0014,-0.0061,4.1e-05,-0.002,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00014,0.00014,0.0023,0.034,0.034,0.017,0.045,0.045,0.048,7.7e-06,7.7e-06,6.3e-06,0.032,0.032,0.0012,0,0,0,0,0,0,0,0 -17690000,0.71,0.00026,-0.013,0.71,0.0051,0.0006,0.0019,-0.0032,-0.0026,-3.7e+02,-0.0014,-0.0061,4.1e-05,-0.002,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00014,0.00014,0.0023,0.037,0.037,0.017,0.052,0.052,0.048,7.7e-06,7.7e-06,6.3e-06,0.032,0.032,0.0012,0,0,0,0,0,0,0,0 -17790000,0.71,0.00017,-0.013,0.71,0.0076,0.00033,0.00059,-0.0021,-0.0022,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.002,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00014,0.00014,0.0023,0.033,0.033,0.016,0.045,0.045,0.048,7e-06,7e-06,6.3e-06,0.032,0.032,0.0011,0,0,0,0,0,0,0,0 -17890000,0.71,0.00018,-0.013,0.71,0.0092,-0.00043,0.00069,-0.0012,-0.0022,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.002,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00014,0.00014,0.0024,0.037,0.037,0.016,0.052,0.052,0.048,7e-06,7e-06,6.3e-06,0.032,0.032,0.0011,0,0,0,0,0,0,0,0 -17990000,0.71,0.00012,-0.013,0.71,0.011,-0.0022,0.0019,-0.00052,-0.0019,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00013,0.00013,0.0024,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-06,6.4e-06,6.3e-06,0.031,0.031,0.001,0,0,0,0,0,0,0,0 -18090000,0.71,0.00013,-0.013,0.71,0.012,-0.0023,0.0043,0.0006,-0.0021,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00014,0.00014,0.0024,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-06,6.4e-06,6.3e-06,0.031,0.031,0.00097,0,0,0,0,0,0,0,0 -18190000,0.71,9.6e-05,-0.013,0.71,0.012,-0.0013,0.0056,0.0015,-0.0017,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00013,0.00013,0.0024,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-06,5.8e-06,6.3e-06,0.031,0.031,0.00092,0,0,0,0,0,0,0,0 -18290000,0.71,3.7e-05,-0.012,0.71,0.012,-0.0018,0.0068,0.0027,-0.0018,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00013,0.00013,0.0024,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-06,5.8e-06,6.3e-06,0.031,0.031,0.00089,0,0,0,0,0,0,0,0 -18390000,0.71,5.4e-05,-0.013,0.71,0.013,-0.00018,0.008,0.0032,-0.0014,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0018,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00013,0.00013,0.0024,0.031,0.031,0.014,0.045,0.045,0.046,5.2e-06,5.2e-06,6.3e-06,0.031,0.031,0.00084,0,0,0,0,0,0,0,0 -18490000,0.71,7e-05,-0.012,0.71,0.014,0.00024,0.0076,0.0047,-0.0014,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0018,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00013,0.00013,0.0024,0.034,0.034,0.014,0.051,0.051,0.046,5.2e-06,5.2e-06,6.3e-06,0.031,0.031,0.00082,0,0,0,0,0,0,0,0 -18590000,0.71,7.7e-05,-0.012,0.71,0.013,0.00048,0.0058,0.0035,-0.0012,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00012,0.00012,0.0024,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-06,4.8e-06,6.3e-06,0.031,0.031,0.00078,0,0,0,0,0,0,0,0 -18690000,0.71,4.5e-05,-0.012,0.71,0.014,-0.00022,0.0039,0.0049,-0.0011,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00013,0.00013,0.0024,0.033,0.033,0.013,0.051,0.051,0.045,4.8e-06,4.8e-06,6.3e-06,0.031,0.031,0.00075,0,0,0,0,0,0,0,0 -18790000,0.71,7.5e-05,-0.012,0.71,0.012,8.9e-05,0.0035,0.0037,-0.0009,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00012,0.00012,0.0024,0.03,0.03,0.013,0.045,0.045,0.045,4.3e-06,4.3e-06,6.3e-06,0.031,0.031,0.00072,0,0,0,0,0,0,0,0 -18890000,0.71,0.0001,-0.012,0.71,0.013,0.00059,0.0042,0.005,-0.00083,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00012,0.00012,0.0024,0.033,0.033,0.013,0.051,0.051,0.045,4.3e-06,4.3e-06,6.3e-06,0.031,0.031,0.0007,0,0,0,0,0,0,0,0 -18990000,0.71,8.9e-05,-0.012,0.71,0.014,0.0015,0.0028,0.0063,-0.00069,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00012,0.00012,0.0024,0.029,0.029,0.012,0.045,0.045,0.044,3.9e-06,3.9e-06,6.3e-06,0.031,0.031,0.00066,0,0,0,0,0,0,0,0 -19090000,0.71,7.3e-05,-0.012,0.71,0.015,0.0021,0.0058,0.0078,-0.00049,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00012,0.00012,0.0024,0.032,0.032,0.012,0.051,0.051,0.044,3.9e-06,3.9e-06,6.3e-06,0.031,0.031,0.00065,0,0,0,0,0,0,0,0 -19190000,0.71,7.7e-05,-0.012,0.71,0.015,0.0021,0.0059,0.0086,-0.00044,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00012,0.00012,0.0024,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-06,3.6e-06,6.3e-06,0.03,0.03,0.00062,0,0,0,0,0,0,0,0 -19290000,0.71,9.9e-05,-0.012,0.71,0.015,0.0013,0.0086,0.01,-0.00025,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00012,0.00012,0.0024,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-06,3.6e-06,6.3e-06,0.03,0.03,0.0006,0,0,0,0,0,0,0,0 -19390000,0.71,0.00011,-0.012,0.71,0.013,0.00041,0.012,0.008,-0.00027,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00011,0.00011,0.0024,0.027,0.027,0.012,0.044,0.044,0.043,3.3e-06,3.3e-06,6.3e-06,0.03,0.03,0.00058,0,0,0,0,0,0,0,0 -19490000,0.71,0.00014,-0.012,0.71,0.012,-0.00031,0.0088,0.0092,-0.00027,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00011,0.00011,0.0024,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-06,3.3e-06,6.3e-06,0.03,0.03,0.00056,0,0,0,0,0,0,0,0 -19590000,0.71,0.00019,-0.012,0.71,0.0096,-0.0013,0.0081,0.0075,-0.00029,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00011,0.00011,0.0024,0.027,0.027,0.011,0.044,0.044,0.042,3e-06,3e-06,6.3e-06,0.03,0.03,0.00054,0,0,0,0,0,0,0,0 -19690000,0.71,0.00019,-0.012,0.71,0.01,-0.0035,0.0096,0.0084,-0.00054,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00011,0.00011,0.0024,0.029,0.029,0.011,0.05,0.05,0.042,3e-06,3e-06,6.3e-06,0.03,0.03,0.00052,0,0,0,0,0,0,0,0 -19790000,0.71,0.00025,-0.012,0.71,0.0077,-0.0044,0.01,0.0068,-0.00043,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0065,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00011,0.00011,0.0024,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-06,2.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19890000,0.71,0.0002,-0.012,0.71,0.0065,-0.0047,0.011,0.0075,-0.0009,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0065,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00011,0.00011,0.0024,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-06,2.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19990000,0.71,0.00019,-0.012,0.71,0.004,-0.0054,0.014,0.0061,-0.00075,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0018,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00011,0.00011,0.0024,0.025,0.026,0.01,0.044,0.044,0.041,2.5e-06,2.5e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20090000,0.71,0.00019,-0.012,0.71,0.0038,-0.0073,0.014,0.0065,-0.0014,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0018,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00011,0.00011,0.0024,0.028,0.028,0.01,0.049,0.049,0.042,2.5e-06,2.5e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20190000,0.71,0.0003,-0.012,0.71,0.0015,-0.008,0.017,0.0042,-0.0011,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0017,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00011,0.0001,0.0024,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-06,2.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20290000,0.71,0.00026,-0.012,0.71,0.00034,-0.0096,0.015,0.0043,-0.002,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0017,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00011,0.00011,0.0024,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-06,2.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20390000,0.71,0.00028,-0.012,0.71,-0.0021,-0.01,0.017,0.0024,-0.0015,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0016,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0001,0.0001,0.0024,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-06,2.1e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20490000,0.71,0.00033,-0.012,0.71,-0.0026,-0.011,0.016,0.0022,-0.0026,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0016,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0001,0.0001,0.0024,0.026,0.026,0.0096,0.049,0.049,0.041,2.1e-06,2.1e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20590000,0.71,0.00035,-0.012,0.71,-0.0022,-0.011,0.013,0.0019,-0.0021,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0014,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0001,0.0001,0.0024,0.024,0.024,0.0094,0.044,0.044,0.04,1.9e-06,1.9e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20690000,0.71,0.00038,-0.012,0.71,-0.0022,-0.012,0.015,0.0016,-0.0032,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0014,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0001,0.0001,0.0024,0.026,0.026,0.0093,0.049,0.049,0.04,1.9e-06,1.9e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20790000,0.71,0.00041,-0.012,0.71,-0.0033,-0.011,0.015,0.0014,-0.0025,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0012,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0001,0.0001,0.0024,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-06,1.8e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20890000,0.71,0.0004,-0.012,0.71,-0.0038,-0.014,0.014,0.001,-0.0038,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0012,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0001,0.0001,0.0024,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-06,1.8e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20990000,0.71,0.0004,-0.012,0.71,-0.004,-0.014,0.015,0.0027,-0.0031,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00098,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,9.9e-05,9.8e-05,0.0024,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-06,1.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -21090000,0.71,0.0004,-0.012,0.71,-0.0041,-0.017,0.015,0.0022,-0.0047,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00098,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0001,9.9e-05,0.0024,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-06,1.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -21190000,0.71,0.00044,-0.012,0.71,-0.0034,-0.016,0.014,0.0037,-0.0038,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00074,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,9.8e-05,9.7e-05,0.0024,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-06,1.5e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21290000,0.71,0.00048,-0.012,0.71,-0.0039,-0.018,0.016,0.0034,-0.0055,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00073,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,9.9e-05,9.8e-05,0.0024,0.024,0.024,0.0086,0.048,0.048,0.039,1.5e-06,1.5e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21390000,0.71,0.00053,-0.012,0.71,-0.0047,-0.017,0.016,0.0028,-0.0034,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00036,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,9.7e-05,9.6e-05,0.0024,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21490000,0.71,0.00054,-0.012,0.71,-0.0053,-0.018,0.015,0.0023,-0.0052,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00036,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,9.7e-05,9.7e-05,0.0024,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21590000,0.71,0.00056,-0.012,0.71,-0.0058,-0.016,0.015,0.0019,-0.0032,-3.7e+02,-0.0014,-0.006,4.5e-05,-7.6e-06,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,9.6e-05,9.5e-05,0.0024,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21690000,0.71,0.00057,-0.012,0.71,-0.0057,-0.017,0.017,0.0013,-0.0048,-3.7e+02,-0.0014,-0.006,4.5e-05,-8.8e-06,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,9.6e-05,9.5e-05,0.0024,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21790000,0.71,0.00059,-0.012,0.71,-0.0063,-0.011,0.015,8.8e-05,-0.00078,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00052,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,9.5e-05,9.4e-05,0.0024,0.021,0.021,0.0082,0.042,0.042,0.038,1.2e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21890000,0.71,0.00059,-0.012,0.71,-0.0063,-0.012,0.016,-0.00054,-0.0019,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00051,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,9.5e-05,9.4e-05,0.0024,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21990000,0.71,0.00065,-0.012,0.71,-0.0068,-0.0092,0.016,-0.0015,0.0014,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00095,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,9.4e-05,9.3e-05,0.0024,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-06,1.2e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22090000,0.71,0.00066,-0.012,0.71,-0.0071,-0.0083,0.015,-0.0021,0.00059,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00095,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,9.4e-05,9.3e-05,0.0024,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-06,1.2e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22190000,0.71,0.00063,-0.012,0.71,-0.0069,-0.0074,0.015,-0.0018,0.00056,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.001,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,9.3e-05,9.2e-05,0.0024,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-06,1.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22290000,0.71,0.00067,-0.012,0.71,-0.0083,-0.0081,0.015,-0.0025,-0.00023,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.001,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,9.3e-05,9.3e-05,0.0024,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-06,1.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22390000,0.71,0.00064,-0.012,0.71,-0.0089,-0.0076,0.017,-0.0022,-0.00021,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0011,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,9.2e-05,9.1e-05,0.0024,0.019,0.019,0.0079,0.042,0.042,0.037,1e-06,1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22490000,0.71,0.00065,-0.012,0.71,-0.0095,-0.0075,0.018,-0.0031,-0.00099,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0011,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,9.3e-05,9.2e-05,0.0025,0.021,0.021,0.0079,0.047,0.047,0.037,1e-06,1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22590000,0.71,0.00063,-0.012,0.71,-0.0092,-0.007,0.017,-0.0034,0.0001,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,9.1e-05,9.1e-05,0.0025,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-07,9.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22690000,0.71,0.00067,-0.012,0.71,-0.01,-0.0068,0.018,-0.0044,-0.00059,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,9.2e-05,9.1e-05,0.0025,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-07,9.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22790000,0.71,0.00065,-0.012,0.71,-0.011,-0.0056,0.019,-0.0055,-0.00047,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,9.1e-05,9e-05,0.0025,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-07,9.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22890000,0.71,0.00066,-0.012,0.71,-0.012,-0.0052,0.021,-0.0066,-0.001,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,9.1e-05,9e-05,0.0025,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-07,9.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22990000,0.71,0.00064,-0.012,0.71,-0.012,-0.0057,0.022,-0.0074,-0.0009,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0014,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,9e-05,8.9e-05,0.0025,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-07,8.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23090000,0.71,0.00061,-0.012,0.71,-0.013,-0.0057,0.022,-0.0087,-0.0014,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0014,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,9e-05,9e-05,0.0025,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-07,8.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23190000,0.71,0.00067,-0.012,0.71,-0.015,-0.0066,0.024,-0.012,-0.0013,-3.7e+02,-0.0014,-0.0059,4.6e-05,0.0014,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.9e-05,8.9e-05,0.0025,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-07,8.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23290000,0.71,0.00061,-0.012,0.71,-0.015,-0.0079,0.024,-0.013,-0.002,-3.7e+02,-0.0014,-0.0059,4.6e-05,0.0014,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,9e-05,8.9e-05,0.0025,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-07,8.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23390000,0.71,0.00071,-0.012,0.71,-0.016,-0.0081,0.022,-0.016,-0.0018,-3.7e+02,-0.0014,-0.0059,4.6e-05,0.0015,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.9e-05,8.8e-05,0.0025,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-07,7.8e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23490000,0.71,0.0031,-0.0096,0.71,-0.023,-0.009,-0.012,-0.018,-0.0027,-3.7e+02,-0.0014,-0.0059,4.6e-05,0.0015,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.9e-05,8.8e-05,0.0025,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-07,7.8e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23590000,0.71,0.0083,-0.0017,0.71,-0.034,-0.0078,-0.044,-0.017,-0.0013,-3.7e+02,-0.0014,-0.0059,4.6e-05,0.0017,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.8e-05,8.8e-05,0.0025,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-07,7.4e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23690000,0.7,0.0079,0.004,0.71,-0.065,-0.017,-0.094,-0.021,-0.0025,-3.7e+02,-0.0014,-0.0059,4.6e-05,0.0017,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.8e-05,8.8e-05,0.0025,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-07,7.4e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23790000,0.7,0.005,0.00066,0.71,-0.089,-0.028,-0.15,-0.021,-0.0018,-3.7e+02,-0.0014,-0.0059,4.6e-05,0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.7e-05,8.7e-05,0.0025,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-07,7.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23890000,0.7,0.0024,-0.0054,0.71,-0.11,-0.037,-0.2,-0.03,-0.0051,-3.7e+02,-0.0014,-0.0059,4.6e-05,0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.8e-05,8.7e-05,0.0025,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-07,7.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23990000,0.7,0.00099,-0.01,0.71,-0.11,-0.04,-0.25,-0.034,-0.0083,-3.7e+02,-0.0014,-0.0059,4.6e-05,0.0021,0.0059,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.7e-05,8.6e-05,0.0025,0.017,0.017,0.0077,0.041,0.041,0.035,6.8e-07,6.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24090000,0.7,0.0023,-0.0088,0.71,-0.11,-0.04,-0.3,-0.045,-0.012,-3.7e+02,-0.0014,-0.0059,4.6e-05,0.0021,0.0059,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.7e-05,8.7e-05,0.0025,0.018,0.019,0.0078,0.045,0.045,0.035,6.8e-07,6.8e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24190000,0.7,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.046,-0.014,-3.7e+02,-0.0014,-0.0059,4.6e-05,0.0024,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.6e-05,8.6e-05,0.0025,0.017,0.017,0.0077,0.04,0.04,0.035,6.5e-07,6.4e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24290000,0.7,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.019,-3.7e+02,-0.0014,-0.0059,4.6e-05,0.0024,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.6e-05,8.6e-05,0.0025,0.018,0.018,0.0078,0.045,0.045,0.036,6.5e-07,6.5e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24390000,0.7,0.0039,-0.0059,0.71,-0.13,-0.053,-0.46,-0.064,-0.03,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.002,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.6e-05,8.5e-05,0.0025,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-07,6.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24490000,0.7,0.0047,-0.0017,0.71,-0.14,-0.058,-0.51,-0.077,-0.036,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.002,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.6e-05,8.6e-05,0.0025,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-07,6.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24590000,0.7,0.0052,0.0019,0.71,-0.16,-0.069,-0.56,-0.081,-0.045,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.002,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.5e-05,8.5e-05,0.0025,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-07,5.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24690000,0.7,0.0052,0.0028,0.71,-0.18,-0.083,-0.64,-0.098,-0.053,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.002,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.5e-05,8.5e-05,0.0025,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-07,5.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24790000,0.7,0.0049,0.0014,0.71,-0.2,-0.095,-0.72,-0.1,-0.064,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.0024,0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.4e-05,8.4e-05,0.0025,0.017,0.017,0.0078,0.04,0.04,0.035,5.7e-07,5.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24890000,0.7,0.0067,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.074,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.0024,0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.4e-05,8.4e-05,0.0025,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-07,5.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24990000,0.7,0.0085,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.082,-3.7e+02,-0.0013,-0.0059,4.5e-05,0.0033,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.3e-05,8.4e-05,0.0025,0.016,0.017,0.0078,0.04,0.04,0.035,5.5e-07,5.5e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25090000,0.7,0.0088,0.0041,0.71,-0.27,-0.13,-0.85,-0.15,-0.094,-3.7e+02,-0.0013,-0.0059,4.5e-05,0.0033,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.4e-05,8.4e-05,0.0025,0.018,0.019,0.0079,0.044,0.044,0.035,5.5e-07,5.5e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25190000,0.7,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.0029,0.0014,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.3e-05,8.3e-05,0.0025,0.016,0.017,0.0078,0.04,0.04,0.035,5.3e-07,5.3e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25290000,0.7,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.0029,0.0013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.3e-05,8.3e-05,0.0025,0.017,0.019,0.0079,0.044,0.044,0.035,5.3e-07,5.3e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25390000,0.7,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-0.0012,-0.0059,4.1e-05,0.0032,-0.00021,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.2e-05,8.2e-05,0.0025,0.016,0.017,0.0078,0.04,0.04,0.035,5.1e-07,5.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25490000,0.7,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-0.0012,-0.0059,4.1e-05,0.0032,-0.00019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.3e-05,8.3e-05,0.0025,0.017,0.019,0.0079,0.044,0.044,0.035,5.1e-07,5.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25590000,0.7,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-0.0012,-0.0059,4e-05,0.0029,-0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.1e-05,8.1e-05,0.0024,0.016,0.018,0.0079,0.04,0.04,0.035,4.9e-07,4.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25690000,0.7,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-0.0012,-0.0059,4e-05,0.0029,-0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.2e-05,8.2e-05,0.0024,0.017,0.02,0.0079,0.044,0.044,0.035,4.9e-07,5e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25790000,0.7,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-0.0012,-0.0059,4.2e-05,0.0038,-0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.2e-05,8.1e-05,0.0024,0.016,0.019,0.0079,0.04,0.04,0.035,4.8e-07,4.8e-07,6.3e-06,0.029,0.028,0.0005,0,0,0,0,0,0,0,0 -25890000,0.7,0.017,0.029,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-0.0012,-0.0059,4.2e-05,0.0037,-0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.3e-05,8.2e-05,0.0024,0.017,0.021,0.008,0.044,0.044,0.035,4.8e-07,4.8e-07,6.3e-06,0.029,0.028,0.0005,0,0,0,0,0,0,0,0 -25990000,0.7,0.016,0.025,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-0.0011,-0.0059,4e-05,0.0034,-0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,8.1e-05,8.1e-05,0.0024,0.016,0.02,0.0079,0.04,0.04,0.035,4.6e-07,4.7e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26090000,0.7,0.021,0.035,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-0.0011,-0.0059,4e-05,0.0034,-0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,8.3e-05,8.1e-05,0.0024,0.017,0.022,0.008,0.044,0.044,0.035,4.6e-07,4.7e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26190000,0.7,0.023,0.045,0.71,-0.77,-0.4,-1.3,-0.53,-0.42,-3.7e+02,-0.0011,-0.0059,4.3e-05,0.0045,-0.0093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,8.4e-05,8.1e-05,0.0023,0.016,0.021,0.0079,0.039,0.04,0.035,4.5e-07,4.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26290000,0.7,0.024,0.047,0.71,-0.87,-0.44,-1.3,-0.62,-0.46,-3.7e+02,-0.0011,-0.0059,4.3e-05,0.0045,-0.0093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,8.5e-05,8.1e-05,0.0023,0.017,0.024,0.008,0.043,0.045,0.035,4.5e-07,4.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26390000,0.7,0.023,0.043,0.71,-0.94,-0.5,-1.3,-0.68,-0.55,-3.7e+02,-0.001,-0.0059,4.2e-05,0.0033,-0.011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0023,8.2e-05,8e-05,0.0022,0.016,0.023,0.0079,0.039,0.04,0.035,4.4e-07,4.5e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26490000,0.7,0.031,0.059,0.71,-1,-0.54,-1.3,-0.78,-0.6,-3.7e+02,-0.001,-0.0059,4.2e-05,0.0033,-0.011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0023,8.7e-05,8.1e-05,0.0022,0.018,0.026,0.008,0.043,0.045,0.035,4.4e-07,4.5e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26590000,0.7,0.037,0.075,0.71,-1.1,-0.59,-1.3,-0.82,-0.67,-3.7e+02,-0.00096,-0.0059,5.1e-05,0.0041,-0.015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0022,9.2e-05,8.2e-05,0.0021,0.016,0.026,0.008,0.039,0.041,0.035,4.3e-07,4.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26690000,0.7,0.038,0.078,0.71,-1.3,-0.65,-1.3,-0.94,-0.73,-3.7e+02,-0.00096,-0.0059,5.1e-05,0.0041,-0.015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0022,9.3e-05,8.2e-05,0.0021,0.018,0.031,0.008,0.043,0.045,0.035,4.3e-07,4.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26790000,0.7,0.036,0.072,0.71,-1.4,-0.74,-1.3,-1,-0.86,-3.7e+02,-0.00092,-0.006,3.4e-05,0.0021,-0.017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.002,8.8e-05,8.1e-05,0.002,0.017,0.03,0.008,0.039,0.041,0.035,4.2e-07,4.4e-07,6.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26890000,0.7,0.044,0.094,0.71,-1.5,-0.8,-1.3,-1.2,-0.93,-3.7e+02,-0.00092,-0.006,3.4e-05,0.002,-0.017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.002,9.8e-05,8.3e-05,0.002,0.019,0.036,0.0081,0.043,0.046,0.035,4.2e-07,4.4e-07,6.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26990000,0.7,0.051,0.12,0.7,-1.7,-0.88,-1.3,-1.2,-1,-3.7e+02,-0.0008,-0.006,3.3e-05,0.0029,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0018,0.00011,8.3e-05,0.0018,0.018,0.035,0.008,0.039,0.042,0.035,4.1e-07,4.4e-07,6.2e-06,0.028,0.028,0.0005,0.0025,0.0023,0.0025,0.0025,0.0025,0.0025,0,0 -27090000,0.7,0.052,0.12,0.7,-1.9,-0.97,-1.3,-1.4,-1.1,-3.7e+02,-0.0008,-0.006,3.3e-05,0.0028,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0018,0.00011,8.3e-05,0.0018,0.02,0.043,0.0081,0.043,0.047,0.035,4.1e-07,4.4e-07,6.2e-06,0.028,0.028,0.0005,0.0025,0.0015,0.0025,0.0025,0.0025,0.0025,0,0 -27190000,0.71,0.049,0.11,0.7,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-0.00078,-0.0059,0.00013,0.0027,-0.023,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0016,9.7e-05,8.1e-05,0.0016,0.02,0.044,0.0081,0.046,0.05,0.035,4.1e-07,4.4e-07,6.1e-06,0.028,0.028,0.0005,0.0025,0.0011,0.0025,0.0025,0.0025,0.0025,0,0 -27290000,0.71,0.043,0.094,0.7,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-0.00078,-0.0059,0.00013,0.0027,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0016,9e-05,8e-05,0.0016,0.022,0.051,0.0081,0.051,0.057,0.035,4.1e-07,4.4e-07,6.1e-06,0.028,0.028,0.0005,0.0025,0.0009,0.0025,0.0025,0.0025,0.0025,0,0 -27390000,0.72,0.037,0.077,0.69,-2.4,-1.1,-1.2,-2,-1.4,-3.7e+02,-0.00071,-0.0059,0.00019,0.0035,-0.025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0014,8.2e-05,7.8e-05,0.0014,0.021,0.047,0.0081,0.053,0.059,0.035,4e-07,4.4e-07,6.1e-06,0.028,0.028,0.0005,0.0025,0.00074,0.0025,0.0025,0.0025,0.0025,0,0 -27490000,0.72,0.031,0.062,0.69,-2.4,-1.1,-1.2,-2.3,-1.5,-3.7e+02,-0.00071,-0.0059,0.00019,0.0034,-0.025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0014,8e-05,7.8e-05,0.0014,0.023,0.05,0.0082,0.058,0.067,0.035,4e-07,4.4e-07,6.1e-06,0.028,0.028,0.0005,0.0025,0.00063,0.0025,0.0025,0.0025,0.0025,0,0 -27590000,0.72,0.026,0.05,0.69,-2.5,-1.1,-1.2,-2.5,-1.6,-3.7e+02,-0.00072,-0.0059,0.00026,0.0023,-0.024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.7e-05,7.7e-05,0.0012,0.022,0.044,0.0082,0.061,0.068,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00056,0.0025,0.0025,0.0025,0.0025,0,0 -27690000,0.72,0.026,0.048,0.69,-2.6,-1.2,-1.2,-2.8,-1.7,-3.7e+02,-0.00072,-0.0059,0.00026,0.0022,-0.024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.7e-05,7.7e-05,0.0012,0.023,0.045,0.0082,0.067,0.077,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00049,0.0025,0.0025,0.0025,0.0025,0,0 -27790000,0.72,0.026,0.05,0.69,-2.6,-1.2,-1.2,-3.1,-1.8,-3.7e+02,-0.00071,-0.0059,0.0003,0.0016,-0.024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.7e-05,7.7e-05,0.0011,0.022,0.04,0.0082,0.069,0.078,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00044,0.0025,0.0025,0.0025,0.0025,0,0 -27890000,0.72,0.025,0.048,0.69,-2.6,-1.2,-1.2,-3.3,-1.9,-3.7e+02,-0.00071,-0.0059,0.0003,0.0014,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.7e-05,7.7e-05,0.0011,0.023,0.041,0.0083,0.076,0.087,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.0004,0.0025,0.0025,0.0025,0.0025,0,0 -27990000,0.72,0.024,0.044,0.69,-2.7,-1.2,-1.2,-3.6,-2,-3.7e+02,-0.00074,-0.0059,0.00034,0.00057,-0.022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.001,7.7e-05,7.6e-05,0.001,0.022,0.036,0.0083,0.078,0.087,0.035,3.9e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00037,0.0025,0.0025,0.0025,0.0025,0,0 -28090000,0.72,0.03,0.057,0.69,-2.7,-1.2,-1.2,-3.9,-2.1,-3.7e+02,-0.00074,-0.0059,0.00034,0.00043,-0.022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.001,7.7e-05,7.7e-05,0.001,0.023,0.037,0.0084,0.085,0.097,0.035,3.9e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00034,0.0025,0.0025,0.0025,0.0025,0,0 -28190000,0.72,0.036,0.071,0.68,-2.8,-1.2,-0.95,-4.2,-2.2,-3.7e+02,-0.00076,-0.0059,0.00036,-0.00016,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00093,7.8e-05,7.6e-05,0.00094,0.022,0.034,0.0084,0.087,0.097,0.035,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00032,0.0025,0.0025,0.0025,0.0025,0,0 -28290000,0.73,0.028,0.054,0.68,-2.8,-1.2,-0.089,-4.5,-2.4,-3.7e+02,-0.00076,-0.0059,0.00036,-0.00034,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00093,7.7e-05,7.6e-05,0.00094,0.022,0.034,0.0086,0.094,0.11,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.0003,0.0025,0.0025,0.0025,0.0025,0,0 -28390000,0.73,0.011,0.023,0.68,-2.8,-1.2,0.77,-4.8,-2.5,-3.7e+02,-0.00076,-0.0059,0.00036,-0.00065,-0.019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00093,7.9e-05,7.7e-05,0.00095,0.023,0.035,0.0087,0.1,0.12,0.036,3.9e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00028,0.0025,0.0025,0.0025,0.0025,0,0 -28490000,0.73,0.0015,0.0047,0.68,-2.7,-1.2,1.1,-5,-2.6,-3.7e+02,-0.00075,-0.0059,0.00036,-0.00093,-0.019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00093,8.1e-05,7.7e-05,0.00095,0.024,0.035,0.0088,0.11,0.13,0.036,3.9e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00026,0.0025,0.0025,0.0025,0.0025,0,0 -28590000,0.73,-0.00042,0.0012,0.69,-2.7,-1.2,0.96,-5.3,-2.7,-3.7e+02,-0.00075,-0.0059,0.00036,-0.0013,-0.018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00094,8.2e-05,7.7e-05,0.00095,0.025,0.034,0.0089,0.12,0.14,0.036,3.9e-07,4.5e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00025,0.0025,0.0025,0.0025,0.0025,0,0 -28690000,0.73,-0.0012,0.00035,0.69,-2.6,-1.2,0.96,-5.6,-2.8,-3.7e+02,-0.00075,-0.0059,0.00036,-0.0018,-0.017,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00094,8.3e-05,7.8e-05,0.00095,0.026,0.034,0.009,0.13,0.15,0.036,3.9e-07,4.5e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00023,0.0025,0.0025,0.0025,0.0025,0,0 -28790000,0.73,-0.0016,0.00014,0.68,-2.6,-1.2,0.97,-5.9,-2.9,-3.7e+02,-0.00081,-0.006,0.00039,-0.0027,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00091,8.3e-05,7.8e-05,0.00091,0.025,0.03,0.0089,0.13,0.15,0.036,3.9e-07,4.5e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00022,0.0025,0.0025,0.0025,0.0025,0,0 -28890000,0.73,-0.0016,0.00036,0.69,-2.5,-1.2,0.96,-6.1,-3.1,-3.7e+02,-0.00081,-0.006,0.00039,-0.0032,-0.022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00091,8.3e-05,7.8e-05,0.00091,0.026,0.03,0.009,0.14,0.16,0.036,3.9e-07,4.5e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00021,0.0025,0.0025,0.0025,0.0025,0,0 -28990000,0.73,-0.0015,0.00081,0.68,-2.5,-1.1,0.95,-6.5,-3.2,-3.7e+02,-0.00089,-0.006,0.00041,-0.0027,-0.03,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00089,8.3e-05,7.8e-05,0.00089,0.025,0.027,0.009,0.14,0.16,0.036,3.8e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.0002,0.0025,0.0025,0.0025,0.0025,0,0 -29090000,0.73,-0.0013,0.0012,0.68,-2.4,-1.1,0.94,-6.7,-3.3,-3.7e+02,-0.00089,-0.006,0.00041,-0.0032,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0009,8.3e-05,7.8e-05,0.00089,0.026,0.027,0.009,0.15,0.17,0.036,3.8e-07,4.5e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00019,0.0025,0.0025,0.0025,0.0025,0,0 -29190000,0.73,-0.0011,0.0016,0.68,-2.4,-1.1,0.93,-7,-3.4,-3.7e+02,-0.00093,-0.006,0.00041,-0.0034,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00089,8.3e-05,7.8e-05,0.00089,0.024,0.025,0.009,0.15,0.17,0.036,3.8e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0 -29290000,0.73,-0.00074,0.0025,0.68,-2.3,-1.1,0.96,-7.3,-3.5,-3.7e+02,-0.00093,-0.006,0.00041,-0.004,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00089,8.3e-05,7.8e-05,0.00089,0.026,0.026,0.0091,0.16,0.18,0.036,3.8e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0 -29390000,0.73,-0.00016,0.004,0.68,-2.3,-1.1,0.97,-7.6,-3.6,-3.7e+02,-0.00099,-0.006,0.00041,-0.0035,-0.033,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00089,8.3e-05,7.8e-05,0.00089,0.024,0.025,0.009,0.16,0.18,0.036,3.7e-07,4.4e-07,6e-06,0.028,0.027,0.0005,0.0025,0.00017,0.0025,0.0025,0.0025,0.0025,0,0 -29490000,0.73,0.00037,0.0051,0.68,-2.2,-1.1,0.97,-7.8,-3.7,-3.7e+02,-0.00099,-0.006,0.00041,-0.004,-0.032,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00089,8.3e-05,7.8e-05,0.00089,0.026,0.026,0.0091,0.17,0.19,0.037,3.7e-07,4.4e-07,6e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0 -29590000,0.73,0.00081,0.0062,0.68,-2.2,-1.1,0.96,-8.1,-3.8,-3.7e+02,-0.001,-0.006,0.0004,-0.0051,-0.033,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00089,8.3e-05,7.8e-05,0.00089,0.025,0.025,0.009,0.17,0.19,0.036,3.7e-07,4.3e-07,6e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0 -29690000,0.73,0.0011,0.0068,0.68,-2.2,-1.1,0.95,-8.3,-3.9,-3.7e+02,-0.001,-0.006,0.0004,-0.0056,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0009,8.3e-05,7.8e-05,0.0009,0.026,0.026,0.0091,0.18,0.2,0.036,3.7e-07,4.3e-07,6e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0 -29790000,0.73,0.0015,0.0073,0.68,-2.2,-1.1,0.94,-8.6,-4,-3.7e+02,-0.0011,-0.006,0.00038,-0.0059,-0.033,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0009,8.4e-05,7.8e-05,0.0009,0.025,0.025,0.0091,0.18,0.2,0.037,3.6e-07,4.3e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0 -29890000,0.73,0.0015,0.0075,0.68,-2.1,-1.1,0.92,-8.8,-4.1,-3.7e+02,-0.0011,-0.006,0.00038,-0.0068,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0009,8.4e-05,7.8e-05,0.0009,0.026,0.027,0.0091,0.19,0.21,0.037,3.6e-07,4.3e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0 -29990000,0.73,0.0017,0.0077,0.68,-2.1,-1.1,0.91,-9,-4.2,-3.7e+02,-0.0011,-0.006,0.00035,-0.008,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0009,8.4e-05,7.8e-05,0.0009,0.025,0.026,0.009,0.19,0.21,0.036,3.5e-07,4.2e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0 -30090000,0.73,0.0017,0.0076,0.68,-2.1,-1.1,0.89,-9.2,-4.3,-3.7e+02,-0.0011,-0.006,0.00035,-0.0086,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0009,8.4e-05,7.8e-05,0.0009,0.026,0.028,0.0091,0.2,0.22,0.036,3.6e-07,4.2e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 -30190000,0.73,0.0018,0.0074,0.68,-2,-1.1,0.88,-9.5,-4.4,-3.7e+02,-0.0011,-0.0059,0.00032,-0.0088,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00089,8.4e-05,7.8e-05,0.0009,0.025,0.027,0.009,0.2,0.22,0.037,3.5e-07,4.1e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 -30290000,0.73,0.0017,0.0073,0.68,-2,-1.1,0.87,-9.7,-4.5,-3.7e+02,-0.0011,-0.0059,0.00032,-0.0092,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00089,8.4e-05,7.8e-05,0.0009,0.026,0.029,0.0091,0.21,0.23,0.037,3.5e-07,4.1e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 -30390000,0.73,0.0018,0.0071,0.68,-2,-1.1,0.85,-9.9,-4.6,-3.7e+02,-0.0012,-0.0059,0.00029,-0.0098,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00089,8.4e-05,7.8e-05,0.00089,0.025,0.028,0.009,0.21,0.23,0.036,3.4e-07,4e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0 -30490000,0.73,0.0016,0.0068,0.68,-2,-1.1,0.84,-10,-4.7,-3.7e+02,-0.0012,-0.0059,0.00029,-0.01,-0.028,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00089,8.5e-05,7.8e-05,0.0009,0.026,0.03,0.0091,0.22,0.24,0.037,3.5e-07,4e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0 -30590000,0.73,0.0016,0.0065,0.68,-1.9,-1,0.8,-10,-4.8,-3.7e+02,-0.0012,-0.0059,0.00026,-0.01,-0.028,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00088,8.5e-05,7.8e-05,0.00089,0.025,0.028,0.009,0.22,0.24,0.037,3.4e-07,3.9e-07,5.9e-06,0.027,0.026,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0 -30690000,0.73,0.0015,0.0062,0.68,-1.9,-1,0.79,-11,-4.9,-3.7e+02,-0.0012,-0.0059,0.00026,-0.011,-0.026,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00088,8.5e-05,7.8e-05,0.00089,0.026,0.03,0.009,0.23,0.25,0.037,3.4e-07,3.9e-07,5.9e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 -30790000,0.73,0.0015,0.0058,0.68,-1.9,-1,0.78,-11,-5,-3.7e+02,-0.0012,-0.0059,0.00022,-0.011,-0.026,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00087,8.5e-05,7.7e-05,0.00088,0.025,0.029,0.0089,0.23,0.25,0.037,3.3e-07,3.8e-07,5.9e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 -30890000,0.73,0.0013,0.0053,0.68,-1.9,-1,0.77,-11,-5.1,-3.7e+02,-0.0012,-0.0059,0.00022,-0.011,-0.025,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00087,8.5e-05,7.7e-05,0.00088,0.026,0.031,0.009,0.24,0.26,0.037,3.3e-07,3.8e-07,5.9e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 -30990000,0.73,0.0014,0.0048,0.68,-1.8,-1,0.76,-11,-5.2,-3.7e+02,-0.0013,-0.0059,0.00018,-0.011,-0.025,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00086,8.5e-05,7.7e-05,0.00086,0.025,0.03,0.0089,0.24,0.26,0.036,3.3e-07,3.7e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0 -31090000,0.73,0.0012,0.0043,0.68,-1.8,-1,0.75,-11,-5.3,-3.7e+02,-0.0013,-0.0059,0.00018,-0.012,-0.023,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00086,8.5e-05,7.7e-05,0.00087,0.027,0.032,0.0089,0.25,0.27,0.037,3.3e-07,3.7e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0 -31190000,0.73,0.0012,0.004,0.68,-1.8,-1,0.74,-12,-5.4,-3.7e+02,-0.0013,-0.0058,0.00015,-0.012,-0.021,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00084,8.5e-05,7.7e-05,0.00085,0.025,0.03,0.0088,0.25,0.27,0.037,3.2e-07,3.6e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0 -31290000,0.73,0.00093,0.0035,0.68,-1.8,-0.99,0.74,-12,-5.5,-3.7e+02,-0.0013,-0.0058,0.00015,-0.013,-0.02,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00084,8.5e-05,7.7e-05,0.00085,0.027,0.033,0.0089,0.26,0.28,0.037,3.2e-07,3.6e-07,5.8e-06,0.027,0.026,0.0005,0.0025,9.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 -31390000,0.73,0.00091,0.003,0.69,-1.7,-0.98,0.73,-12,-5.6,-3.7e+02,-0.0013,-0.0058,0.00011,-0.013,-0.018,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00082,8.5e-05,7.6e-05,0.00083,0.025,0.031,0.0088,0.25,0.28,0.036,3.2e-07,3.5e-07,5.8e-06,0.027,0.026,0.0005,0.0025,9.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -31490000,0.73,0.00068,0.0024,0.69,-1.7,-0.98,0.73,-12,-5.7,-3.7e+02,-0.0013,-0.0058,0.00011,-0.013,-0.017,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00082,8.5e-05,7.7e-05,0.00083,0.027,0.033,0.0088,0.27,0.29,0.037,3.2e-07,3.5e-07,5.8e-06,0.027,0.026,0.0005,0.0025,9.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 -31590000,0.73,0.00074,0.002,0.69,-1.7,-0.96,0.72,-12,-5.7,-3.7e+02,-0.0013,-0.0058,7.3e-05,-0.014,-0.015,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.0008,8.5e-05,7.6e-05,0.00081,0.025,0.031,0.0087,0.26,0.29,0.037,3.1e-07,3.4e-07,5.8e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -31690000,0.73,0.00047,0.0013,0.69,-1.7,-0.96,0.73,-12,-5.8,-3.7e+02,-0.0013,-0.0058,7.3e-05,-0.014,-0.014,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.0008,8.5e-05,7.6e-05,0.00081,0.027,0.033,0.0087,0.28,0.3,0.037,3.1e-07,3.4e-07,5.8e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -31790000,0.73,0.00039,0.00063,0.69,-1.6,-0.94,0.73,-13,-5.9,-3.7e+02,-0.0014,-0.0058,3.4e-05,-0.014,-0.012,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.00078,8.5e-05,7.6e-05,0.00079,0.025,0.031,0.0087,0.27,0.3,0.037,3.1e-07,3.3e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -31890000,0.73,0.00012,-5.8e-05,0.69,-1.6,-0.93,0.72,-13,-6,-3.7e+02,-0.0014,-0.0058,3.4e-05,-0.015,-0.011,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.00078,8.5e-05,7.6e-05,0.00079,0.027,0.034,0.0087,0.29,0.31,0.037,3.1e-07,3.3e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -31990000,0.72,9.7e-05,-0.00058,0.69,-1.6,-0.92,0.71,-13,-6.1,-3.7e+02,-0.0014,-0.0058,-9.2e-07,-0.015,-0.0094,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.00076,8.4e-05,7.5e-05,0.00077,0.025,0.032,0.0086,0.28,0.31,0.036,3e-07,3.2e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -32090000,0.72,-0.00021,-0.0013,0.69,-1.5,-0.91,0.72,-13,-6.2,-3.7e+02,-0.0014,-0.0058,-1.4e-06,-0.016,-0.0079,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00076,8.5e-05,7.6e-05,0.00077,0.027,0.034,0.0087,0.3,0.32,0.037,3.1e-07,3.3e-07,5.7e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32190000,0.72,-0.00032,-0.0021,0.69,-1.5,-0.9,0.72,-13,-6.3,-3.7e+02,-0.0014,-0.0058,-3.5e-05,-0.016,-0.0058,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00074,8.4e-05,7.5e-05,0.00075,0.025,0.032,0.0086,0.29,0.32,0.036,3e-07,3.2e-07,5.7e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32290000,0.72,-0.00057,-0.0028,0.69,-1.5,-0.89,0.71,-14,-6.3,-3.7e+02,-0.0014,-0.0058,-3.5e-05,-0.016,-0.0042,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.00074,8.5e-05,7.5e-05,0.00075,0.027,0.034,0.0086,0.3,0.33,0.037,3e-07,3.2e-07,5.7e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32390000,0.72,-0.00067,-0.0035,0.69,-1.5,-0.87,0.71,-14,-6.4,-3.7e+02,-0.0014,-0.0057,-5.8e-05,-0.016,-0.0034,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.00072,8.4e-05,7.5e-05,0.00073,0.025,0.032,0.0085,0.3,0.33,0.037,3e-07,3.1e-07,5.7e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32490000,0.72,-0.0008,-0.0038,0.69,-1.4,-0.86,0.72,-14,-6.5,-3.7e+02,-0.0014,-0.0057,-5.9e-05,-0.017,-0.0022,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00072,8.4e-05,7.5e-05,0.00073,0.027,0.034,0.0085,0.31,0.34,0.037,3e-07,3.1e-07,5.7e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32590000,0.72,-0.0007,-0.004,0.69,-1.4,-0.85,0.72,-14,-6.6,-3.7e+02,-0.0014,-0.0057,-8.1e-05,-0.017,-0.0014,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.0007,8.4e-05,7.5e-05,0.00071,0.025,0.032,0.0084,0.31,0.34,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32690000,0.72,-0.00074,-0.0041,0.69,-1.4,-0.84,0.71,-14,-6.7,-3.7e+02,-0.0014,-0.0057,-8.1e-05,-0.017,-0.00081,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.0007,8.4e-05,7.5e-05,0.00071,0.027,0.034,0.0085,0.32,0.35,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32790000,0.72,-0.00061,-0.0041,0.69,-1.3,-0.83,0.71,-14,-6.7,-3.7e+02,-0.0014,-0.0057,-0.0001,-0.017,0.00012,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00068,8.3e-05,7.4e-05,0.00069,0.025,0.032,0.0084,0.32,0.35,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32890000,0.72,-0.00053,-0.004,0.69,-1.3,-0.82,0.71,-14,-6.8,-3.7e+02,-0.0014,-0.0057,-0.0001,-0.017,0.0013,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00068,8.4e-05,7.4e-05,0.00069,0.027,0.033,0.0084,0.33,0.36,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32990000,0.72,-0.0003,-0.004,0.69,-1.3,-0.81,0.7,-15,-6.9,-3.7e+02,-0.0014,-0.0057,-0.00012,-0.017,0.0026,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00066,8.3e-05,7.4e-05,0.00067,0.025,0.031,0.0083,0.33,0.36,0.036,2.9e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -33090000,0.72,-0.00034,-0.004,0.69,-1.3,-0.8,0.7,-15,-7,-3.7e+02,-0.0014,-0.0057,-0.00012,-0.018,0.0032,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00066,8.3e-05,7.4e-05,0.00067,0.026,0.033,0.0084,0.34,0.37,0.036,2.9e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -33190000,0.72,0.0032,-0.0032,0.7,-1.2,-0.78,0.64,-15,-7,-3.7e+02,-0.0015,-0.0057,-0.00014,-0.018,0.0039,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00065,8.2e-05,7.4e-05,0.00064,0.025,0.031,0.0083,0.34,0.37,0.036,2.8e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -33290000,0.67,0.015,-0.0025,0.75,-1.2,-0.77,0.62,-15,-7.1,-3.7e+02,-0.0015,-0.0057,-0.00014,-0.018,0.0043,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00075,8.2e-05,7.4e-05,0.00055,0.026,0.033,0.0083,0.35,0.38,0.036,2.8e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0.0025,9.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33390000,0.56,0.013,-0.0027,0.83,-1.2,-0.75,0.81,-15,-7.2,-3.7e+02,-0.0015,-0.0057,-0.00015,-0.018,0.0053,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00089,8e-05,7.5e-05,0.00038,0.025,0.03,0.0082,0.35,0.38,0.036,2.8e-07,2.8e-07,5.6e-06,0.027,0.025,0.0005,0.0025,9e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33490000,0.43,0.0066,-0.00011,0.9,-1.2,-0.75,0.83,-15,-7.3,-3.7e+02,-0.0015,-0.0057,-0.00015,-0.018,0.0054,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.7e-05,0.00022,0.026,0.032,0.0081,0.36,0.39,0.036,2.8e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0.0025,8.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33590000,0.27,0.0006,-0.0025,0.96,-1.2,-0.74,0.79,-15,-7.3,-3.7e+02,-0.0015,-0.0057,-0.00017,-0.018,0.0054,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.7e-05,7.9e-05,8.1e-05,0.026,0.031,0.0078,0.35,0.39,0.036,2.8e-07,2.8e-07,5.6e-06,0.027,0.025,0.0005,0.0025,8.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33690000,0.1,-0.0028,-0.0055,0.99,-1.1,-0.74,0.8,-15,-7.4,-3.7e+02,-0.0015,-0.0057,-0.00017,-0.018,0.0054,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.5e-05,8.1e-05,9.7e-06,0.028,0.034,0.0076,0.37,0.4,0.036,2.8e-07,2.8e-07,5.6e-06,0.027,0.025,0.0005,0.0025,8.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33790000,-0.068,-0.0044,-0.0073,1,-1.1,-0.72,0.78,-16,-7.5,-3.7e+02,-0.0015,-0.0057,-0.00019,-0.018,0.0054,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.3e-05,8e-05,8.1e-06,0.028,0.034,0.0074,0.36,0.4,0.036,2.7e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33890000,-0.24,-0.0057,-0.008,0.97,-1,-0.7,0.77,-16,-7.5,-3.7e+02,-0.0015,-0.0057,-0.00019,-0.018,0.0054,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.2e-05,8.2e-05,7.6e-05,0.032,0.039,0.0072,0.38,0.41,0.036,2.8e-07,2.8e-07,5.6e-06,0.027,0.025,0.0005,0.0025,8.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33990000,-0.38,-0.0039,-0.012,0.92,-0.96,-0.65,0.74,-16,-7.6,-3.7e+02,-0.0015,-0.0057,-0.00022,-0.018,0.0054,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.001,6.9e-05,7.8e-05,0.00019,0.032,0.038,0.007,0.37,0.41,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34090000,-0.49,-0.003,-0.013,0.87,-0.91,-0.61,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00022,-0.018,0.0054,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0009,6.9e-05,7.8e-05,0.0003,0.037,0.044,0.0069,0.39,0.42,0.036,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34190000,-0.56,-0.0023,-0.012,0.83,-0.89,-0.56,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00023,-0.021,0.0076,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00079,6.5e-05,7.3e-05,0.00038,0.037,0.043,0.0067,0.38,0.42,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34290000,-0.6,-0.0032,-0.0091,0.8,-0.84,-0.51,0.74,-16,-7.8,-3.7e+02,-0.0015,-0.0057,-0.00023,-0.021,0.0076,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00074,6.5e-05,7.2e-05,0.00044,0.043,0.049,0.0066,0.39,0.43,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34390000,-0.63,-0.0033,-0.0067,0.78,-0.83,-0.47,0.74,-16,-7.9,-3.7e+02,-0.0016,-0.0057,-0.00025,-0.026,0.013,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00068,6.1e-05,6.6e-05,0.00047,0.042,0.048,0.0065,0.39,0.43,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34490000,-0.65,-0.0042,-0.0045,0.76,-0.77,-0.42,0.74,-16,-7.9,-3.7e+02,-0.0016,-0.0057,-0.00025,-0.026,0.013,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00066,6.1e-05,6.6e-05,0.00049,0.049,0.055,0.0064,0.4,0.44,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34590000,-0.66,-0.0035,-0.0035,0.75,-0.78,-0.4,0.73,-17,-8,-3.7e+02,-0.0016,-0.0057,-0.00026,-0.036,0.022,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00063,5.6e-05,6e-05,0.0005,0.048,0.052,0.0063,0.4,0.44,0.034,2.7e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,7.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34690000,-0.66,-0.0039,-0.0027,0.75,-0.72,-0.36,0.73,-17,-8,-3.7e+02,-0.0016,-0.0057,-0.00026,-0.036,0.022,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00062,5.6e-05,6e-05,0.00051,0.055,0.06,0.0063,0.41,0.45,0.034,2.7e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,7.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34790000,-0.67,-0.0027,-0.0025,0.75,-0.73,-0.35,0.72,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00026,-0.047,0.033,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00061,5.1e-05,5.5e-05,0.0005,0.052,0.056,0.0062,0.41,0.45,0.034,2.6e-07,2.7e-07,5.5e-06,0.025,0.024,0.0005,0.0025,7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34890000,-0.67,-0.0028,-0.0024,0.74,-0.68,-0.31,0.72,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00026,-0.047,0.033,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00061,5.1e-05,5.5e-05,0.00051,0.059,0.064,0.0062,0.42,0.46,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.024,0.0005,0.0025,6.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34990000,-0.67,-0.009,-0.0051,0.74,0.34,0.28,-0.13,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00027,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0006,4.7e-05,5e-05,0.00051,0.06,0.07,0.0068,0.42,0.45,0.034,2.6e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35090000,-0.67,-0.0091,-0.0051,0.74,0.47,0.3,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00027,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0006,4.7e-05,5e-05,0.00051,0.065,0.077,0.0068,0.43,0.46,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35190000,-0.67,-0.0091,-0.0052,0.74,0.49,0.33,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00027,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0006,4.7e-05,5e-05,0.00051,0.07,0.082,0.0067,0.44,0.47,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35290000,-0.67,-0.0091,-0.0052,0.74,0.51,0.37,-0.18,-17,-8,-3.7e+02,-0.0017,-0.0057,-0.00027,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0006,4.7e-05,5e-05,0.00051,0.076,0.087,0.0066,0.46,0.48,0.033,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35390000,-0.67,-0.0092,-0.0052,0.74,0.54,0.4,-0.18,-17,-8,-3.7e+02,-0.0017,-0.0057,-0.00027,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0006,4.7e-05,5e-05,0.00051,0.082,0.094,0.0066,0.47,0.49,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35490000,-0.67,-0.0092,-0.0052,0.74,0.56,0.44,-0.18,-17,-8,-3.7e+02,-0.0017,-0.0057,-0.00027,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0006,4.6e-05,5e-05,0.00052,0.088,0.1,0.0065,0.49,0.51,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35590000,-0.67,-0.0061,-0.0053,0.74,0.45,0.36,-0.19,-17,-8,-3.7e+02,-0.0017,-0.0057,-0.00025,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00057,3.9e-05,4.3e-05,0.00049,0.07,0.076,0.0062,0.48,0.5,0.033,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35690000,-0.67,-0.0061,-0.0053,0.74,0.46,0.39,-0.19,-17,-8,-3.7e+02,-0.0017,-0.0057,-0.00025,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00057,3.9e-05,4.3e-05,0.00049,0.075,0.081,0.0062,0.5,0.52,0.033,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35790000,-0.67,-0.0038,-0.0053,0.74,0.38,0.33,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00023,-0.064,0.05,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00056,3.4e-05,3.8e-05,0.00048,0.062,0.066,0.0059,0.49,0.51,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35890000,-0.67,-0.0038,-0.0053,0.74,0.4,0.36,-0.19,-17,-8,-3.7e+02,-0.0017,-0.0057,-0.00023,-0.064,0.05,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00056,3.4e-05,3.8e-05,0.00048,0.067,0.071,0.0059,0.5,0.53,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35990000,-0.67,-0.0018,-0.0053,0.74,0.33,0.31,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00023,-0.072,0.056,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00055,3e-05,3.4e-05,0.00047,0.058,0.06,0.0057,0.5,0.52,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36090000,-0.67,-0.0019,-0.0052,0.74,0.34,0.33,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00023,-0.072,0.057,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00056,3e-05,3.4e-05,0.00047,0.063,0.066,0.0057,0.51,0.53,0.032,2.7e-07,2.8e-07,5.4e-06,0.025,0.023,0.0005,0.0025,5.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36190000,-0.67,-0.00042,-0.0051,0.74,0.28,0.28,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00022,-0.083,0.066,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00055,2.7e-05,3.1e-05,0.00047,0.055,0.057,0.0056,0.5,0.53,0.032,2.7e-07,2.8e-07,5.4e-06,0.024,0.023,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36290000,-0.67,-0.00055,-0.0051,0.74,0.29,0.31,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00022,-0.083,0.066,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00055,2.7e-05,3.2e-05,0.00047,0.061,0.063,0.0056,0.52,0.54,0.032,2.8e-07,2.8e-07,5.4e-06,0.024,0.023,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36390000,-0.67,0.00057,-0.0049,0.74,0.24,0.26,-0.18,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.00022,-0.096,0.076,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00055,2.4e-05,2.9e-05,0.00047,0.054,0.055,0.0055,0.51,0.54,0.032,2.8e-07,2.8e-07,5.4e-06,0.024,0.022,0.0005,0.0025,5.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36490000,-0.67,0.00047,-0.0049,0.74,0.25,0.28,-0.18,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.00022,-0.097,0.076,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00056,2.4e-05,2.9e-05,0.00047,0.059,0.061,0.0055,0.53,0.55,0.032,2.8e-07,2.8e-07,5.4e-06,0.024,0.022,0.0005,0.0025,5.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36590000,-0.67,0.0013,-0.0047,0.74,0.21,0.24,-0.18,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.00022,-0.11,0.086,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00056,2.2e-05,2.7e-05,0.00047,0.053,0.054,0.0055,0.52,0.55,0.031,2.8e-07,2.8e-07,5.4e-06,0.023,0.022,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36690000,-0.67,0.0013,-0.0047,0.74,0.21,0.26,-0.17,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.00022,-0.11,0.086,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00056,2.2e-05,2.7e-05,0.00047,0.058,0.06,0.0055,0.54,0.56,0.031,2.8e-07,2.8e-07,5.4e-06,0.023,0.022,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36790000,-0.67,0.0019,-0.0045,0.74,0.18,0.22,-0.17,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00022,-0.12,0.095,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00056,2.1e-05,2.6e-05,0.00048,0.052,0.053,0.0055,0.53,0.56,0.031,2.8e-07,2.8e-07,5.4e-06,0.022,0.021,0.0005,0.0025,5.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36890000,-0.67,0.0018,-0.0045,0.74,0.18,0.24,-0.16,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.00022,-0.12,0.096,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00056,2.1e-05,2.6e-05,0.00048,0.057,0.059,0.0056,0.55,0.57,0.031,2.8e-07,2.8e-07,5.4e-06,0.022,0.021,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36990000,-0.67,0.0023,-0.0043,0.74,0.15,0.2,-0.16,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00023,-0.14,0.1,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00056,2e-05,2.5e-05,0.00048,0.051,0.052,0.0056,0.54,0.57,0.031,2.8e-07,2.8e-07,5.4e-06,0.021,0.02,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37090000,-0.67,0.0023,-0.0042,0.74,0.15,0.21,-0.15,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.00023,-0.14,0.1,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00056,2e-05,2.5e-05,0.00048,0.056,0.058,0.0057,0.55,0.58,0.031,2.8e-07,2.9e-07,5.4e-06,0.021,0.02,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37190000,-0.67,0.0026,-0.0041,0.74,0.12,0.18,-0.14,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00023,-0.15,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00057,1.9e-05,2.4e-05,0.00048,0.05,0.052,0.0057,0.55,0.58,0.031,2.8e-07,2.9e-07,5.4e-06,0.021,0.019,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37290000,-0.67,0.0026,-0.0041,0.74,0.12,0.19,-0.14,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.00023,-0.15,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00057,1.9e-05,2.4e-05,0.00048,0.055,0.057,0.0059,0.56,0.59,0.031,2.8e-07,2.9e-07,5.4e-06,0.021,0.019,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37390000,-0.67,0.0028,-0.0039,0.74,0.1,0.16,-0.13,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00024,-0.16,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00057,1.8e-05,2.3e-05,0.00048,0.05,0.051,0.0059,0.56,0.59,0.031,2.9e-07,2.9e-07,5.4e-06,0.02,0.018,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37490000,-0.67,0.0028,-0.0038,0.74,0.099,0.17,-0.13,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.00024,-0.16,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00057,1.8e-05,2.3e-05,0.00049,0.054,0.056,0.006,0.57,0.6,0.031,2.9e-07,2.9e-07,5.4e-06,0.02,0.018,0.0005,0.0025,4.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37590000,-0.67,0.003,-0.0037,0.74,0.079,0.14,-0.12,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00024,-0.17,0.12,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.00057,1.8e-05,2.3e-05,0.00049,0.049,0.05,0.0061,0.57,0.6,0.031,2.9e-07,2.9e-07,5.4e-06,0.019,0.018,0.0005,0.0025,4.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37690000,-0.67,0.0029,-0.0037,0.74,0.077,0.15,-0.11,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00024,-0.17,0.12,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.00057,1.8e-05,2.3e-05,0.00049,0.053,0.055,0.0062,0.58,0.61,0.031,2.9e-07,2.9e-07,5.4e-06,0.019,0.018,0.0005,0.0025,4.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37790000,-0.67,0.003,-0.0036,0.74,0.061,0.13,-0.1,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00025,-0.18,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00057,1.8e-05,2.2e-05,0.00049,0.048,0.049,0.0063,0.58,0.61,0.03,2.9e-07,2.9e-07,5.4e-06,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37890000,-0.67,0.003,-0.0036,0.74,0.058,0.13,-0.094,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00025,-0.18,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00057,1.8e-05,2.2e-05,0.00049,0.052,0.053,0.0064,0.59,0.62,0.03,2.9e-07,2.9e-07,5.4e-06,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37990000,-0.67,0.0031,-0.0036,0.74,0.044,0.11,-0.085,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00026,-0.19,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00058,1.7e-05,2.2e-05,0.00049,0.047,0.048,0.0065,0.59,0.62,0.031,2.9e-07,2.9e-07,5.4e-06,0.017,0.016,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38090000,-0.67,0.003,-0.0035,0.74,0.04,0.12,-0.075,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00026,-0.19,0.13,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.00058,1.8e-05,2.2e-05,0.00049,0.051,0.052,0.0066,0.6,0.63,0.031,2.9e-07,3e-07,5.4e-06,0.017,0.016,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38190000,-0.67,0.0031,-0.0034,0.74,0.027,0.1,-0.067,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00026,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.00058,1.7e-05,2.2e-05,0.00049,0.045,0.047,0.0067,0.6,0.63,0.031,2.9e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38290000,-0.67,0.0031,-0.0034,0.74,0.023,0.1,-0.06,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00026,-0.2,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.00058,1.8e-05,2.2e-05,0.00049,0.049,0.051,0.0068,0.61,0.64,0.031,2.9e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38390000,-0.67,0.0031,-0.0033,0.74,0.015,0.087,-0.052,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00027,-0.2,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.00058,1.7e-05,2.2e-05,0.00049,0.044,0.046,0.0069,0.61,0.64,0.031,2.9e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38490000,-0.67,0.0031,-0.0033,0.74,0.012,0.089,-0.045,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00027,-0.2,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.00058,1.8e-05,2.2e-05,0.00049,0.048,0.049,0.007,0.62,0.65,0.031,3e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38590000,-0.67,0.0031,-0.0031,0.74,0.0071,0.076,-0.038,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00027,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.00058,1.8e-05,2.2e-05,0.00049,0.043,0.044,0.0071,0.62,0.65,0.031,3e-07,3e-07,5.4e-06,0.015,0.014,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38690000,-0.67,0.003,-0.0031,0.74,0.0029,0.076,-0.031,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00027,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.00058,1.8e-05,2.2e-05,0.00049,0.046,0.048,0.0072,0.63,0.66,0.031,3e-07,3e-07,5.4e-06,0.015,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38790000,-0.67,0.003,-0.0031,0.74,-0.0023,0.063,-0.023,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00028,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.00058,1.8e-05,2.2e-05,0.00049,0.042,0.043,0.0073,0.63,0.66,0.031,3e-07,3e-07,5.4e-06,0.014,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38890000,-0.67,0.0028,-0.0031,0.74,-0.012,0.052,0.48,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00028,-0.21,0.14,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00058,1.8e-05,2.2e-05,0.0005,0.045,0.046,0.0075,0.64,0.67,0.032,3e-07,3e-07,5.4e-06,0.014,0.014,0.0005,0.0025,4.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 +10000,1,-0.0094,-0.01,-3.2e-06,0.00023,7.3e-05,-0.011,7.1e-06,2.2e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00018,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +90000,1,-0.0094,-0.011,6.9e-05,-0.00047,0.0026,-0.026,-1.6e-05,0.00011,-0.0023,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00046,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +190000,1,-0.0094,-0.011,2.9e-05,6.9e-05,0.0039,-0.041,-5.9e-06,0.00043,-0.0044,-3e-11,-2.7e-12,5.9e-13,0,0,-2e-09,0,0,0,0,0,0,0,0,0.011,0.011,0.00093,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +290000,1,-0.0094,-0.011,6.4e-05,0.001,0.0064,-0.053,3.8e-05,0.00036,-0.007,9.1e-10,1e-10,-2.8e-11,0,0,-4.8e-07,0,0,0,0,0,0,0,0,0.012,0.011,0.00077,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +390000,1,-0.0095,-0.011,7.2e-05,0.0024,0.0083,-0.059,0.00021,0.0011,-0.0094,-1.1e-08,2.8e-09,7.6e-11,0,0,-4.5e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +490000,1,-0.0095,-0.012,2.2e-05,0.0039,0.0048,-0.06,0.00024,0.00048,-0.011,1.6e-06,-3.7e-07,1.4e-08,0,0,-1.6e-05,0,0,0,0,0,0,0,0,0.013,0.013,0.00073,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +590000,1,-0.0095,-0.012,2.9e-05,0.006,0.0073,-0.059,0.00074,0.0011,-0.012,1.6e-06,-3.4e-07,1.4e-08,0,0,-3.4e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.001,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +690000,1,-0.0097,-0.012,8.9e-05,0.0063,0.0051,-0.06,0.0005,0.00054,-0.013,5.5e-06,-3.2e-06,1.2e-07,0,0,-6.3e-05,0,0,0,0,0,0,0,0,0.016,0.016,0.00062,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +790000,1,-0.0098,-0.013,0.0001,0.0086,0.0072,-0.063,0.0012,0.0011,-0.014,5.4e-06,-3.1e-06,1.1e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,0.018,0.018,0.00079,2.8,2.8,2,0.42,0.42,0.28,0.01,0.01,0.0012,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +890000,1,-0.0099,-0.013,0.00012,0.01,0.0059,-0.077,0.00096,0.00071,-0.021,1.6e-05,-1.5e-05,3.4e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,0.019,0.019,0.00053,1.3,1.3,2,0.2,0.2,0.43,0.0099,0.01,0.00068,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +990000,1,-0.0099,-0.013,0.00013,0.015,0.0062,-0.092,0.0022,0.0013,-0.029,1.6e-05,-1.5e-05,3.4e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,0.021,0.021,0.00065,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.00068,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1090000,1,-0.01,-0.014,0.00013,0.016,0.0048,-0.11,0.0018,0.00084,-0.039,4.1e-05,-6.2e-05,9.6e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,0.023,0.023,0.00046,0.92,0.92,2,0.17,0.17,0.84,0.0098,0.0098,0.00042,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1190000,1,-0.01,-0.014,0.0001,0.02,0.005,-0.12,0.0035,0.0013,-0.051,4.1e-05,-6.2e-05,9.6e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,0.025,0.025,0.00054,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00042,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1290000,1,-0.01,-0.014,0.00016,0.02,0.0041,-0.14,0.0027,0.00085,-0.064,8.2e-05,-0.00019,2.3e-06,0,0,-9.6e-05,0,0,0,0,0,0,0,0,0.026,0.026,0.00041,0.88,0.88,2,0.15,0.15,1.4,0.0095,0.0095,0.00028,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1390000,1,-0.01,-0.014,0.00017,0.026,0.0038,-0.15,0.0051,0.0013,-0.078,8.2e-05,-0.00019,2.3e-06,0,0,-9.6e-05,0,0,0,0,0,0,0,0,0.028,0.028,0.00047,1.1,1.1,2,0.21,0.21,1.7,0.0095,0.0095,0.00028,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1490000,1,-0.01,-0.014,0.00015,0.024,0.0026,-0.16,0.0038,0.00078,-0.093,0.00014,-0.00046,4.7e-06,0,0,-9.8e-05,0,0,0,0,0,0,0,0,0.027,0.027,0.00036,0.95,0.95,2,0.14,0.14,2.1,0.0088,0.0088,0.0002,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1590000,1,-0.011,-0.014,0.00014,0.031,0.003,-0.18,0.0065,0.0011,-0.11,0.00014,-0.00046,4.7e-06,0,0,-9.8e-05,0,0,0,0,0,0,0,0,0.03,0.03,0.00042,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.0002,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1690000,1,-0.011,-0.014,0.00011,0.028,-0.00047,-0.19,0.0045,0.00057,-0.13,0.00019,-0.00088,8.1e-06,0,0,-0.0001,0,0,0,0,0,0,0,0,0.025,0.025,0.00033,1,1,2,0.14,0.14,3,0.0078,0.0078,0.00015,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1790000,1,-0.011,-0.014,7.5e-05,0.035,-0.0024,-0.2,0.0076,0.00044,-0.15,0.00019,-0.00088,8.1e-06,0,0,-0.0001,0,0,0,0,0,0,0,0,0.028,0.028,0.00037,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.00015,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1890000,1,-0.011,-0.015,5.5e-05,0.043,-0.0037,-0.22,0.011,0.00014,-0.17,0.00019,-0.00088,8.1e-06,0,0,-0.0001,0,0,0,0,0,0,0,0,0.031,0.031,0.00042,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.00015,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1990000,1,-0.011,-0.014,4.7e-05,0.036,-0.0051,-0.23,0.0082,-0.00038,-0.19,0.0002,-0.0014,1.3e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.024,0.024,0.00033,1.3,1.3,2,0.2,0.2,4.7,0.0066,0.0066,0.00011,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2090000,1,-0.011,-0.014,6.8e-06,0.041,-0.0077,-0.24,0.012,-0.001,-0.22,0.0002,-0.0014,1.3e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.026,0.026,0.00037,1.7,1.7,2.1,0.31,0.31,5.3,0.0066,0.0066,0.00011,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2190000,1,-0.011,-0.014,-1.3e-06,0.033,-0.0072,-0.26,0.0079,-0.0011,-0.24,0.00015,-0.002,1.8e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.02,0.02,0.0003,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,8.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2290000,1,-0.011,-0.014,-1.7e-05,0.039,-0.0098,-0.27,0.011,-0.0019,-0.27,0.00015,-0.002,1.8e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.022,0.022,0.00033,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,8.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2390000,1,-0.011,-0.013,-1.9e-05,0.03,-0.009,-0.29,0.0074,-0.0016,-0.3,5.8e-05,-0.0025,2.2e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.016,0.016,0.00027,1,1,2.1,0.19,0.19,7.4,0.0045,0.0045,7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2490000,1,-0.011,-0.013,-4e-05,0.034,-0.011,-0.3,0.011,-0.0025,-0.32,5.8e-05,-0.0025,2.2e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.017,0.017,0.0003,1.3,1.3,2.1,0.28,0.28,8.2,0.0045,0.0045,7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2590000,1,-0.011,-0.013,-4.3e-05,0.026,-0.0093,-0.31,0.0068,-0.0018,-0.36,-5.2e-05,-0.003,2.6e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.013,0.013,0.00025,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,5.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2690000,1,-0.011,-0.013,-5e-05,0.03,-0.011,-0.33,0.0096,-0.0029,-0.39,-5.2e-05,-0.003,2.6e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.014,0.014,0.00027,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,5.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2790000,1,-0.011,-0.013,-7.1e-05,0.023,-0.0096,-0.34,0.0061,-0.002,-0.42,-0.00017,-0.0033,2.8e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.011,0.011,0.00023,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,4.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2890000,1,-0.011,-0.013,-0.00013,0.027,-0.011,-0.35,0.0086,-0.003,-0.46,-0.00017,-0.0033,2.8e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.012,0.012,0.00025,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,4.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2990000,1,-0.011,-0.013,-9.1e-05,0.022,-0.0097,-0.36,0.0056,-0.0021,-0.49,-0.00028,-0.0036,3.1e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.009,0.009,0.00021,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,3.9e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3090000,1,-0.011,-0.013,-9.2e-05,0.024,-0.011,-0.38,0.0079,-0.0032,-0.53,-0.00028,-0.0036,3.1e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.01,0.0099,0.00023,0.82,0.82,2.2,0.22,0.22,14,0.0027,0.0027,3.9e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3190000,1,-0.011,-0.013,-0.00016,0.019,-0.0088,-0.39,0.0052,-0.0022,-0.57,-0.00039,-0.0039,3.3e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.0078,0.0078,0.0002,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,3.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3290000,1,-0.011,-0.013,-0.00013,0.023,-0.011,-0.4,0.0073,-0.0031,-0.61,-0.00039,-0.0039,3.3e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00022,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,3.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3390000,1,-0.011,-0.012,-0.00017,0.018,-0.0094,-0.42,0.0049,-0.0022,-0.65,-0.00049,-0.0041,3.4e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00019,0.53,0.53,2.3,0.14,0.14,17,0.0019,0.0019,2.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3490000,1,-0.011,-0.013,-0.00018,0.021,-0.012,-0.43,0.0068,-0.0032,-0.69,-0.00049,-0.0041,3.4e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.0076,0.0076,0.0002,0.65,0.65,2.3,0.19,0.19,19,0.0019,0.0019,2.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3590000,1,-0.011,-0.012,-0.00017,0.016,-0.011,-0.44,0.0046,-0.0023,-0.73,-0.0006,-0.0044,3.6e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0061,0.0061,0.00018,0.48,0.48,2.4,0.13,0.13,20,0.0016,0.0016,2.4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3690000,1,-0.011,-0.012,-4.8e-05,0.019,-0.014,-0.46,0.0064,-0.0036,-0.78,-0.0006,-0.0044,3.6e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0068,0.0067,0.00019,0.59,0.59,2.4,0.18,0.18,21,0.0016,0.0016,2.4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3790000,1,-0.011,-0.012,-1.3e-05,0.015,-0.014,-0.47,0.0043,-0.0026,-0.83,-0.00072,-0.0045,3.8e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0055,0.0055,0.00017,0.44,0.45,2.4,0.12,0.12,23,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3890000,1,-0.011,-0.012,-5.1e-05,0.017,-0.015,-0.48,0.0059,-0.004,-0.87,-0.00072,-0.0045,3.8e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.006,0.006,0.00018,0.54,0.54,2.4,0.17,0.17,24,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3990000,1,-0.011,-0.012,-5.2e-05,0.02,-0.016,-0.5,0.0078,-0.0056,-0.92,-0.00072,-0.0045,3.8e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0066,0.0066,0.00019,0.66,0.66,2.5,0.22,0.23,26,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4090000,1,-0.011,-0.012,-6.7e-05,0.017,-0.014,-0.51,0.0056,-0.0042,-0.97,-0.00084,-0.0047,4e-05,0,0,-9.6e-05,0,0,0,0,0,0,0,0,0.0054,0.0053,0.00017,0.5,0.5,2.5,0.16,0.16,27,0.0012,0.0011,1.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4190000,1,-0.011,-0.012,-9.6e-05,0.02,-0.017,-0.53,0.0075,-0.0057,-1,-0.00084,-0.0047,4e-05,0,0,-9.6e-05,0,0,0,0,0,0,0,0,0.0058,0.0058,0.00018,0.6,0.61,2.5,0.21,0.21,29,0.0012,0.0011,1.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4290000,1,-0.01,-0.012,-0.00015,0.017,-0.012,-0.54,0.0054,-0.0042,-1.1,-0.00097,-0.0049,4.2e-05,0,0,-9.1e-05,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.46,0.46,2.6,0.15,0.15,31,0.00095,0.00095,1.6e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4390000,1,-0.01,-0.012,-0.00014,0.018,-0.013,-0.55,0.0072,-0.0055,-1.1,-0.00097,-0.0049,4.2e-05,0,0,-9.1e-05,0,0,0,0,0,0,0,0,0.0052,0.0051,0.00017,0.56,0.56,2.6,0.2,0.2,33,0.00095,0.00095,1.6e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4490000,1,-0.01,-0.012,-8.5e-05,0.015,-0.01,-0.57,0.0051,-0.0038,-1.2,-0.0011,-0.005,4.3e-05,0,0,-8.7e-05,0,0,0,0,0,0,0,0,0.0042,0.0042,0.00015,0.43,0.43,2.6,0.14,0.14,34,0.00078,0.00078,1.4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4590000,1,-0.01,-0.012,-6e-05,0.018,-0.012,-0.58,0.0068,-0.0049,-1.2,-0.0011,-0.005,4.3e-05,0,0,-8.7e-05,0,0,0,0,0,0,0,0,0.0045,0.0045,0.00016,0.51,0.51,2.7,0.19,0.19,36,0.00078,0.00078,1.4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4690000,1,-0.01,-0.012,-6.7e-05,0.014,-0.01,-0.6,0.0049,-0.0034,-1.3,-0.0012,-0.0052,4.5e-05,0,0,-8.2e-05,0,0,0,0,0,0,0,0,0.0037,0.0036,0.00015,0.39,0.39,2.7,0.14,0.14,38,0.00064,0.00064,1.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4790000,1,-0.01,-0.012,-8.2e-05,0.016,-0.012,-0.61,0.0064,-0.0045,-1.4,-0.0012,-0.0052,4.5e-05,0,0,-8.2e-05,0,0,0,0,0,0,0,0,0.004,0.0039,0.00015,0.47,0.47,2.7,0.18,0.18,40,0.00064,0.00064,1.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4890000,1,-0.01,-0.012,-0.0001,0.013,-0.01,-0.63,0.0046,-0.0033,-1.4,-0.0013,-0.0053,4.6e-05,0,0,-7.7e-05,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,2.8,0.13,0.13,42,0.00052,0.00052,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4990000,1,-0.01,-0.012,-0.00013,0.015,-0.011,-0.64,0.006,-0.0043,-1.5,-0.0013,-0.0053,4.6e-05,0,0,-7.7e-05,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00015,0.43,0.43,2.8,0.17,0.17,44,0.00052,0.00052,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5090000,1,-0.01,-0.011,-9.3e-05,0.012,-0.0086,-0.66,0.0043,-0.0031,-1.6,-0.0013,-0.0054,4.7e-05,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,2.8,0.12,0.12,46,0.00042,0.00042,1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5190000,1,-0.01,-0.011,-7.2e-05,0.013,-0.01,-0.67,0.0056,-0.004,-1.6,-0.0013,-0.0054,4.7e-05,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.003,0.003,0.00014,0.39,0.39,2.9,0.16,0.16,49,0.00042,0.00042,1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5290000,1,-0.01,-0.011,-9.1e-05,0.0093,-0.0074,-0.68,0.0039,-0.0029,-1.7,-0.0014,-0.0055,4.8e-05,0,0,-6.9e-05,0,0,0,0,0,0,0,0,0.0024,0.0024,0.00013,0.3,0.3,2.9,0.12,0.12,51,0.00034,0.00034,9.2e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5390000,1,-0.0099,-0.011,-3.8e-05,0.0089,-0.0083,-0.7,0.0048,-0.0037,-1.8,-0.0014,-0.0055,4.8e-05,0,0,-6.9e-05,0,0,0,0,0,0,0,0,0.0026,0.0026,0.00014,0.36,0.36,2.9,0.16,0.16,53,0.00034,0.00034,9.2e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5490000,1,-0.0098,-0.011,-3.4e-05,0.0062,-0.0064,-0.71,0.0033,-0.0026,-1.8,-0.0014,-0.0055,4.9e-05,0,0,-6.6e-05,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.28,0.28,3,0.11,0.11,56,0.00028,0.00027,8.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5590000,1,-0.0098,-0.011,-6e-05,0.0069,-0.0068,-0.73,0.0039,-0.0032,-1.9,-0.0014,-0.0055,4.9e-05,0,0,-6.6e-05,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00013,0.33,0.33,3,0.15,0.15,58,0.00028,0.00027,8.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5690000,1,-0.0096,-0.011,5.9e-06,0.0049,-0.004,-0.74,0.0027,-0.0022,-2,-0.0015,-0.0056,5e-05,0,0,-6.3e-05,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.25,0.25,3.1,0.11,0.11,61,0.00022,0.00022,7.5e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5790000,1,-0.0096,-0.011,-2.3e-06,0.0053,-0.003,-0.75,0.0031,-0.0026,-2,-0.0015,-0.0056,5e-05,0,0,-6.3e-05,0,0,0,0,0,0,0,0,0.0019,0.0019,0.00013,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,7.5e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5890000,1,-0.0095,-0.011,-3.2e-05,0.0045,-0.0011,0.0028,0.0022,-0.0017,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-6.4e-05,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00012,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5990000,1,-0.0095,-0.011,-1.4e-05,0.0049,0.00031,0.015,0.0026,-0.0017,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00012,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6090000,1,-0.0094,-0.011,-3.4e-05,0.006,0.0015,-0.011,0.0032,-0.0016,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-6.4e-05,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00013,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6190000,0.7,0.0013,-0.015,0.71,0.0035,0.0029,-0.005,0.0023,-0.00066,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-8.8e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0013,0.0013,0.018,0.22,0.22,4.9,0.13,0.13,0.32,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6290000,0.7,0.0013,-0.015,0.71,0.0035,0.0043,-0.012,0.0026,-0.00028,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-9.5e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.22,0.22,3.2,0.16,0.16,0.3,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6390000,0.7,0.0014,-0.014,0.71,0.0024,0.0048,-0.05,0.0029,0.00018,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-3.6e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.23,0.23,2.3,0.19,0.19,0.29,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6490000,0.7,0.0014,-0.014,0.71,0.0022,0.0056,-0.052,0.0031,0.00072,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-8.5e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.24,0.24,1.5,0.23,0.23,0.26,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6590000,0.7,0.0014,-0.014,0.71,0.0017,0.0057,-0.099,0.0034,0.0013,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,9.5e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.25,0.25,1.1,0.28,0.28,0.23,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6690000,0.7,0.0014,-0.014,0.71,0.0021,0.0068,-0.076,0.0036,0.0019,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.00022,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.26,0.26,0.78,0.33,0.33,0.21,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6790000,0.7,0.0014,-0.014,0.71,0.0008,0.0068,-0.11,0.0037,0.0026,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,8.4e-06,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.28,0.28,0.6,0.38,0.38,0.2,0.00015,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6890000,0.71,0.0014,-0.014,0.71,-0.0012,0.0073,-0.12,0.0037,0.0033,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-4.3e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.3,0.3,0.46,0.44,0.44,0.18,0.00015,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6990000,0.71,0.0015,-0.014,0.71,-0.0013,0.0082,-0.12,0.0035,0.0041,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.00034,0.37,0.0037,0.025,0,0,0,0,0,0.0015,0.0015,0.018,0.32,0.32,0.36,0.51,0.51,0.16,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +7090000,0.71,0.0015,-0.014,0.71,-0.0018,0.0079,-0.13,0.0033,0.0049,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0007,0.37,0.0037,0.025,0,0,0,0,0,0.0015,0.0015,0.018,0.35,0.35,0.29,0.58,0.58,0.16,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +7190000,0.71,0.0015,-0.014,0.71,-0.0035,0.0081,-0.15,0.0031,0.0057,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.00049,0.37,0.0037,0.025,0,0,0,0,0,0.0015,0.0015,0.018,0.37,0.37,0.24,0.66,0.66,0.15,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +7290000,0.71,0.0015,-0.014,0.71,-0.005,0.0083,-0.15,0.0026,0.0065,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.0015,0.018,0.41,0.41,0.2,0.76,0.76,0.14,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +7390000,0.71,0.0015,-0.014,0.71,-0.0051,0.0098,-0.16,0.0021,0.0073,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.0016,0.018,0.44,0.44,0.18,0.85,0.85,0.13,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7490000,0.71,0.0016,-0.014,0.71,-0.0067,0.01,-0.16,0.0015,0.0083,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0021,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.0016,0.018,0.48,0.48,0.15,0.96,0.96,0.12,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7590000,0.71,0.0016,-0.014,0.71,-0.0086,0.012,-0.17,0.00072,0.0093,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.003,0.37,0.0037,0.025,0,0,0,0,0,0.0017,0.0017,0.018,0.51,0.52,0.14,1.1,1.1,0.12,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7690000,0.71,0.0017,-0.014,0.71,-0.01,0.012,-0.16,-0.00026,0.01,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.005,0.37,0.0037,0.025,0,0,0,0,0,0.0017,0.0017,0.018,0.56,0.56,0.13,1.2,1.2,0.11,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7790000,0.71,0.0017,-0.014,0.71,-0.012,0.013,-0.16,-0.0014,0.011,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.007,0.37,0.0037,0.025,0,0,0,0,0,0.0017,0.0017,0.018,0.6,0.6,0.12,1.3,1.3,0.11,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7890000,0.71,0.0017,-0.014,0.71,-0.015,0.015,-0.16,-0.0027,0.013,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0096,0.37,0.0037,0.025,0,0,0,0,0,0.0018,0.0018,0.018,0.65,0.66,0.11,1.5,1.5,0.1,0.00014,0.00014,6.3e-06,0.04,0.04,0.038,0,0,0,0,0,0,0,0 +7990000,0.71,0.0018,-0.014,0.71,-0.016,0.016,-0.16,-0.0043,0.014,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.0018,0.0018,0.018,0.7,0.7,0.1,1.7,1.7,0.099,0.00014,0.00014,6.3e-06,0.04,0.04,0.038,0,0,0,0,0,0,0,0 +8090000,0.71,0.0018,-0.014,0.71,-0.018,0.018,-0.17,-0.006,0.016,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.0019,0.0019,0.018,0.76,0.76,0.1,1.9,1.9,0.097,0.00014,0.00014,6.3e-06,0.04,0.04,0.037,0,0,0,0,0,0,0,0 +8190000,0.71,0.0017,-0.014,0.71,-0.021,0.019,-0.18,-0.008,0.018,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.013,0.37,0.0037,0.025,0,0,0,0,0,0.0019,0.0019,0.018,0.83,0.83,0.099,2.1,2.1,0.094,0.00014,0.00014,6.3e-06,0.04,0.04,0.037,0,0,0,0,0,0,0,0 +8290000,0.71,0.0018,-0.014,0.71,-0.022,0.02,-0.17,-0.01,0.019,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.017,0.37,0.0037,0.025,0,0,0,0,0,0.002,0.002,0.018,0.88,0.88,0.097,2.3,2.3,0.091,0.00014,0.00014,6.3e-06,0.04,0.04,0.036,0,0,0,0,0,0,0,0 +8390000,0.71,0.0018,-0.014,0.71,-0.025,0.021,-0.17,-0.013,0.021,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.021,0.37,0.0037,0.025,0,0,0,0,0,0.0021,0.002,0.018,0.95,0.95,0.097,2.5,2.5,0.091,0.00014,0.00014,6.3e-06,0.04,0.04,0.035,0,0,0,0,0,0,0,0 +8490000,0.71,0.0018,-0.014,0.71,-0.026,0.022,-0.17,-0.015,0.022,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.025,0.37,0.0037,0.025,0,0,0,0,0,0.0021,0.0021,0.018,1,1,0.096,2.8,2.8,0.089,0.00014,0.00014,6.3e-06,0.04,0.04,0.034,0,0,0,0,0,0,0,0 +8590000,0.71,0.0019,-0.014,0.71,-0.029,0.025,-0.17,-0.018,0.024,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.029,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0022,0.018,1.1,1.1,0.095,3.1,3.1,0.088,0.00014,0.00014,6.3e-06,0.04,0.04,0.034,0,0,0,0,0,0,0,0 +8690000,0.71,0.0019,-0.014,0.71,-0.032,0.025,-0.16,-0.021,0.026,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.035,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0022,0.018,1.1,1.1,0.096,3.3,3.3,0.088,0.00014,0.00014,6.3e-06,0.04,0.04,0.033,0,0,0,0,0,0,0,0 +8790000,0.71,0.0019,-0.014,0.71,-0.034,0.027,-0.15,-0.024,0.028,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.041,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0023,0.018,1.2,1.2,0.095,3.7,3.7,0.087,0.00014,0.00014,6.3e-06,0.04,0.04,0.032,0,0,0,0,0,0,0,0 +8890000,0.71,0.0019,-0.014,0.71,-0.036,0.028,-0.15,-0.027,0.03,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.045,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0023,0.018,1.3,1.3,0.095,3.9,3.9,0.086,0.00013,0.00013,6.3e-06,0.04,0.04,0.03,0,0,0,0,0,0,0,0 +8990000,0.71,0.002,-0.014,0.71,-0.038,0.028,-0.14,-0.031,0.032,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.051,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0024,0.018,1.4,1.4,0.096,4.3,4.3,0.087,0.00013,0.00013,6.3e-06,0.04,0.04,0.029,0,0,0,0,0,0,0,0 +9090000,0.71,0.002,-0.014,0.71,-0.04,0.029,-0.14,-0.034,0.033,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.053,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0024,0.018,1.4,1.4,0.095,4.6,4.6,0.086,0.00013,0.00013,6.3e-06,0.04,0.04,0.028,0,0,0,0,0,0,0,0 +9190000,0.71,0.002,-0.014,0.71,-0.042,0.03,-0.14,-0.038,0.036,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.057,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.0025,0.018,1.5,1.5,0.094,5.1,5.1,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.027,0,0,0,0,0,0,0,0 +9290000,0.71,0.002,-0.014,0.71,-0.042,0.03,-0.14,-0.041,0.037,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.061,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.0025,0.018,1.6,1.6,0.093,5.3,5.3,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.025,0,0,0,0,0,0,0,0 +9390000,0.71,0.002,-0.014,0.71,-0.044,0.033,-0.14,-0.045,0.04,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.065,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0026,0.018,1.7,1.7,0.093,5.8,5.9,0.086,0.00013,0.00013,6.3e-06,0.04,0.04,0.024,0,0,0,0,0,0,0,0 +9490000,0.71,0.002,-0.014,0.71,-0.045,0.032,-0.13,-0.047,0.04,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.068,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0025,0.018,1.7,1.7,0.091,6.1,6.1,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.023,0,0,0,0,0,0,0,0 +9590000,0.71,0.002,-0.014,0.71,-0.048,0.034,-0.13,-0.052,0.043,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.072,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0026,0.018,1.8,1.8,0.09,6.7,6.7,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.021,0,0,0,0,0,0,0,0 +9690000,0.71,0.002,-0.014,0.71,-0.048,0.035,-0.12,-0.054,0.043,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.077,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0026,0.018,1.9,1.9,0.089,6.8,6.8,0.086,0.00012,0.00012,6.3e-06,0.04,0.04,0.02,0,0,0,0,0,0,0,0 +9790000,0.71,0.002,-0.014,0.71,-0.049,0.037,-0.11,-0.059,0.047,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.082,0.37,0.0037,0.025,0,0,0,0,0,0.0027,0.0027,0.018,2,2,0.087,7.5,7.5,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.019,0,0,0,0,0,0,0,0 +9890000,0.71,0.002,-0.014,0.71,-0.049,0.038,-0.11,-0.06,0.046,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.085,0.37,0.0037,0.025,0,0,0,0,0,0.0027,0.0027,0.018,2,2,0.084,7.6,7.6,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.018,0,0,0,0,0,0,0,0 +9990000,0.71,0.0021,-0.014,0.71,-0.051,0.038,-0.1,-0.065,0.05,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.089,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.0028,0.018,2.1,2.1,0.083,8.4,8.4,0.086,0.00012,0.00012,6.3e-06,0.04,0.04,0.017,0,0,0,0,0,0,0,0 +10090000,0.71,0.0021,-0.014,0.71,-0.049,0.037,-0.096,-0.064,0.049,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.091,0.37,0.0037,0.025,0,0,0,0,0,0.0027,0.0027,0.018,2.1,2.1,0.08,8.4,8.4,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.016,0,0,0,0,0,0,0,0 +10190000,0.71,0.0021,-0.014,0.71,-0.051,0.04,-0.096,-0.07,0.053,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.0028,0.018,2.2,2.2,0.078,9.2,9.2,0.084,0.00012,0.00012,6.3e-06,0.04,0.04,0.014,0,0,0,0,0,0,0,0 +10290000,0.71,0.0021,-0.014,0.71,-0.052,0.041,-0.084,-0.075,0.057,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.0029,0.0029,0.018,2.4,2.4,0.076,10,10,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.014,0,0,0,0,0,0,0,0 +10390000,0.71,0.0021,-0.014,0.71,0.0095,-0.019,0.0096,0.00087,-0.0017,-3.7e+02,-0.0015,-0.0056,4.8e-05,-6.6e-08,4.9e-08,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.003,0.003,0.018,0.25,0.25,0.56,0.25,0.25,0.078,0.00012,0.00012,6.3e-06,0.04,0.04,0.013,0,0,0,0,0,0,0,0 +10490000,0.71,0.0021,-0.014,0.71,0.0082,-0.017,0.023,0.0017,-0.0035,-3.7e+02,-0.0015,-0.0056,4.8e-05,-1.7e-06,1.3e-06,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0031,0.0031,0.018,0.26,0.26,0.55,0.26,0.26,0.08,0.00012,0.00012,6.3e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0 +10590000,0.71,0.0022,-0.014,0.71,0.0078,-0.0065,0.026,0.0018,-0.00081,-3.7e+02,-0.0015,-0.0056,4.9e-05,-0.00027,3e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0031,0.0031,0.018,0.14,0.14,0.27,0.13,0.13,0.073,0.00012,0.00012,6.3e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0 +10690000,0.71,0.0023,-0.014,0.71,0.0057,-0.0058,0.03,0.0025,-0.0014,-3.7e+02,-0.0015,-0.0056,4.9e-05,-0.00027,3.1e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0032,0.0032,0.018,0.15,0.15,0.26,0.14,0.14,0.078,0.00012,0.00012,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0 +10790000,0.71,0.0022,-0.014,0.71,0.0052,-0.003,0.024,0.0027,-0.00072,-3.7e+02,-0.0014,-0.0056,4.8e-05,-0.00042,0.00016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0031,0.0031,0.018,0.11,0.11,0.17,0.091,0.091,0.072,0.00011,0.00011,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0 +10890000,0.71,0.0022,-0.014,0.71,0.0039,-0.0017,0.02,0.0031,-0.00092,-3.7e+02,-0.0014,-0.0056,4.8e-05,-0.00042,0.00016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0032,0.0032,0.018,0.13,0.13,0.16,0.098,0.098,0.075,0.00011,0.00011,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0 +10990000,0.71,0.0022,-0.014,0.71,0.0067,0.0034,0.014,0.0047,-0.0022,-3.7e+02,-0.0014,-0.0055,4.6e-05,-0.00082,0.00076,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0029,0.0029,0.018,0.1,0.1,0.12,0.073,0.073,0.071,0.0001,0.0001,6.3e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0 +11090000,0.71,0.0022,-0.014,0.71,0.0055,0.0059,0.019,0.0053,-0.0018,-3.7e+02,-0.0014,-0.0055,4.6e-05,-0.00082,0.00076,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.003,0.003,0.018,0.13,0.13,0.11,0.08,0.08,0.074,0.0001,0.0001,6.3e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0 +11190000,0.71,0.002,-0.014,0.71,0.01,0.0083,0.0077,0.0067,-0.0028,-3.7e+02,-0.0013,-0.0055,4.4e-05,-0.00093,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0026,0.018,0.1,0.1,0.084,0.063,0.063,0.069,9.3e-05,9.3e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 +11290000,0.71,0.0021,-0.014,0.71,0.01,0.011,0.0074,0.0078,-0.0018,-3.7e+02,-0.0013,-0.0055,4.4e-05,-0.00093,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0027,0.0027,0.018,0.13,0.13,0.078,0.071,0.071,0.072,9.3e-05,9.3e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 +11390000,0.71,0.0022,-0.014,0.71,0.0053,0.0092,0.0017,0.0055,-0.0019,-3.7e+02,-0.0013,-0.0056,4.6e-05,-0.0005,0.00088,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0022,0.018,0.1,0.1,0.063,0.058,0.058,0.068,8.2e-05,8.2e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 +11490000,0.71,0.0022,-0.014,0.71,0.0028,0.012,0.0025,0.0059,-0.00089,-3.7e+02,-0.0013,-0.0056,4.6e-05,-0.00051,0.00089,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0023,0.018,0.13,0.13,0.058,0.066,0.066,0.069,8.2e-05,8.2e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 +11590000,0.71,0.0021,-0.014,0.71,-0.0016,0.01,-0.0034,0.0045,-0.0014,-3.7e+02,-0.0014,-0.0056,4.6e-05,-8.6e-05,0.00077,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0019,0.0019,0.018,0.1,0.1,0.049,0.054,0.054,0.066,7.2e-05,7.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +11690000,0.71,0.002,-0.014,0.71,-0.0044,0.013,-0.0079,0.0042,-0.00026,-3.7e+02,-0.0014,-0.0056,4.6e-05,-7.7e-05,0.00076,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0019,0.0019,0.018,0.12,0.12,0.046,0.063,0.063,0.066,7.2e-05,7.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +11790000,0.71,0.0021,-0.014,0.71,-0.01,0.013,-0.0098,0.0018,0.00056,-3.7e+02,-0.0014,-0.0056,4.6e-05,3.2e-05,0.00057,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.0016,0.018,0.097,0.097,0.039,0.053,0.053,0.063,6.3e-05,6.3e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +11890000,0.71,0.0021,-0.014,0.71,-0.012,0.014,-0.011,0.00076,0.0019,-3.7e+02,-0.0014,-0.0056,4.6e-05,2.7e-05,0.00057,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.0016,0.018,0.12,0.12,0.037,0.061,0.061,0.063,6.3e-05,6.3e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +11990000,0.71,0.0021,-0.014,0.71,-0.013,0.014,-0.016,-0.0003,0.0023,-3.7e+02,-0.0014,-0.0057,4.6e-05,0.00017,0.00059,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.091,0.091,0.033,0.051,0.051,0.061,5.7e-05,5.7e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12090000,0.71,0.0021,-0.014,0.71,-0.015,0.016,-0.022,-0.0017,0.0038,-3.7e+02,-0.0014,-0.0057,4.6e-05,0.00018,0.00057,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.11,0.11,0.031,0.06,0.06,0.061,5.7e-05,5.7e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12190000,0.71,0.0017,-0.014,0.71,-0.008,0.013,-0.017,0.0015,0.0019,-3.7e+02,-0.0013,-0.0057,4.3e-05,0.00044,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0012,0.0012,0.018,0.085,0.085,0.028,0.051,0.051,0.059,5.2e-05,5.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12290000,0.71,0.0017,-0.014,0.71,-0.011,0.015,-0.016,0.00055,0.0033,-3.7e+02,-0.0013,-0.0057,4.3e-05,0.00041,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0013,0.0012,0.018,0.1,0.1,0.028,0.06,0.06,0.059,5.2e-05,5.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12390000,0.71,0.0014,-0.014,0.71,-0.0051,0.011,-0.015,0.003,0.0016,-3.7e+02,-0.0012,-0.0058,4.1e-05,0.00057,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,0.0011,0.018,0.079,0.079,0.026,0.05,0.05,0.057,4.8e-05,4.8e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12490000,0.71,0.0014,-0.014,0.71,-0.0063,0.013,-0.018,0.0025,0.0029,-3.7e+02,-0.0012,-0.0058,4.1e-05,0.00057,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,0.0011,0.018,0.093,0.093,0.026,0.059,0.059,0.057,4.8e-05,4.8e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12590000,0.71,0.0015,-0.014,0.71,-0.014,0.011,-0.023,-0.0028,0.0014,-3.7e+02,-0.0013,-0.0058,4.3e-05,0.00071,0.0012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.001,0.001,0.018,0.074,0.074,0.025,0.05,0.05,0.055,4.5e-05,4.5e-05,6.3e-06,0.037,0.037,0.0099,0,0,0,0,0,0,0,0 +12690000,0.71,0.0015,-0.014,0.71,-0.014,0.012,-0.027,-0.0042,0.0026,-3.7e+02,-0.0013,-0.0058,4.3e-05,0.00073,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.001,0.001,0.018,0.085,0.085,0.025,0.058,0.058,0.055,4.5e-05,4.5e-05,6.3e-06,0.037,0.037,0.0098,0,0,0,0,0,0,0,0 +12790000,0.71,0.0015,-0.013,0.71,-0.02,0.0091,-0.03,-0.0076,0.0013,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.00077,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00094,0.00094,0.018,0.068,0.068,0.024,0.049,0.049,0.053,4.2e-05,4.2e-05,6.3e-06,0.037,0.037,0.0097,0,0,0,0,0,0,0,0 +12890000,0.71,0.0015,-0.013,0.71,-0.021,0.0091,-0.029,-0.0096,0.0022,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.00071,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00097,0.00097,0.018,0.079,0.079,0.025,0.058,0.058,0.054,4.2e-05,4.2e-05,6.3e-06,0.037,0.037,0.0096,0,0,0,0,0,0,0,0 +12990000,0.71,0.0012,-0.014,0.71,-0.0084,0.0066,-0.03,-0.001,0.0012,-3.7e+02,-0.0012,-0.0059,4e-05,0.00068,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00089,0.00089,0.018,0.064,0.064,0.025,0.049,0.049,0.052,4e-05,4e-05,6.3e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0 +13090000,0.71,0.0012,-0.014,0.71,-0.0091,0.0067,-0.03,-0.0019,0.0018,-3.7e+02,-0.0012,-0.0059,4e-05,0.00065,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00092,0.00092,0.018,0.073,0.073,0.025,0.058,0.058,0.052,4e-05,4e-05,6.3e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0 +13190000,0.71,0.00091,-0.014,0.71,1.9e-05,0.0061,-0.027,0.0044,0.0012,-3.7e+02,-0.0012,-0.0059,3.8e-05,0.00051,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00086,0.00086,0.018,0.06,0.06,0.025,0.049,0.049,0.051,3.8e-05,3.8e-05,6.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0 +13290000,0.71,0.00092,-0.014,0.71,-0.00022,0.0069,-0.024,0.0044,0.0018,-3.7e+02,-0.0012,-0.0059,3.8e-05,0.00037,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00089,0.00089,0.018,0.068,0.068,0.027,0.057,0.057,0.051,3.8e-05,3.8e-05,6.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0 +13390000,0.71,0.00077,-0.014,0.71,0.0006,0.0059,-0.02,0.0033,0.0011,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.0002,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00084,0.00084,0.018,0.056,0.056,0.026,0.049,0.049,0.05,3.6e-05,3.6e-05,6.3e-06,0.037,0.037,0.0088,0,0,0,0,0,0,0,0 +13490000,0.71,0.0008,-0.014,0.71,0.00011,0.0058,-0.019,0.0034,0.0016,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.00012,0.0016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00086,0.00086,0.018,0.064,0.064,0.028,0.057,0.057,0.05,3.6e-05,3.6e-05,6.3e-06,0.037,0.037,0.0087,0,0,0,0,0,0,0,0 +13590000,0.71,0.00074,-0.014,0.71,0.00036,0.006,-0.021,0.0024,0.001,-3.7e+02,-0.0012,-0.006,3.7e-05,9e-05,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00082,0.00082,0.018,0.053,0.053,0.028,0.049,0.049,0.05,3.4e-05,3.4e-05,6.3e-06,0.036,0.036,0.0084,0,0,0,0,0,0,0,0 +13690000,0.71,0.00072,-0.014,0.71,0.0011,0.0078,-0.025,0.0025,0.0017,-3.7e+02,-0.0012,-0.006,3.7e-05,0.00012,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00084,0.00084,0.018,0.06,0.06,0.029,0.056,0.056,0.05,3.4e-05,3.4e-05,6.3e-06,0.036,0.036,0.0083,0,0,0,0,0,0,0,0 +13790000,0.71,0.0006,-0.014,0.71,0.0016,0.0036,-0.027,0.0035,-0.00064,-3.7e+02,-0.0011,-0.006,3.6e-05,-0.0001,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00081,0.0008,0.018,0.051,0.051,0.029,0.048,0.048,0.049,3.3e-05,3.3e-05,6.3e-06,0.036,0.036,0.0079,0,0,0,0,0,0,0,0 +13890000,0.71,0.00057,-0.014,0.71,0.0021,0.0035,-0.031,0.0037,-0.0003,-3.7e+02,-0.0011,-0.006,3.6e-05,-7.1e-05,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00083,0.00083,0.018,0.057,0.057,0.03,0.056,0.056,0.05,3.3e-05,3.3e-05,6.3e-06,0.036,0.036,0.0078,0,0,0,0,0,0,0,0 +13990000,0.71,0.0005,-0.014,0.71,0.0024,0.001,-0.03,0.0045,-0.002,-3.7e+02,-0.0011,-0.006,3.5e-05,-0.00034,0.0012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0008,0.0008,0.018,0.048,0.048,0.03,0.048,0.048,0.05,3.1e-05,3.1e-05,6.3e-06,0.036,0.036,0.0074,0,0,0,0,0,0,0,0 +14090000,0.71,0.00049,-0.014,0.71,0.0025,0.0012,-0.031,0.0047,-0.0019,-3.7e+02,-0.0011,-0.006,3.5e-05,-0.00033,0.0012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00082,0.00082,0.018,0.055,0.055,0.031,0.055,0.055,0.05,3.1e-05,3.1e-05,6.3e-06,0.036,0.036,0.0073,0,0,0,0,0,0,0,0 +14190000,0.71,0.00038,-0.014,0.71,0.0058,0.00062,-0.033,0.0068,-0.0017,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00031,0.00088,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00079,0.00079,0.018,0.046,0.046,0.031,0.048,0.048,0.05,2.9e-05,2.9e-05,6.3e-06,0.036,0.036,0.0069,0,0,0,0,0,0,0,0 +14290000,0.71,0.00039,-0.014,0.71,0.0066,0.0014,-0.032,0.0074,-0.0016,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00038,0.00094,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00081,0.00081,0.018,0.052,0.052,0.032,0.055,0.055,0.051,2.9e-05,2.9e-05,6.3e-06,0.036,0.036,0.0067,0,0,0,0,0,0,0,0 +14390000,0.71,0.00031,-0.014,0.71,0.0084,0.0023,-0.034,0.0088,-0.0013,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00039,0.00069,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00078,0.00078,0.018,0.045,0.045,0.031,0.048,0.048,0.05,2.8e-05,2.8e-05,6.3e-06,0.036,0.036,0.0063,0,0,0,0,0,0,0,0 +14490000,0.71,0.00029,-0.013,0.71,0.0084,0.0035,-0.037,0.0096,-0.0011,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00034,0.00064,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0008,0.0008,0.018,0.05,0.05,0.032,0.055,0.055,0.051,2.8e-05,2.8e-05,6.3e-06,0.036,0.036,0.0062,0,0,0,0,0,0,0,0 +14590000,0.71,0.00028,-0.013,0.71,0.0049,0.0019,-0.037,0.006,-0.0025,-3.7e+02,-0.0011,-0.0061,3.5e-05,-0.00071,0.001,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00077,0.00077,0.018,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-05,2.6e-05,6.3e-06,0.036,0.036,0.0058,0,0,0,0,0,0,0,0 +14690000,0.71,0.00024,-0.013,0.71,0.0063,-0.001,-0.034,0.0066,-0.0024,-3.7e+02,-0.0011,-0.0061,3.5e-05,-0.00082,0.0011,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00079,0.00079,0.018,0.049,0.049,0.032,0.054,0.054,0.051,2.6e-05,2.6e-05,6.3e-06,0.036,0.036,0.0056,0,0,0,0,0,0,0,0 +14790000,0.71,0.00027,-0.013,0.71,0.0031,-0.0026,-0.03,0.0037,-0.0034,-3.7e+02,-0.0011,-0.0061,3.6e-05,-0.0012,0.0016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00077,0.00077,0.018,0.042,0.042,0.031,0.047,0.047,0.051,2.5e-05,2.5e-05,6.3e-06,0.036,0.036,0.0053,0,0,0,0,0,0,0,0 +14890000,0.71,0.00026,-0.013,0.71,0.0046,-0.0017,-0.033,0.0041,-0.0036,-3.7e+02,-0.0011,-0.0061,3.6e-05,-0.0012,0.0016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00079,0.00079,0.018,0.047,0.047,0.031,0.054,0.054,0.052,2.5e-05,2.5e-05,6.3e-06,0.036,0.036,0.0051,0,0,0,0,0,0,0,0 +14990000,0.71,0.00026,-0.013,0.71,0.0034,-0.0018,-0.029,0.0032,-0.0029,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0013,0.0019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00076,0.00076,0.018,0.041,0.041,0.03,0.047,0.047,0.051,2.3e-05,2.3e-05,6.3e-06,0.036,0.036,0.0048,0,0,0,0,0,0,0,0 +15090000,0.71,0.00018,-0.013,0.71,0.0038,-0.002,-0.032,0.0035,-0.0031,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0012,0.0018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00078,0.00078,0.019,0.046,0.046,0.031,0.054,0.054,0.052,2.3e-05,2.3e-05,6.3e-06,0.036,0.036,0.0046,0,0,0,0,0,0,0,0 +15190000,0.71,0.0002,-0.013,0.71,0.0032,-0.0008,-0.029,0.0028,-0.0024,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0012,0.002,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00075,0.00075,0.019,0.04,0.04,0.03,0.047,0.047,0.052,2.2e-05,2.2e-05,6.3e-06,0.035,0.035,0.0043,0,0,0,0,0,0,0,0 +15290000,0.71,0.00016,-0.013,0.71,0.0038,-0.00064,-0.027,0.0031,-0.0025,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0013,0.0021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00077,0.00077,0.019,0.045,0.045,0.03,0.054,0.054,0.052,2.2e-05,2.2e-05,6.3e-06,0.035,0.035,0.0042,0,0,0,0,0,0,0,0 +15390000,0.71,0.00017,-0.013,0.71,0.003,-0.0003,-0.024,0.00057,-0.002,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00074,0.00074,0.019,0.04,0.04,0.029,0.047,0.047,0.051,2e-05,2e-05,6.3e-06,0.035,0.035,0.0039,0,0,0,0,0,0,0,0 +15490000,0.71,0.00019,-0.013,0.71,0.0043,-0.00068,-0.024,0.00095,-0.0021,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00076,0.00076,0.019,0.045,0.045,0.029,0.053,0.053,0.053,2e-05,2e-05,6.3e-06,0.035,0.035,0.0037,0,0,0,0,0,0,0,0 +15590000,0.71,0.0002,-0.013,0.71,0.0024,-0.00067,-0.023,-0.0013,-0.0017,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00073,0.00073,0.019,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-05,1.9e-05,6.3e-06,0.035,0.035,0.0035,0,0,0,0,0,0,0,0 +15690000,0.71,0.0002,-0.013,0.71,0.0027,-0.00085,-0.023,-0.0011,-0.0018,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00074,0.00074,0.019,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-05,1.9e-05,6.3e-06,0.035,0.035,0.0033,0,0,0,0,0,0,0,0 +15790000,0.71,0.00017,-0.013,0.71,0.0032,-0.0025,-0.026,-0.00095,-0.0028,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0016,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00071,0.00071,0.019,0.038,0.038,0.027,0.046,0.046,0.051,1.7e-05,1.7e-05,6.3e-06,0.035,0.035,0.0031,0,0,0,0,0,0,0,0 +15890000,0.71,0.00012,-0.013,0.71,0.0041,-0.003,-0.024,-0.00056,-0.0031,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0016,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00073,0.00073,0.019,0.043,0.043,0.027,0.053,0.053,0.052,1.7e-05,1.7e-05,6.3e-06,0.035,0.035,0.003,0,0,0,0,0,0,0,0 +15990000,0.71,6.2e-05,-0.013,0.71,0.004,-0.0039,-0.019,-0.00063,-0.0039,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0019,0.0027,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0007,0.0007,0.019,0.038,0.038,0.026,0.046,0.046,0.051,1.6e-05,1.6e-05,6.3e-06,0.034,0.034,0.0028,0,0,0,0,0,0,0,0 +16090000,0.71,6.5e-05,-0.013,0.71,0.0057,-0.0041,-0.016,-0.00016,-0.0043,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.002,0.0028,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00071,0.00072,0.019,0.043,0.043,0.025,0.053,0.053,0.052,1.6e-05,1.6e-05,6.3e-06,0.034,0.034,0.0027,0,0,0,0,0,0,0,0 +16190000,0.71,9e-05,-0.013,0.71,0.0057,-0.0033,-0.014,-0.00037,-0.0035,-3.7e+02,-0.0012,-0.0061,3.8e-05,-0.0019,0.003,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00068,0.00068,0.019,0.037,0.037,0.025,0.046,0.046,0.051,1.5e-05,1.5e-05,6.3e-06,0.034,0.034,0.0025,0,0,0,0,0,0,0,0 +16290000,0.71,0.00011,-0.013,0.71,0.0073,-0.0042,-0.016,0.00029,-0.0038,-3.7e+02,-0.0012,-0.0061,3.8e-05,-0.0018,0.003,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0007,0.0007,0.019,0.042,0.042,0.024,0.053,0.053,0.052,1.5e-05,1.5e-05,6.3e-06,0.034,0.034,0.0024,0,0,0,0,0,0,0,0 +16390000,0.71,0.0001,-0.013,0.71,0.0062,-0.0044,-0.015,-4.2e-05,-0.0031,-3.7e+02,-0.0013,-0.0061,3.8e-05,-0.0017,0.0033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00067,0.00067,0.019,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-05,1.4e-05,6.3e-06,0.034,0.034,0.0022,0,0,0,0,0,0,0,0 +16490000,0.71,0.00012,-0.013,0.71,0.0054,-0.0039,-0.018,0.00051,-0.0035,-3.7e+02,-0.0013,-0.0061,3.8e-05,-0.0017,0.0032,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00068,0.00068,0.019,0.041,0.041,0.023,0.052,0.052,0.052,1.4e-05,1.4e-05,6.3e-06,0.034,0.034,0.0021,0,0,0,0,0,0,0,0 +16590000,0.71,0.00038,-0.013,0.71,0.0018,-0.0012,-0.018,-0.0024,-8.7e-05,-3.7e+02,-0.0013,-0.006,4e-05,-0.001,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00065,0.00065,0.019,0.036,0.036,0.022,0.046,0.046,0.051,1.2e-05,1.2e-05,6.3e-06,0.033,0.033,0.002,0,0,0,0,0,0,0,0 +16690000,0.71,0.00036,-0.013,0.71,0.002,-0.00074,-0.015,-0.0022,-0.00018,-3.7e+02,-0.0013,-0.006,4e-05,-0.0011,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00067,0.00067,0.019,0.041,0.041,0.022,0.052,0.052,0.051,1.2e-05,1.2e-05,6.3e-06,0.033,0.033,0.0019,0,0,0,0,0,0,0,0 +16790000,0.71,0.00051,-0.013,0.71,-0.0013,0.0015,-0.014,-0.0046,0.0025,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0005,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00064,0.00064,0.019,0.036,0.036,0.021,0.046,0.046,0.05,1.1e-05,1.1e-05,6.3e-06,0.033,0.033,0.0018,0,0,0,0,0,0,0,0 +16890000,0.71,0.00053,-0.013,0.71,-0.0016,0.0023,-0.011,-0.0047,0.0027,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.00054,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00065,0.00065,0.019,0.04,0.04,0.021,0.052,0.052,0.051,1.1e-05,1.1e-05,6.3e-06,0.033,0.033,0.0017,0,0,0,0,0,0,0,0 +16990000,0.71,0.00046,-0.013,0.71,-0.0016,0.00032,-0.01,-0.0052,0.00084,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.00095,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00062,0.00062,0.019,0.035,0.035,0.02,0.046,0.046,0.05,1e-05,1e-05,6.3e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0 +17090000,0.71,0.00043,-0.013,0.71,-0.0008,0.0013,-0.01,-0.0053,0.0009,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.00094,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00063,0.00063,0.019,0.039,0.039,0.02,0.052,0.052,0.05,1e-05,1e-05,6.3e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0 +17190000,0.71,0.00042,-0.013,0.71,-0.00034,0.0013,-0.011,-0.0056,-0.00054,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0013,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0006,0.0006,0.019,0.035,0.035,0.019,0.046,0.046,0.049,9.4e-06,9.4e-06,6.3e-06,0.032,0.032,0.0015,0,0,0,0,0,0,0,0 +17290000,0.71,0.0004,-0.013,0.71,0.0017,0.0023,-0.0066,-0.0056,-0.00038,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0013,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00061,0.00061,0.019,0.039,0.039,0.019,0.052,0.052,0.049,9.4e-06,9.4e-06,6.3e-06,0.032,0.032,0.0014,0,0,0,0,0,0,0,0 +17390000,0.71,0.00036,-0.013,0.71,0.0024,0.0015,-0.0047,-0.0046,-0.0016,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0017,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00059,0.00059,0.019,0.034,0.034,0.018,0.046,0.046,0.048,8.5e-06,8.5e-06,6.3e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0 +17490000,0.71,0.00036,-0.013,0.71,0.0029,0.001,-0.003,-0.0044,-0.0015,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0017,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0006,0.0006,0.019,0.038,0.038,0.018,0.052,0.052,0.049,8.5e-06,8.5e-06,6.3e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0 +17590000,0.71,0.00027,-0.013,0.71,0.0042,-0.00013,0.0025,-0.0037,-0.0026,-3.7e+02,-0.0014,-0.0061,4.1e-05,-0.002,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00057,0.00057,0.019,0.034,0.034,0.017,0.045,0.045,0.048,7.7e-06,7.7e-06,6.3e-06,0.032,0.032,0.0012,0,0,0,0,0,0,0,0 +17690000,0.71,0.00024,-0.013,0.71,0.0051,0.00058,0.0019,-0.0032,-0.0026,-3.7e+02,-0.0014,-0.0061,4.1e-05,-0.002,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00058,0.00058,0.019,0.037,0.037,0.017,0.052,0.052,0.048,7.7e-06,7.7e-06,6.3e-06,0.032,0.032,0.0012,0,0,0,0,0,0,0,0 +17790000,0.71,0.00015,-0.013,0.71,0.0076,0.0003,0.00059,-0.0021,-0.0022,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.002,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00056,0.00055,0.019,0.033,0.033,0.016,0.045,0.045,0.048,7e-06,7e-06,6.3e-06,0.032,0.032,0.0011,0,0,0,0,0,0,0,0 +17890000,0.71,0.00016,-0.013,0.71,0.0092,-0.00046,0.00069,-0.0012,-0.0022,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.002,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00056,0.00056,0.019,0.037,0.037,0.016,0.052,0.052,0.048,7e-06,7e-06,6.3e-06,0.032,0.032,0.0011,0,0,0,0,0,0,0,0 +17990000,0.71,0.00011,-0.013,0.71,0.011,-0.0022,0.0019,-0.00052,-0.0019,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00054,0.00054,0.019,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-06,6.4e-06,6.3e-06,0.031,0.031,0.001,0,0,0,0,0,0,0,0 +18090000,0.71,0.00011,-0.013,0.71,0.012,-0.0024,0.0043,0.0006,-0.0022,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00055,0.00055,0.019,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-06,6.4e-06,6.3e-06,0.031,0.031,0.00097,0,0,0,0,0,0,0,0 +18190000,0.71,8e-05,-0.013,0.71,0.012,-0.0013,0.0056,0.0015,-0.0017,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00053,0.00053,0.019,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-06,5.8e-06,6.3e-06,0.031,0.031,0.00092,0,0,0,0,0,0,0,0 +18290000,0.71,2.1e-05,-0.012,0.71,0.012,-0.0019,0.0068,0.0027,-0.0018,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00053,0.00053,0.019,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-06,5.8e-06,6.3e-06,0.031,0.031,0.00089,0,0,0,0,0,0,0,0 +18390000,0.71,3.8e-05,-0.013,0.71,0.013,-0.0002,0.008,0.0032,-0.0014,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0018,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00051,0.00051,0.019,0.031,0.031,0.014,0.045,0.045,0.046,5.2e-06,5.2e-06,6.3e-06,0.031,0.031,0.00084,0,0,0,0,0,0,0,0 +18490000,0.71,5.4e-05,-0.012,0.71,0.014,0.00021,0.0076,0.0047,-0.0014,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0018,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00052,0.00052,0.019,0.034,0.034,0.014,0.051,0.051,0.046,5.2e-06,5.2e-06,6.3e-06,0.031,0.031,0.00082,0,0,0,0,0,0,0,0 +18590000,0.71,6e-05,-0.012,0.71,0.013,0.00045,0.0058,0.0035,-0.0012,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0018,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0005,0.0005,0.019,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-06,4.8e-06,6.3e-06,0.031,0.031,0.00078,0,0,0,0,0,0,0,0 +18690000,0.71,2.9e-05,-0.012,0.71,0.014,-0.00024,0.0039,0.0049,-0.0011,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0018,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00051,0.00051,0.019,0.033,0.033,0.013,0.051,0.051,0.045,4.8e-06,4.8e-06,6.3e-06,0.031,0.031,0.00075,0,0,0,0,0,0,0,0 +18790000,0.71,5.9e-05,-0.012,0.71,0.012,6.5e-05,0.0035,0.0037,-0.00091,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00049,0.00049,0.019,0.03,0.03,0.013,0.045,0.045,0.045,4.3e-06,4.3e-06,6.3e-06,0.031,0.031,0.00072,0,0,0,0,0,0,0,0 +18890000,0.71,8.4e-05,-0.012,0.71,0.013,0.00056,0.0042,0.005,-0.00084,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00049,0.00049,0.019,0.033,0.033,0.013,0.051,0.051,0.045,4.3e-06,4.3e-06,6.3e-06,0.031,0.031,0.0007,0,0,0,0,0,0,0,0 +18990000,0.71,7.3e-05,-0.012,0.71,0.014,0.0015,0.0028,0.0063,-0.0007,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00048,0.00048,0.019,0.029,0.029,0.012,0.045,0.045,0.044,3.9e-06,3.9e-06,6.3e-06,0.031,0.031,0.00066,0,0,0,0,0,0,0,0 +19090000,0.71,5.7e-05,-0.012,0.71,0.015,0.0021,0.0058,0.0078,-0.0005,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00048,0.00048,0.019,0.032,0.032,0.012,0.051,0.051,0.044,3.9e-06,3.9e-06,6.3e-06,0.031,0.031,0.00065,0,0,0,0,0,0,0,0 +19190000,0.71,6.1e-05,-0.012,0.71,0.015,0.0021,0.0059,0.0086,-0.00045,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00047,0.00047,0.019,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-06,3.6e-06,6.3e-06,0.03,0.03,0.00062,0,0,0,0,0,0,0,0 +19290000,0.71,8.3e-05,-0.012,0.71,0.015,0.0013,0.0086,0.01,-0.00026,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00047,0.00047,0.019,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-06,3.6e-06,6.3e-06,0.03,0.03,0.0006,0,0,0,0,0,0,0,0 +19390000,0.71,9.6e-05,-0.012,0.71,0.013,0.00039,0.012,0.008,-0.00028,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00046,0.00046,0.019,0.027,0.027,0.012,0.044,0.044,0.043,3.3e-06,3.3e-06,6.3e-06,0.03,0.03,0.00058,0,0,0,0,0,0,0,0 +19490000,0.71,0.00012,-0.012,0.71,0.012,-0.00032,0.0088,0.0092,-0.00028,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00046,0.00046,0.019,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-06,3.3e-06,6.3e-06,0.03,0.03,0.00056,0,0,0,0,0,0,0,0 +19590000,0.71,0.00017,-0.012,0.71,0.0096,-0.0013,0.0081,0.0075,-0.00029,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00045,0.00045,0.019,0.027,0.027,0.011,0.044,0.044,0.042,3e-06,3e-06,6.3e-06,0.03,0.03,0.00054,0,0,0,0,0,0,0,0 +19690000,0.71,0.00017,-0.012,0.71,0.01,-0.0035,0.0096,0.0084,-0.00054,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00045,0.00045,0.019,0.029,0.029,0.011,0.05,0.05,0.042,3e-06,3e-06,6.3e-06,0.03,0.03,0.00052,0,0,0,0,0,0,0,0 +19790000,0.71,0.00024,-0.012,0.71,0.0077,-0.0044,0.01,0.0068,-0.00044,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0065,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00044,0.00044,0.019,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-06,2.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19890000,0.71,0.00019,-0.012,0.71,0.0064,-0.0047,0.011,0.0075,-0.0009,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0065,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00044,0.00044,0.019,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-06,2.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19990000,0.71,0.00018,-0.012,0.71,0.004,-0.0054,0.014,0.0061,-0.00075,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0018,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00043,0.00043,0.019,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-06,2.5e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20090000,0.71,0.00018,-0.012,0.71,0.0038,-0.0073,0.014,0.0065,-0.0014,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0018,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00043,0.00043,0.019,0.028,0.028,0.01,0.049,0.049,0.042,2.5e-06,2.5e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20190000,0.71,0.00028,-0.012,0.71,0.0014,-0.008,0.017,0.0042,-0.0011,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0017,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00042,0.00042,0.019,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-06,2.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20290000,0.71,0.00024,-0.012,0.71,0.00031,-0.0096,0.015,0.0043,-0.002,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0017,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00043,0.00043,0.019,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-06,2.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20390000,0.71,0.00026,-0.012,0.71,-0.0021,-0.01,0.017,0.0024,-0.0015,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0016,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00042,0.00042,0.019,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-06,2.1e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20490000,0.71,0.00032,-0.012,0.71,-0.0026,-0.011,0.016,0.0022,-0.0026,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0016,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00042,0.00042,0.019,0.026,0.026,0.0096,0.049,0.049,0.041,2.1e-06,2.1e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20590000,0.71,0.00034,-0.012,0.71,-0.0023,-0.011,0.013,0.0019,-0.0021,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0014,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00041,0.00041,0.019,0.024,0.024,0.0094,0.044,0.044,0.04,1.9e-06,1.9e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20690000,0.71,0.00036,-0.012,0.71,-0.0022,-0.012,0.015,0.0016,-0.0032,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0014,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00041,0.00041,0.019,0.026,0.026,0.0093,0.049,0.049,0.04,1.9e-06,2e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20790000,0.71,0.0004,-0.012,0.71,-0.0034,-0.011,0.015,0.0014,-0.0025,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0012,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00041,0.0004,0.019,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-06,1.8e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20890000,0.71,0.00038,-0.012,0.71,-0.0038,-0.014,0.014,0.001,-0.0038,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0012,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00041,0.00041,0.019,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-06,1.8e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20990000,0.71,0.00039,-0.012,0.71,-0.004,-0.014,0.015,0.0026,-0.0031,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00098,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0004,0.0004,0.019,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-06,1.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +21090000,0.71,0.00039,-0.012,0.71,-0.0042,-0.017,0.015,0.0022,-0.0047,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00098,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0004,0.0004,0.019,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-06,1.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +21190000,0.71,0.00043,-0.012,0.71,-0.0034,-0.016,0.014,0.0037,-0.0038,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00073,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00039,0.019,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-06,1.5e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21290000,0.71,0.00047,-0.012,0.71,-0.004,-0.018,0.016,0.0034,-0.0055,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00073,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0004,0.0004,0.019,0.024,0.024,0.0086,0.048,0.048,0.039,1.5e-06,1.5e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21390000,0.71,0.00051,-0.012,0.71,-0.0048,-0.017,0.016,0.0028,-0.0034,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00035,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00039,0.019,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21490000,0.71,0.00052,-0.012,0.71,-0.0053,-0.018,0.015,0.0023,-0.0052,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00036,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00039,0.019,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21590000,0.71,0.00055,-0.012,0.71,-0.0058,-0.015,0.015,0.0019,-0.0032,-3.7e+02,-0.0014,-0.006,4.4e-05,-4.5e-06,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00038,0.02,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21690000,0.71,0.00056,-0.012,0.71,-0.0057,-0.017,0.017,0.0013,-0.0048,-3.7e+02,-0.0014,-0.006,4.4e-05,-5.7e-06,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00039,0.02,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21790000,0.71,0.00057,-0.012,0.71,-0.0063,-0.011,0.015,7.2e-05,-0.00077,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00052,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00038,0.00038,0.02,0.021,0.021,0.0082,0.042,0.042,0.038,1.2e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21890000,0.71,0.00058,-0.012,0.71,-0.0063,-0.012,0.016,-0.00057,-0.0019,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00051,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00038,0.00038,0.02,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21990000,0.71,0.00063,-0.012,0.71,-0.0068,-0.0091,0.016,-0.0015,0.0015,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00096,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00038,0.00038,0.02,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-06,1.2e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22090000,0.71,0.00064,-0.012,0.71,-0.0072,-0.0083,0.015,-0.0022,0.0006,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00095,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00038,0.00038,0.02,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-06,1.2e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22190000,0.71,0.00061,-0.012,0.71,-0.007,-0.0074,0.015,-0.0018,0.00056,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.001,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.02,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-06,1.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22290000,0.71,0.00065,-0.012,0.71,-0.0083,-0.0081,0.015,-0.0026,-0.00022,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.001,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00038,0.00037,0.02,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-06,1.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22390000,0.71,0.00063,-0.012,0.71,-0.0089,-0.0076,0.017,-0.0022,-0.0002,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0011,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.02,0.019,0.019,0.0079,0.042,0.042,0.037,1e-06,1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22490000,0.71,0.00063,-0.012,0.71,-0.0096,-0.0075,0.018,-0.0031,-0.00098,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0011,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.02,0.021,0.021,0.0079,0.047,0.047,0.037,1e-06,1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22590000,0.71,0.00062,-0.012,0.71,-0.0093,-0.007,0.017,-0.0034,0.00011,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.02,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-07,9.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22690000,0.71,0.00065,-0.012,0.71,-0.011,-0.0068,0.018,-0.0044,-0.00058,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.02,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-07,9.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22790000,0.71,0.00063,-0.012,0.71,-0.011,-0.0056,0.019,-0.0055,-0.00046,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00036,0.02,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-07,9.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22890000,0.71,0.00064,-0.012,0.71,-0.012,-0.0052,0.021,-0.0067,-0.001,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.02,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-07,9.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22990000,0.71,0.00063,-0.012,0.71,-0.012,-0.0056,0.022,-0.0074,-0.00089,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0014,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-07,8.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23090000,0.71,0.00059,-0.012,0.71,-0.013,-0.0056,0.022,-0.0087,-0.0014,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0014,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00036,0.02,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-07,8.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23190000,0.71,0.00066,-0.012,0.71,-0.015,-0.0066,0.024,-0.012,-0.0013,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0015,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-07,8.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23290000,0.71,0.0006,-0.012,0.71,-0.015,-0.0078,0.024,-0.013,-0.002,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0014,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00036,0.02,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-07,8.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23390000,0.71,0.00069,-0.012,0.71,-0.016,-0.0081,0.022,-0.016,-0.0018,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0015,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-07,7.8e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23490000,0.71,0.0031,-0.0096,0.71,-0.023,-0.0089,-0.012,-0.018,-0.0026,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0015,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00036,0.02,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-07,7.8e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23590000,0.71,0.0083,-0.0018,0.71,-0.034,-0.0077,-0.044,-0.017,-0.0013,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0017,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00035,0.02,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-07,7.4e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23690000,0.71,0.0079,0.004,0.71,-0.065,-0.016,-0.094,-0.021,-0.0025,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0017,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00036,0.02,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-07,7.4e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23790000,0.71,0.005,0.00066,0.71,-0.089,-0.028,-0.15,-0.021,-0.0018,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.002,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00035,0.02,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-07,7.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23890000,0.71,0.0024,-0.0054,0.71,-0.11,-0.037,-0.2,-0.03,-0.0051,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-07,7.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23990000,0.7,0.00098,-0.01,0.71,-0.11,-0.04,-0.25,-0.034,-0.0083,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0021,0.0059,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00035,0.02,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-07,6.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24090000,0.7,0.0023,-0.0088,0.71,-0.11,-0.04,-0.3,-0.045,-0.012,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0021,0.0059,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00035,0.02,0.018,0.019,0.0078,0.045,0.045,0.035,6.8e-07,6.8e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24190000,0.7,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.046,-0.014,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0024,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00034,0.02,0.017,0.017,0.0077,0.04,0.04,0.035,6.5e-07,6.4e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24290000,0.7,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.019,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0024,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00034,0.02,0.018,0.018,0.0078,0.045,0.045,0.036,6.5e-07,6.5e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24390000,0.7,0.0039,-0.0059,0.71,-0.13,-0.052,-0.46,-0.064,-0.03,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.002,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00034,0.02,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-07,6.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24490000,0.7,0.0047,-0.0018,0.71,-0.14,-0.058,-0.51,-0.077,-0.036,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.002,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-07,6.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24590000,0.7,0.0052,0.0019,0.71,-0.16,-0.069,-0.56,-0.081,-0.045,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.002,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-07,5.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24690000,0.7,0.0052,0.0028,0.71,-0.18,-0.083,-0.64,-0.098,-0.052,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.002,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-07,5.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24790000,0.7,0.0049,0.0014,0.71,-0.2,-0.095,-0.72,-0.1,-0.063,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0024,0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.017,0.017,0.0078,0.04,0.04,0.035,5.7e-07,5.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24890000,0.7,0.0067,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.074,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0024,0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-07,5.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24990000,0.7,0.0085,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.0033,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00034,0.02,0.016,0.017,0.0078,0.04,0.04,0.035,5.5e-07,5.5e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25090000,0.7,0.0088,0.0041,0.71,-0.27,-0.13,-0.85,-0.15,-0.093,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.0033,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.018,0.019,0.0079,0.044,0.044,0.035,5.5e-07,5.5e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25190000,0.7,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.0029,0.0013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00033,0.02,0.016,0.017,0.0078,0.04,0.04,0.035,5.3e-07,5.3e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25290000,0.7,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.0029,0.0013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00034,0.02,0.018,0.019,0.0079,0.044,0.044,0.035,5.3e-07,5.3e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25390000,0.7,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0032,-0.00021,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00035,0.02,0.016,0.017,0.0078,0.04,0.04,0.035,5.1e-07,5.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25490000,0.7,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0032,-0.0002,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00036,0.02,0.017,0.019,0.0079,0.044,0.044,0.035,5.1e-07,5.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25590000,0.7,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.0029,-0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00035,0.02,0.016,0.018,0.0079,0.04,0.04,0.035,4.9e-07,4.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25690000,0.7,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.0029,-0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00037,0.02,0.017,0.02,0.0079,0.044,0.044,0.035,4.9e-07,4.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25790000,0.7,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0037,-0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00039,0.019,0.016,0.019,0.0079,0.04,0.04,0.035,4.8e-07,4.8e-07,6.3e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 +25890000,0.7,0.017,0.028,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0037,-0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00039,0.019,0.017,0.021,0.008,0.044,0.044,0.035,4.8e-07,4.8e-07,6.3e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 +25990000,0.7,0.016,0.025,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-0.0011,-0.0059,3.7e-05,0.0034,-0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00037,0.019,0.016,0.02,0.0079,0.04,0.04,0.035,4.6e-07,4.7e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26090000,0.7,0.021,0.035,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-0.0011,-0.0059,3.7e-05,0.0034,-0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00042,0.019,0.017,0.023,0.008,0.044,0.044,0.035,4.6e-07,4.7e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26190000,0.7,0.023,0.045,0.71,-0.77,-0.4,-1.3,-0.53,-0.42,-3.7e+02,-0.0011,-0.0059,4e-05,0.0045,-0.0093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00046,0.018,0.016,0.022,0.0079,0.039,0.04,0.035,4.5e-07,4.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26290000,0.7,0.024,0.047,0.71,-0.87,-0.44,-1.3,-0.62,-0.46,-3.7e+02,-0.0011,-0.0059,4e-05,0.0045,-0.0093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00047,0.018,0.017,0.025,0.008,0.044,0.045,0.035,4.5e-07,4.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26390000,0.7,0.023,0.043,0.71,-0.94,-0.49,-1.3,-0.68,-0.55,-3.7e+02,-0.001,-0.0059,3.8e-05,0.0033,-0.011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00044,0.018,0.016,0.024,0.0079,0.039,0.04,0.035,4.4e-07,4.5e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26490000,0.7,0.031,0.059,0.71,-1,-0.53,-1.3,-0.78,-0.6,-3.7e+02,-0.001,-0.0059,3.8e-05,0.0033,-0.011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00056,0.018,0.018,0.027,0.008,0.043,0.045,0.035,4.4e-07,4.5e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26590000,0.7,0.037,0.075,0.71,-1.1,-0.59,-1.3,-0.82,-0.67,-3.7e+02,-0.00096,-0.0059,4.7e-05,0.0041,-0.015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00067,0.017,0.016,0.027,0.008,0.039,0.041,0.035,4.3e-07,4.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26690000,0.7,0.038,0.078,0.71,-1.3,-0.65,-1.3,-0.94,-0.73,-3.7e+02,-0.00096,-0.0059,4.7e-05,0.0041,-0.015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.0007,0.017,0.018,0.032,0.008,0.043,0.046,0.035,4.3e-07,4.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26790000,0.7,0.036,0.072,0.71,-1.4,-0.74,-1.3,-1,-0.86,-3.7e+02,-0.00092,-0.006,2.9e-05,0.0021,-0.017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.0006,0.015,0.017,0.031,0.008,0.039,0.041,0.035,4.2e-07,4.4e-07,6.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26890000,0.7,0.044,0.094,0.7,-1.5,-0.8,-1.3,-1.2,-0.93,-3.7e+02,-0.00092,-0.006,2.9e-05,0.002,-0.017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00081,0.015,0.019,0.037,0.0081,0.043,0.046,0.035,4.2e-07,4.4e-07,6.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26990000,0.7,0.051,0.12,0.7,-1.7,-0.88,-1.3,-1.2,-1,-3.7e+02,-0.0008,-0.006,3e-05,0.0029,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00096,0.014,0.018,0.036,0.008,0.039,0.042,0.035,4.1e-07,4.3e-07,6.2e-06,0.028,0.028,0.0005,0.0025,0.0023,0.0025,0.0025,0.0025,0.0025,0,0 +27090000,0.7,0.052,0.12,0.7,-1.9,-0.97,-1.3,-1.4,-1.1,-3.7e+02,-0.0008,-0.006,3e-05,0.0029,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0004,0.001,0.013,0.02,0.045,0.0081,0.043,0.047,0.035,4.1e-07,4.4e-07,6.2e-06,0.028,0.028,0.0005,0.0025,0.0015,0.0025,0.0025,0.0025,0.0025,0,0 +27190000,0.71,0.049,0.11,0.7,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-0.00078,-0.0059,0.00012,0.0028,-0.023,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.0008,0.012,0.02,0.045,0.0081,0.046,0.05,0.035,4.1e-07,4.4e-07,6.1e-06,0.028,0.028,0.0005,0.0025,0.0011,0.0025,0.0025,0.0025,0.0025,0,0 +27290000,0.71,0.043,0.094,0.7,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-0.00078,-0.0059,0.00012,0.0027,-0.023,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00067,0.012,0.022,0.052,0.0081,0.051,0.057,0.035,4.1e-07,4.4e-07,6.1e-06,0.028,0.028,0.0005,0.0025,0.0009,0.0025,0.0025,0.0025,0.0025,0,0 +27390000,0.72,0.037,0.077,0.69,-2.4,-1.1,-1.2,-2,-1.4,-3.7e+02,-0.00071,-0.0059,0.0002,0.0036,-0.025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.0005,0.011,0.021,0.048,0.0081,0.053,0.059,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00074,0.0025,0.0025,0.0025,0.0025,0,0 +27490000,0.72,0.031,0.062,0.69,-2.4,-1.1,-1.2,-2.3,-1.5,-3.7e+02,-0.00071,-0.0059,0.0002,0.0035,-0.025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00043,0.011,0.023,0.052,0.0082,0.058,0.067,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00063,0.0025,0.0025,0.0025,0.0025,0,0 +27590000,0.72,0.026,0.05,0.69,-2.5,-1.1,-1.2,-2.5,-1.6,-3.7e+02,-0.00072,-0.0059,0.00026,0.0024,-0.024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00036,0.0094,0.021,0.045,0.0082,0.061,0.068,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00056,0.0025,0.0025,0.0025,0.0025,0,0 +27690000,0.72,0.026,0.048,0.69,-2.6,-1.1,-1.2,-2.8,-1.7,-3.7e+02,-0.00072,-0.0059,0.00026,0.0023,-0.024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00036,0.0094,0.023,0.046,0.0082,0.067,0.077,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00049,0.0025,0.0025,0.0025,0.0025,0,0 +27790000,0.72,0.026,0.05,0.69,-2.6,-1.1,-1.2,-3.1,-1.8,-3.7e+02,-0.00071,-0.0059,0.0003,0.0016,-0.024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00035,0.0084,0.021,0.04,0.0082,0.069,0.078,0.035,3.9e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00044,0.0025,0.0025,0.0025,0.0025,0,0 +27890000,0.72,0.025,0.048,0.69,-2.6,-1.2,-1.2,-3.3,-1.9,-3.7e+02,-0.00071,-0.0059,0.0003,0.0015,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00035,0.0084,0.023,0.042,0.0083,0.075,0.087,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.0004,0.0025,0.0025,0.0025,0.0025,0,0 +27990000,0.72,0.025,0.044,0.69,-2.7,-1.2,-1.2,-3.6,-2,-3.7e+02,-0.00074,-0.0059,0.00033,0.00041,-0.022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0077,0.022,0.037,0.0083,0.078,0.088,0.035,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00037,0.0025,0.0025,0.0025,0.0025,0,0 +28090000,0.72,0.031,0.057,0.69,-2.7,-1.2,-1.2,-3.9,-2.1,-3.7e+02,-0.00074,-0.0059,0.00033,0.00028,-0.022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00036,0.0077,0.023,0.038,0.0084,0.085,0.097,0.035,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00034,0.0025,0.0025,0.0025,0.0025,0,0 +28190000,0.72,0.036,0.07,0.68,-2.8,-1.2,-0.95,-4.2,-2.2,-3.7e+02,-0.00076,-0.0059,0.00035,-0.00052,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00039,0.0071,0.022,0.034,0.0084,0.087,0.097,0.035,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00032,0.0025,0.0025,0.0025,0.0025,0,0 +28290000,0.73,0.028,0.054,0.68,-2.8,-1.2,-0.089,-4.5,-2.4,-3.7e+02,-0.00076,-0.0059,0.00035,-0.0007,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0072,0.022,0.035,0.0086,0.094,0.11,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.0003,0.0025,0.0025,0.0025,0.0025,0,0 +28390000,0.73,0.011,0.023,0.68,-2.8,-1.2,0.77,-4.8,-2.5,-3.7e+02,-0.00076,-0.0059,0.00035,-0.001,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00031,0.0072,0.023,0.036,0.0087,0.1,0.12,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00028,0.0025,0.0025,0.0025,0.0025,0,0 +28490000,0.73,0.0015,0.0046,0.68,-2.7,-1.2,1.1,-5,-2.6,-3.7e+02,-0.00076,-0.0059,0.00035,-0.0013,-0.019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00032,0.0072,0.024,0.036,0.0088,0.11,0.13,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00026,0.0025,0.0025,0.0025,0.0025,0,0 +28590000,0.73,-0.00034,0.0012,0.69,-2.7,-1.2,0.96,-5.3,-2.7,-3.7e+02,-0.00075,-0.0059,0.00035,-0.0017,-0.018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00032,0.0073,0.025,0.035,0.0089,0.12,0.14,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00025,0.0025,0.0025,0.0025,0.0025,0,0 +28690000,0.73,-0.0011,0.00028,0.69,-2.6,-1.2,0.96,-5.6,-2.8,-3.7e+02,-0.00075,-0.0059,0.00035,-0.0021,-0.017,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0073,0.026,0.035,0.009,0.13,0.15,0.036,3.9e-07,4.5e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00023,0.0025,0.0025,0.0025,0.0025,0,0 +28790000,0.73,-0.0015,9.4e-05,0.68,-2.6,-1.2,0.97,-5.9,-2.9,-3.7e+02,-0.00081,-0.006,0.00038,-0.0039,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.007,0.025,0.03,0.0089,0.13,0.15,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00022,0.0025,0.0025,0.0025,0.0025,0,0 +28890000,0.73,-0.0015,0.00032,0.69,-2.5,-1.2,0.96,-6.1,-3.1,-3.7e+02,-0.00081,-0.006,0.00038,-0.0043,-0.022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.007,0.026,0.03,0.009,0.14,0.16,0.036,3.9e-07,4.5e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00021,0.0025,0.0025,0.0025,0.0025,0,0 +28990000,0.73,-0.0014,0.00081,0.68,-2.5,-1.1,0.95,-6.5,-3.2,-3.7e+02,-0.00089,-0.006,0.0004,-0.0052,-0.03,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.027,0.009,0.14,0.16,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.0002,0.0025,0.0025,0.0025,0.0025,0,0 +29090000,0.73,-0.0013,0.0012,0.68,-2.4,-1.1,0.94,-6.7,-3.3,-3.7e+02,-0.00089,-0.006,0.0004,-0.0057,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.028,0.009,0.15,0.17,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00019,0.0025,0.0025,0.0025,0.0025,0,0 +29190000,0.73,-0.0011,0.0017,0.68,-2.4,-1.1,0.93,-7,-3.4,-3.7e+02,-0.00093,-0.006,0.00041,-0.0067,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0068,0.024,0.025,0.009,0.15,0.17,0.036,3.7e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0 +29290000,0.73,-0.00074,0.0025,0.68,-2.3,-1.1,0.96,-7.3,-3.5,-3.7e+02,-0.00093,-0.006,0.00041,-0.0073,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0068,0.026,0.026,0.0091,0.16,0.18,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0 +29390000,0.73,-0.00021,0.004,0.68,-2.3,-1.1,0.97,-7.6,-3.6,-3.7e+02,-0.00099,-0.006,0.00041,-0.0081,-0.033,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0068,0.024,0.025,0.009,0.16,0.18,0.036,3.7e-07,4.4e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00017,0.0025,0.0025,0.0025,0.0025,0,0 +29490000,0.73,0.00032,0.0051,0.68,-2.2,-1.1,0.97,-7.8,-3.7,-3.7e+02,-0.00099,-0.006,0.00041,-0.0086,-0.032,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0068,0.026,0.026,0.0091,0.17,0.19,0.037,3.7e-07,4.4e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0 +29590000,0.73,0.00073,0.0063,0.68,-2.2,-1.1,0.96,-8.1,-3.8,-3.7e+02,-0.001,-0.006,0.00039,-0.011,-0.033,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.024,0.025,0.009,0.17,0.19,0.036,3.6e-07,4.3e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0 +29690000,0.73,0.001,0.0069,0.68,-2.2,-1.1,0.95,-8.3,-3.9,-3.7e+02,-0.001,-0.006,0.00039,-0.011,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.026,0.0091,0.18,0.2,0.036,3.7e-07,4.3e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0 +29790000,0.73,0.0013,0.0075,0.68,-2.2,-1.1,0.94,-8.6,-4,-3.7e+02,-0.0011,-0.006,0.00038,-0.013,-0.033,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.025,0.0091,0.18,0.2,0.037,3.6e-07,4.2e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0 +29890000,0.73,0.0014,0.0077,0.68,-2.1,-1.1,0.92,-8.8,-4.1,-3.7e+02,-0.0011,-0.006,0.00038,-0.013,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.027,0.0091,0.19,0.21,0.037,3.6e-07,4.3e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0 +29990000,0.73,0.0016,0.0079,0.68,-2.1,-1.1,0.91,-9,-4.2,-3.7e+02,-0.0011,-0.006,0.00035,-0.015,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.026,0.009,0.19,0.21,0.036,3.5e-07,4.2e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0 +30090000,0.73,0.0015,0.0078,0.68,-2.1,-1.1,0.89,-9.2,-4.3,-3.7e+02,-0.0011,-0.006,0.00035,-0.016,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.027,0.0091,0.2,0.22,0.036,3.6e-07,4.2e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 +30190000,0.73,0.0016,0.0077,0.68,-2,-1.1,0.88,-9.5,-4.4,-3.7e+02,-0.0011,-0.0059,0.00032,-0.017,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.026,0.009,0.2,0.22,0.037,3.5e-07,4.1e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 +30290000,0.73,0.0015,0.0075,0.68,-2,-1.1,0.87,-9.7,-4.5,-3.7e+02,-0.0011,-0.0059,0.00032,-0.018,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.028,0.0091,0.21,0.23,0.037,3.5e-07,4.1e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 +30390000,0.73,0.0016,0.0074,0.68,-2,-1,0.85,-9.9,-4.6,-3.7e+02,-0.0012,-0.0059,0.0003,-0.019,-0.027,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.027,0.009,0.21,0.23,0.036,3.4e-07,4e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0 +30490000,0.73,0.0014,0.0071,0.68,-2,-1,0.83,-10,-4.7,-3.7e+02,-0.0012,-0.0059,0.0003,-0.019,-0.027,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.029,0.0091,0.22,0.24,0.037,3.4e-07,4e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0 +30590000,0.73,0.0014,0.0068,0.68,-1.9,-1,0.79,-10,-4.8,-3.7e+02,-0.0012,-0.0059,0.00027,-0.02,-0.026,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0068,0.025,0.028,0.009,0.22,0.24,0.037,3.4e-07,3.9e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0 +30690000,0.73,0.0012,0.0065,0.68,-1.9,-1,0.79,-11,-4.9,-3.7e+02,-0.0012,-0.0059,0.00027,-0.021,-0.025,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0068,0.026,0.03,0.009,0.23,0.25,0.037,3.4e-07,3.9e-07,5.9e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 +30790000,0.73,0.0013,0.0062,0.68,-1.9,-1,0.78,-11,-5,-3.7e+02,-0.0012,-0.0059,0.00023,-0.022,-0.025,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0067,0.025,0.029,0.009,0.23,0.25,0.037,3.3e-07,3.8e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 +30890000,0.73,0.0011,0.0058,0.68,-1.9,-1,0.77,-11,-5.1,-3.7e+02,-0.0012,-0.0059,0.00023,-0.022,-0.023,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0067,0.026,0.031,0.009,0.24,0.26,0.037,3.3e-07,3.8e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 +30990000,0.73,0.0011,0.0053,0.68,-1.8,-1,0.76,-11,-5.2,-3.7e+02,-0.0013,-0.0059,0.00019,-0.023,-0.023,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0066,0.025,0.03,0.0089,0.24,0.26,0.036,3.3e-07,3.7e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0 +31090000,0.73,0.00088,0.0048,0.68,-1.8,-1,0.75,-11,-5.3,-3.7e+02,-0.0013,-0.0059,0.00019,-0.023,-0.021,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0067,0.026,0.032,0.009,0.25,0.27,0.037,3.3e-07,3.7e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0 +31190000,0.73,0.00089,0.0045,0.68,-1.8,-0.99,0.73,-12,-5.4,-3.7e+02,-0.0013,-0.0059,0.00016,-0.025,-0.019,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0065,0.025,0.03,0.0088,0.25,0.27,0.037,3.2e-07,3.6e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0 +31290000,0.73,0.00064,0.004,0.68,-1.8,-0.99,0.74,-12,-5.5,-3.7e+02,-0.0013,-0.0059,0.00016,-0.025,-0.017,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0065,0.026,0.032,0.0089,0.26,0.28,0.037,3.2e-07,3.6e-07,5.8e-06,0.027,0.026,0.0005,0.0025,9.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +31390000,0.73,0.00059,0.0035,0.68,-1.7,-0.98,0.73,-12,-5.6,-3.7e+02,-0.0013,-0.0059,0.00013,-0.026,-0.015,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0064,0.025,0.031,0.0088,0.25,0.28,0.036,3.2e-07,3.5e-07,5.8e-06,0.027,0.026,0.0005,0.0025,9.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +31490000,0.73,0.00036,0.0029,0.68,-1.7,-0.98,0.73,-12,-5.7,-3.7e+02,-0.0013,-0.0059,0.00013,-0.027,-0.014,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0064,0.026,0.033,0.0088,0.27,0.29,0.037,3.2e-07,3.5e-07,5.8e-06,0.027,0.026,0.0005,0.0025,9.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +31590000,0.73,0.0004,0.0025,0.69,-1.7,-0.96,0.72,-12,-5.7,-3.7e+02,-0.0013,-0.0058,9.2e-05,-0.027,-0.012,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0062,0.025,0.031,0.0087,0.26,0.29,0.037,3.1e-07,3.4e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +31690000,0.73,0.00013,0.0019,0.69,-1.7,-0.95,0.73,-13,-5.8,-3.7e+02,-0.0013,-0.0058,9.1e-05,-0.028,-0.011,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0063,0.027,0.033,0.0088,0.28,0.3,0.037,3.1e-07,3.4e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +31790000,0.73,2.9e-05,0.0012,0.69,-1.6,-0.94,0.72,-13,-5.9,-3.7e+02,-0.0014,-0.0058,5.4e-05,-0.028,-0.0093,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0061,0.025,0.031,0.0087,0.27,0.3,0.037,3.1e-07,3.3e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +31890000,0.73,-0.00024,0.00056,0.69,-1.6,-0.93,0.72,-13,-6,-3.7e+02,-0.0014,-0.0058,5.4e-05,-0.029,-0.008,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0061,0.027,0.034,0.0087,0.29,0.31,0.037,3.1e-07,3.3e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +31990000,0.73,-0.00028,6.4e-05,0.69,-1.6,-0.91,0.71,-13,-6.1,-3.7e+02,-0.0014,-0.0058,2e-05,-0.03,-0.0061,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0059,0.025,0.032,0.0086,0.28,0.31,0.036,3e-07,3.2e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +32090000,0.73,-0.00059,-0.00064,0.69,-1.5,-0.91,0.72,-13,-6.2,-3.7e+02,-0.0014,-0.0058,2e-05,-0.03,-0.0045,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0059,0.027,0.034,0.0087,0.29,0.32,0.037,3.1e-07,3.3e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +32190000,0.72,-0.00071,-0.0015,0.69,-1.5,-0.89,0.72,-13,-6.3,-3.7e+02,-0.0014,-0.0058,-1.2e-05,-0.031,-0.0023,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0058,0.025,0.032,0.0086,0.29,0.32,0.036,3e-07,3.2e-07,5.7e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32290000,0.72,-0.00097,-0.0022,0.69,-1.5,-0.89,0.71,-14,-6.3,-3.7e+02,-0.0014,-0.0058,-1.2e-05,-0.032,-0.00072,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0058,0.026,0.034,0.0086,0.3,0.33,0.037,3e-07,3.2e-07,5.7e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32390000,0.72,-0.0011,-0.0028,0.69,-1.5,-0.87,0.71,-14,-6.4,-3.7e+02,-0.0014,-0.0058,-3.5e-05,-0.032,0.00022,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00034,0.0056,0.025,0.032,0.0085,0.3,0.33,0.037,3e-07,3.1e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32490000,0.72,-0.0012,-0.0031,0.69,-1.4,-0.86,0.72,-14,-6.5,-3.7e+02,-0.0014,-0.0058,-3.5e-05,-0.032,0.0014,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0056,0.026,0.034,0.0086,0.31,0.34,0.037,3e-07,3.1e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32590000,0.72,-0.0011,-0.0033,0.69,-1.4,-0.85,0.71,-14,-6.6,-3.7e+02,-0.0014,-0.0058,-5.7e-05,-0.032,0.0022,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.0054,0.025,0.032,0.0084,0.31,0.34,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32690000,0.72,-0.0012,-0.0034,0.69,-1.4,-0.84,0.71,-14,-6.7,-3.7e+02,-0.0014,-0.0058,-5.7e-05,-0.033,0.0028,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00034,0.0055,0.026,0.034,0.0085,0.32,0.35,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32790000,0.72,-0.001,-0.0034,0.69,-1.3,-0.82,0.71,-14,-6.7,-3.7e+02,-0.0014,-0.0058,-7.8e-05,-0.033,0.0038,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.0053,0.025,0.032,0.0084,0.32,0.35,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32890000,0.72,-0.00095,-0.0033,0.69,-1.3,-0.82,0.71,-14,-6.8,-3.7e+02,-0.0014,-0.0058,-7.8e-05,-0.033,0.0049,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.0053,0.026,0.034,0.0084,0.33,0.36,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32990000,0.72,-0.00074,-0.0033,0.69,-1.3,-0.8,0.7,-15,-6.9,-3.7e+02,-0.0014,-0.0058,-9.7e-05,-0.034,0.0063,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.0051,0.025,0.032,0.0083,0.33,0.36,0.036,2.9e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +33090000,0.72,-0.00078,-0.0033,0.69,-1.3,-0.8,0.7,-15,-7,-3.7e+02,-0.0014,-0.0058,-9.7e-05,-0.034,0.0068,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.0052,0.026,0.034,0.0084,0.34,0.37,0.036,2.9e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +33190000,0.72,0.0027,-0.0024,0.7,-1.2,-0.78,0.64,-15,-7,-3.7e+02,-0.0015,-0.0057,-0.00012,-0.034,0.0076,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.005,0.025,0.031,0.0083,0.34,0.37,0.036,2.8e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +33290000,0.67,0.015,-0.0017,0.75,-1.2,-0.77,0.62,-15,-7.1,-3.7e+02,-0.0015,-0.0057,-0.00012,-0.034,0.008,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.005,0.026,0.033,0.0083,0.35,0.38,0.036,2.8e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0.0025,9.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33390000,0.56,0.013,-0.0019,0.83,-1.2,-0.75,0.81,-15,-7.2,-3.7e+02,-0.0015,-0.0057,-0.00013,-0.034,0.009,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00029,0.00033,0.0049,0.025,0.03,0.0083,0.35,0.38,0.036,2.8e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33490000,0.43,0.0064,0.00074,0.9,-1.2,-0.75,0.83,-15,-7.3,-3.7e+02,-0.0015,-0.0057,-0.00013,-0.034,0.0091,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.0049,0.026,0.032,0.0081,0.36,0.39,0.036,2.8e-07,2.9e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33590000,0.27,0.00058,-0.0017,0.96,-1.2,-0.74,0.79,-15,-7.3,-3.7e+02,-0.0015,-0.0057,-0.00014,-0.034,0.0091,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00032,0.0048,0.026,0.031,0.0078,0.35,0.39,0.036,2.8e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33690000,0.1,-0.0027,-0.0046,0.99,-1.1,-0.74,0.8,-15,-7.4,-3.7e+02,-0.0015,-0.0057,-0.00014,-0.034,0.0091,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00031,0.0049,0.028,0.035,0.0076,0.37,0.4,0.036,2.8e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33790000,-0.067,-0.0042,-0.0065,1,-1.1,-0.72,0.78,-16,-7.5,-3.7e+02,-0.0015,-0.0057,-0.00016,-0.034,0.0091,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00029,0.0048,0.028,0.034,0.0074,0.36,0.4,0.036,2.7e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33890000,-0.23,-0.0053,-0.0072,0.97,-1,-0.7,0.77,-16,-7.5,-3.7e+02,-0.0015,-0.0057,-0.00016,-0.034,0.0091,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00029,0.0048,0.032,0.039,0.0072,0.38,0.41,0.036,2.7e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33990000,-0.38,-0.0035,-0.011,0.92,-0.97,-0.66,0.74,-16,-7.6,-3.7e+02,-0.0015,-0.0057,-0.00019,-0.034,0.0091,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00029,0.0047,0.032,0.039,0.007,0.37,0.41,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34090000,-0.49,-0.0024,-0.013,0.87,-0.92,-0.61,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00019,-0.034,0.0091,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00029,0.0047,0.036,0.044,0.0069,0.39,0.42,0.036,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34190000,-0.56,-0.0017,-0.011,0.83,-0.9,-0.57,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.0002,-0.037,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00028,0.00028,0.0046,0.037,0.043,0.0067,0.38,0.42,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34290000,-0.6,-0.0026,-0.0085,0.8,-0.85,-0.52,0.74,-16,-7.8,-3.7e+02,-0.0015,-0.0057,-0.0002,-0.037,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00028,0.00028,0.0046,0.043,0.05,0.0066,0.39,0.43,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34390000,-0.63,-0.0027,-0.0061,0.78,-0.84,-0.48,0.73,-16,-7.9,-3.7e+02,-0.0016,-0.0057,-0.00022,-0.041,0.016,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00026,0.00026,0.0045,0.042,0.048,0.0065,0.39,0.43,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34490000,-0.65,-0.0036,-0.004,0.76,-0.79,-0.44,0.73,-16,-7.9,-3.7e+02,-0.0016,-0.0057,-0.00022,-0.041,0.016,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00025,0.00027,0.0045,0.049,0.056,0.0064,0.4,0.44,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34590000,-0.66,-0.003,-0.003,0.76,-0.79,-0.42,0.73,-17,-8,-3.7e+02,-0.0016,-0.0057,-0.00022,-0.051,0.026,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00023,0.00024,0.0044,0.048,0.053,0.0063,0.4,0.44,0.034,2.6e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,7.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34690000,-0.66,-0.0034,-0.0022,0.75,-0.73,-0.38,0.73,-17,-8,-3.7e+02,-0.0016,-0.0057,-0.00022,-0.051,0.026,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00023,0.00024,0.0044,0.055,0.061,0.0063,0.41,0.45,0.034,2.7e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,7.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34790000,-0.67,-0.0023,-0.002,0.75,-0.74,-0.37,0.72,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00022,-0.061,0.037,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00021,0.00022,0.0044,0.052,0.056,0.0062,0.41,0.45,0.034,2.6e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34890000,-0.67,-0.0023,-0.0019,0.74,-0.69,-0.34,0.72,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00022,-0.061,0.037,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00021,0.00022,0.0044,0.059,0.064,0.0062,0.42,0.46,0.034,2.6e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,6.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34990000,-0.67,-0.0086,-0.0047,0.74,0.33,0.25,-0.13,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00022,-0.074,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0002,0.0043,0.059,0.07,0.0068,0.42,0.46,0.034,2.6e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35090000,-0.67,-0.0087,-0.0047,0.74,0.46,0.27,-0.19,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00022,-0.074,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0002,0.0044,0.064,0.077,0.0068,0.43,0.46,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35190000,-0.67,-0.0087,-0.0048,0.74,0.48,0.3,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00022,-0.074,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0002,0.0044,0.07,0.083,0.0067,0.44,0.47,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35290000,-0.67,-0.0087,-0.0048,0.74,0.5,0.34,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00022,-0.074,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0002,0.0044,0.075,0.089,0.0066,0.46,0.48,0.033,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35390000,-0.67,-0.0088,-0.0048,0.74,0.53,0.37,-0.18,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00022,-0.074,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0002,0.0044,0.081,0.095,0.0066,0.47,0.49,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35490000,-0.67,-0.0088,-0.0048,0.74,0.55,0.4,-0.18,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00022,-0.074,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0002,0.0044,0.088,0.1,0.0065,0.49,0.51,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35590000,-0.67,-0.0058,-0.005,0.74,0.44,0.33,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.0002,-0.074,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00017,0.0042,0.07,0.077,0.0062,0.48,0.5,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,6.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35690000,-0.67,-0.0058,-0.005,0.74,0.46,0.36,-0.19,-17,-8,-3.7e+02,-0.0017,-0.0058,-0.0002,-0.074,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00017,0.0042,0.075,0.082,0.0061,0.5,0.52,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,6.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35790000,-0.67,-0.0036,-0.0051,0.74,0.38,0.3,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.076,0.053,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00014,0.00015,0.0041,0.062,0.066,0.0059,0.49,0.51,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35890000,-0.67,-0.0036,-0.0051,0.74,0.39,0.33,-0.19,-17,-8,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.076,0.053,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00014,0.00015,0.0041,0.067,0.072,0.0059,0.5,0.53,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35990000,-0.67,-0.0017,-0.0051,0.74,0.32,0.28,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.083,0.059,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00012,0.00013,0.004,0.058,0.061,0.0057,0.5,0.52,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36090000,-0.67,-0.0018,-0.0051,0.74,0.33,0.3,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.083,0.059,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00012,0.00013,0.0041,0.063,0.066,0.0057,0.51,0.53,0.032,2.7e-07,2.8e-07,5.4e-06,0.025,0.023,0.0005,0.0025,5.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36190000,-0.67,-0.0004,-0.005,0.74,0.27,0.26,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.094,0.068,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00011,0.00012,0.004,0.055,0.057,0.0055,0.5,0.53,0.032,2.7e-07,2.8e-07,5.4e-06,0.024,0.023,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36290000,-0.67,-0.00052,-0.005,0.74,0.28,0.28,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.094,0.069,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00011,0.00012,0.004,0.061,0.063,0.0056,0.52,0.54,0.032,2.7e-07,2.8e-07,5.4e-06,0.024,0.023,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36390000,-0.67,0.00054,-0.0049,0.74,0.24,0.24,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.11,0.078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,9.8e-05,0.00011,0.004,0.054,0.055,0.0055,0.51,0.54,0.032,2.8e-07,2.8e-07,5.4e-06,0.024,0.022,0.0005,0.0025,5.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36490000,-0.67,0.00044,-0.0049,0.74,0.24,0.26,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.11,0.078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,9.8e-05,0.00011,0.0041,0.059,0.061,0.0055,0.53,0.55,0.032,2.8e-07,2.8e-07,5.4e-06,0.024,0.022,0.0005,0.0025,5.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36590000,-0.67,0.0012,-0.0048,0.74,0.2,0.22,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.12,0.088,-0.092,0.37,0.0037,0.025,0,0,0,0,0,9e-05,0.0001,0.0041,0.053,0.054,0.0055,0.52,0.55,0.031,2.8e-07,2.8e-07,5.4e-06,0.023,0.022,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36690000,-0.67,0.0012,-0.0047,0.74,0.21,0.24,-0.17,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.12,0.088,-0.092,0.37,0.0037,0.025,0,0,0,0,0,9e-05,0.0001,0.0041,0.058,0.06,0.0055,0.54,0.56,0.031,2.8e-07,2.8e-07,5.4e-06,0.023,0.022,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36790000,-0.67,0.0018,-0.0046,0.74,0.17,0.21,-0.17,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.13,0.098,-0.093,0.37,0.0037,0.025,0,0,0,0,0,8.4e-05,9.7e-05,0.0041,0.052,0.053,0.0055,0.53,0.56,0.031,2.8e-07,2.8e-07,5.4e-06,0.022,0.021,0.0005,0.0025,5.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36890000,-0.67,0.0017,-0.0046,0.74,0.17,0.22,-0.16,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.13,0.098,-0.093,0.37,0.0037,0.025,0,0,0,0,0,8.4e-05,9.8e-05,0.0041,0.057,0.059,0.0056,0.55,0.57,0.031,2.8e-07,2.8e-07,5.4e-06,0.022,0.021,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36990000,-0.67,0.0022,-0.0044,0.74,0.14,0.19,-0.16,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.15,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,8e-05,9.3e-05,0.0041,0.051,0.053,0.0056,0.54,0.57,0.031,2.8e-07,2.8e-07,5.4e-06,0.022,0.02,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37090000,-0.67,0.0021,-0.0043,0.74,0.15,0.2,-0.15,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.15,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,8e-05,9.3e-05,0.0041,0.056,0.058,0.0057,0.55,0.58,0.031,2.8e-07,2.9e-07,5.4e-06,0.022,0.02,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37190000,-0.67,0.0025,-0.0042,0.74,0.12,0.17,-0.14,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.16,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,7.7e-05,8.9e-05,0.0041,0.051,0.052,0.0057,0.55,0.58,0.031,2.8e-07,2.9e-07,5.4e-06,0.021,0.019,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37290000,-0.67,0.0024,-0.0042,0.74,0.12,0.18,-0.14,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.16,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,7.7e-05,9e-05,0.0041,0.055,0.057,0.0059,0.56,0.59,0.031,2.8e-07,2.9e-07,5.4e-06,0.021,0.019,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37390000,-0.67,0.0027,-0.004,0.74,0.097,0.15,-0.13,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.17,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,7.4e-05,8.7e-05,0.0042,0.05,0.051,0.0059,0.56,0.59,0.031,2.9e-07,2.9e-07,5.4e-06,0.02,0.019,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37490000,-0.67,0.0026,-0.004,0.74,0.096,0.16,-0.12,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.17,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,7.5e-05,8.7e-05,0.0042,0.054,0.056,0.006,0.57,0.6,0.031,2.9e-07,2.9e-07,5.4e-06,0.02,0.019,0.0005,0.0025,4.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37590000,-0.67,0.0028,-0.0039,0.74,0.076,0.14,-0.12,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.18,0.13,-0.095,0.37,0.0037,0.025,0,0,0,0,0,7.3e-05,8.5e-05,0.0042,0.049,0.05,0.0061,0.57,0.6,0.031,2.9e-07,2.9e-07,5.4e-06,0.019,0.018,0.0005,0.0025,4.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37690000,-0.67,0.0027,-0.0039,0.74,0.074,0.14,-0.11,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.18,0.13,-0.095,0.37,0.0037,0.025,0,0,0,0,0,7.3e-05,8.5e-05,0.0042,0.053,0.055,0.0062,0.58,0.61,0.031,2.9e-07,2.9e-07,5.4e-06,0.019,0.018,0.0005,0.0025,4.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37790000,-0.67,0.0028,-0.0038,0.74,0.058,0.12,-0.1,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.19,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.4e-05,0.0042,0.048,0.049,0.0063,0.58,0.61,0.03,2.9e-07,2.9e-07,5.4e-06,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37890000,-0.67,0.0028,-0.0038,0.74,0.055,0.13,-0.093,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.19,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.4e-05,0.0042,0.052,0.053,0.0064,0.59,0.62,0.03,2.9e-07,2.9e-07,5.4e-06,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37990000,-0.67,0.0029,-0.0038,0.74,0.041,0.11,-0.084,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.2,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,8.3e-05,0.0042,0.047,0.048,0.0065,0.59,0.62,0.031,2.9e-07,2.9e-07,5.4e-06,0.017,0.016,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38090000,-0.67,0.0028,-0.0038,0.74,0.037,0.11,-0.074,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.2,0.13,-0.097,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.3e-05,0.0042,0.05,0.052,0.0066,0.6,0.63,0.031,2.9e-07,3e-07,5.4e-06,0.017,0.016,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38190000,-0.67,0.0029,-0.0036,0.74,0.024,0.096,-0.066,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,8.2e-05,0.0042,0.045,0.047,0.0067,0.6,0.63,0.031,2.9e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38290000,-0.67,0.0028,-0.0036,0.74,0.021,0.097,-0.059,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.3e-05,0.0042,0.049,0.05,0.0068,0.61,0.64,0.031,2.9e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38390000,-0.67,0.0029,-0.0035,0.74,0.013,0.084,-0.051,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.21,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,8.2e-05,0.0042,0.044,0.045,0.0069,0.61,0.64,0.031,2.9e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38490000,-0.67,0.0028,-0.0035,0.74,0.0096,0.086,-0.044,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.21,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.3e-05,0.0043,0.048,0.049,0.007,0.62,0.65,0.031,3e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38590000,-0.67,0.0029,-0.0034,0.74,0.0052,0.074,-0.037,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.2e-05,0.0043,0.043,0.044,0.0071,0.62,0.65,0.031,3e-07,3e-07,5.4e-06,0.015,0.014,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38690000,-0.67,0.0028,-0.0034,0.74,0.00079,0.074,-0.03,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.3e-05,0.0043,0.046,0.048,0.0072,0.63,0.66,0.031,3e-07,3e-07,5.4e-06,0.015,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38790000,-0.67,0.0028,-0.0033,0.74,-0.0042,0.062,-0.022,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00019,-0.22,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.3e-05,0.0043,0.042,0.043,0.0073,0.63,0.66,0.031,3e-07,3e-07,5.4e-06,0.014,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38890000,-0.67,0.0026,-0.0034,0.74,-0.014,0.051,0.48,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00019,-0.22,0.14,-0.1,0.37,0.0037,0.025,0,0,0,0,0,7.3e-05,8.3e-05,0.0043,0.045,0.046,0.0075,0.64,0.67,0.032,3e-07,3e-07,5.4e-06,0.014,0.014,0.0005,0.0025,4.2e-05,0.0025,0.0025,0.0025,0.0025,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 85ba22c8011f..5c606d3b7a3d 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -1,351 +1,351 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23] -10000,1,-0.011,-0.01,0.00023,0.00033,-0.00013,-0.01,1e-05,-3.8e-06,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,5.7e-07,0.0025,0.0025,4.3e-05,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -90000,1,-0.011,-0.01,0.00033,-0.001,-0.0031,-0.024,-3.8e-05,-0.00013,-0.0021,0,0,0,0,0,0,0,0,0,0,0,0,0,0,6.2e-07,0.0026,0.0026,0.00011,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -190000,1,-0.012,-0.011,0.00044,-0.0023,-0.003,-0.037,-0.00017,-0.00043,-0.017,4.7e-10,-5e-10,-1.5e-11,0,0,-6.8e-08,0,0,0,0,0,0,0,0,6.7e-07,0.0027,0.0027,0.00023,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -290000,1,-0.012,-0.011,0.00045,-0.0033,-0.0044,-0.046,-0.00024,-0.00025,-0.018,3.9e-09,-5.9e-09,-4.7e-10,0,0,-2.9e-06,0,0,0,0,0,0,0,0,7.4e-07,0.0029,0.0029,0.00019,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -390000,1,-0.012,-0.011,0.0005,-0.0025,-0.006,-0.063,-0.00056,-0.00072,-0.013,-7.2e-09,-5.8e-09,-1.3e-09,0,0,8.8e-06,0,0,0,0,0,0,0,0,8.2e-07,0.0031,0.0031,0.0003,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -490000,1,-0.012,-0.012,0.00056,-0.0007,-0.0063,-0.069,-0.00015,-0.00047,-0.011,-1.2e-06,7.5e-07,-1.7e-07,0,0,1.6e-05,0,0,0,0,0,0,0,0,9.2e-07,0.0033,0.0034,0.00018,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -590000,1,-0.012,-0.012,0.00058,-0.002,-0.009,-0.12,-0.00028,-0.0013,-0.029,-1.3e-06,7.8e-07,-1.8e-07,0,0,6.4e-05,0,0,0,0,0,0,0,0,1e-06,0.0037,0.0037,0.00025,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -690000,1,-0.012,-0.012,0.00062,5.3e-05,-0.0089,-0.05,-8e-05,-0.00079,-0.0088,-5.6e-06,1.6e-06,-5.2e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,1.2e-06,0.004,0.004,0.00015,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -790000,1,-0.012,-0.012,0.00062,0.0022,-0.011,-0.054,-2.3e-05,-0.0017,-0.011,-5.4e-06,1.7e-06,-5.1e-07,0,0,-0.00013,0,0,0,0,0,0,0,0,1.3e-06,0.0044,0.0044,0.0002,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.0012,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -890000,1,-0.012,-0.013,0.00063,0.0031,-0.0085,-0.093,0.00015,-0.0011,-0.031,-2.2e-05,1.2e-06,-7.5e-07,0,0,-3.3e-05,0,0,0,0,0,0,0,0,1.5e-06,0.0048,0.0048,0.00013,1.3,1.3,1.3,0.2,0.2,0.25,0.0099,0.0099,0.00067,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -990000,1,-0.012,-0.013,0.0006,0.006,-0.0099,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1.2e-06,-7.5e-07,0,0,1.3e-05,0,0,0,0,0,0,0,0,1.7e-06,0.0053,0.0053,0.00016,1.5,1.5,0.95,0.3,0.3,0.23,0.0099,0.0099,0.00067,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1090000,1,-0.012,-0.013,0.00056,0.011,-0.013,-0.13,0.00077,-0.0015,-0.062,-6e-05,-1.5e-05,-1.8e-07,0,0,4.5e-05,0,0,0,0,0,0,0,0,1.8e-06,0.0056,0.0057,0.00011,0.92,0.92,0.69,0.17,0.17,0.2,0.0098,0.0098,0.00042,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1190000,1,-0.012,-0.013,0.0005,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.8e-05,-1.3e-05,-2.2e-07,0,0,-0.00048,0,0,0,0,0,0,0,0,2.1e-06,0.0062,0.0063,0.00013,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.00042,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1290000,1,-0.012,-0.014,0.00045,0.019,-0.018,-0.11,0.002,-0.0024,-0.048,-0.00017,-9.5e-05,3e-06,0,0,-0.00075,0,0,0,0,0,0,0,0,2.1e-06,0.0064,0.0064,9.8e-05,0.87,0.87,0.41,0.15,0.15,0.18,0.0095,0.0095,0.00028,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1390000,1,-0.012,-0.014,0.00042,0.026,-0.023,-0.097,0.0043,-0.0045,-0.038,-0.00016,-9e-05,2.8e-06,0,0,-0.0014,0,0,0,0,0,0,0,0,2.4e-06,0.007,0.007,0.00011,1.1,1.1,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00028,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1490000,1,-0.012,-0.014,0.0004,0.024,-0.021,-0.12,0.0034,-0.0033,-0.053,-0.00039,-0.00033,1.1e-05,0,0,-0.0012,0,0,0,0,0,0,0,0,2.3e-06,0.0067,0.0067,8.7e-05,0.95,0.94,0.27,0.14,0.14,0.15,0.0088,0.0088,0.0002,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1590000,1,-0.012,-0.014,0.00042,0.031,-0.025,-0.13,0.0062,-0.0056,-0.063,-0.00039,-0.00033,1.1e-05,0,0,-0.0014,0,0,0,0,0,0,0,0,2.6e-06,0.0073,0.0073,0.0001,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.0002,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1690000,1,-0.012,-0.014,0.00046,0.028,-0.02,-0.13,0.0044,-0.0038,-0.068,-0.00074,-0.00073,2.4e-05,0,0,-0.0018,0,0,0,0,0,0,0,0,2.3e-06,0.0063,0.0063,7.9e-05,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.00015,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1790000,1,-0.012,-0.014,0.00041,0.036,-0.025,-0.13,0.0076,-0.006,-0.067,-0.00073,-0.00072,2.4e-05,0,0,-0.0028,0,0,0,0,0,0,0,0,2.6e-06,0.0069,0.007,8.9e-05,1.3,1.3,0.16,0.2,0.2,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -1890000,1,-0.012,-0.014,0.00041,0.043,-0.026,-0.14,0.012,-0.0085,-0.075,-0.00073,-0.00072,2.4e-05,0,0,-0.0032,0,0,0,0,0,0,0,0,2.9e-06,0.0076,0.0076,0.0001,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -1990000,1,-0.011,-0.014,0.0004,0.035,-0.018,-0.14,0.0082,-0.0055,-0.074,-0.0011,-0.0013,3.9e-05,0,0,-0.0046,0,0,0,0,0,0,0,0,2.3e-06,0.006,0.006,8e-05,1.3,1.3,0.13,0.2,0.2,0.11,0.0066,0.0066,0.00011,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -2090000,1,-0.011,-0.014,0.00042,0.042,-0.021,-0.14,0.012,-0.0076,-0.071,-0.0011,-0.0012,3.8e-05,0,0,-0.0065,0,0,0,0,0,0,0,0,2.6e-06,0.0066,0.0066,8.9e-05,1.7,1.7,0.12,0.31,0.31,0.11,0.0066,0.0066,0.00011,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -2190000,1,-0.011,-0.014,0.00036,0.033,-0.014,-0.14,0.0081,-0.0045,-0.077,-0.0015,-0.0018,5.1e-05,0,0,-0.0075,0,0,0,0,0,0,0,0,2e-06,0.0049,0.005,7.2e-05,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,8.8e-05,0.04,0.04,0.038,0,0,0,0,0,0,0,0 -2290000,1,-0.011,-0.014,0.00035,0.038,-0.015,-0.14,0.012,-0.0059,-0.075,-0.0014,-0.0018,5.1e-05,0,0,-0.0098,0,0,0,0,0,0,0,0,2.2e-06,0.0054,0.0054,8e-05,1.5,1.5,0.11,0.29,0.29,0.1,0.0055,0.0055,8.8e-05,0.04,0.04,0.038,0,0,0,0,0,0,0,0 -2390000,1,-0.011,-0.013,0.00035,0.029,-0.01,-0.14,0.0075,-0.0034,-0.072,-0.0017,-0.0023,5.9e-05,0,0,-0.012,0,0,0,0,0,0,0,0,1.6e-06,0.004,0.004,6.6e-05,1,1,0.1,0.19,0.19,0.098,0.0045,0.0045,7e-05,0.04,0.04,0.038,0,0,0,0,0,0,0,0 -2490000,1,-0.011,-0.014,0.00043,0.033,-0.0092,-0.14,0.011,-0.0044,-0.079,-0.0017,-0.0023,5.9e-05,0,0,-0.013,0,0,0,0,0,0,0,0,1.7e-06,0.0044,0.0044,7.2e-05,1.3,1.3,0.1,0.28,0.28,0.097,0.0045,0.0045,7e-05,0.04,0.04,0.037,0,0,0,0,0,0,0,0 -2590000,1,-0.01,-0.013,0.00032,0.023,-0.0062,-0.15,0.0066,-0.0025,-0.085,-0.0019,-0.0027,6.4e-05,0,0,-0.015,0,0,0,0,0,0,0,0,1.3e-06,0.0032,0.0032,6.1e-05,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,5.7e-05,0.04,0.04,0.036,0,0,0,0,0,0,0,0 -2690000,1,-0.01,-0.013,0.00036,0.027,-0.0055,-0.15,0.0091,-0.0031,-0.084,-0.0019,-0.0027,6.4e-05,0,0,-0.018,0,0,0,0,0,0,0,0,1.4e-06,0.0035,0.0035,6.6e-05,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,5.7e-05,0.04,0.04,0.036,0,0,0,0,0,0,0,0 -2790000,1,-0.01,-0.013,0.00029,0.022,-0.0031,-0.14,0.0059,-0.0017,-0.081,-0.002,-0.003,6.7e-05,0,0,-0.022,0,0,0,0,0,0,0,0,1e-06,0.0027,0.0027,5.6e-05,0.76,0.77,0.096,0.16,0.16,0.089,0.0032,0.0032,4.7e-05,0.04,0.04,0.035,0,0,0,0,0,0,0,0 -2890000,1,-0.01,-0.013,0.00021,0.026,-0.0049,-0.14,0.0083,-0.0022,-0.081,-0.002,-0.003,6.6e-05,0,0,-0.025,0,0,0,0,0,0,0,0,1.1e-06,0.0029,0.0029,6.1e-05,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,4.7e-05,0.04,0.04,0.034,0,0,0,0,0,0,0,0 -2990000,1,-0.01,-0.013,0.00022,0.02,-0.0038,-0.15,0.0054,-0.0013,-0.086,-0.002,-0.0033,6.7e-05,0,0,-0.028,0,0,0,0,0,0,0,0,8.5e-07,0.0023,0.0023,5.3e-05,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,3.9e-05,0.04,0.04,0.033,0,0,0,0,0,0,0,0 -3090000,1,-0.01,-0.013,0.00042,0.025,-0.0067,-0.15,0.0077,-0.0019,-0.087,-0.002,-0.0033,6.7e-05,0,0,-0.031,0,0,0,0,0,0,0,0,9.3e-07,0.0025,0.0025,5.7e-05,0.82,0.82,0.095,0.22,0.22,0.086,0.0027,0.0027,3.9e-05,0.04,0.04,0.032,0,0,0,0,0,0,0,0 -3190000,1,-0.01,-0.013,0.00045,0.021,-0.0065,-0.15,0.0051,-0.0014,-0.097,-0.0021,-0.0036,6.8e-05,0,0,-0.033,0,0,0,0,0,0,0,0,7.2e-07,0.002,0.002,4.9e-05,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,3.3e-05,0.04,0.04,0.031,0,0,0,0,0,0,0,0 -3290000,1,-0.01,-0.013,0.00047,0.024,-0.0067,-0.15,0.0074,-0.0021,-0.11,-0.0021,-0.0036,6.7e-05,0,0,-0.034,0,0,0,0,0,0,0,0,7.8e-07,0.0022,0.0022,5.3e-05,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,3.3e-05,0.04,0.04,0.03,0,0,0,0,0,0,0,0 -3390000,1,-0.0098,-0.013,0.00047,0.019,-0.0037,-0.15,0.005,-0.0014,-0.1,-0.0021,-0.0038,6.7e-05,0,0,-0.04,0,0,0,0,0,0,0,0,6e-07,0.0017,0.0017,4.6e-05,0.53,0.53,0.095,0.14,0.14,0.085,0.0019,0.0019,2.8e-05,0.04,0.04,0.029,0,0,0,0,0,0,0,0 -3490000,1,-0.0097,-0.013,0.00045,0.025,-0.0024,-0.15,0.0073,-0.0017,-0.1,-0.0021,-0.0038,6.7e-05,0,0,-0.044,0,0,0,0,0,0,0,0,6.5e-07,0.0019,0.0019,5e-05,0.65,0.65,0.095,0.19,0.19,0.086,0.0019,0.0019,2.8e-05,0.04,0.04,0.028,0,0,0,0,0,0,0,0 -3590000,1,-0.0096,-0.013,0.0004,0.022,-0.0019,-0.15,0.0051,-0.001,-0.11,-0.0022,-0.004,6.6e-05,0,0,-0.047,0,0,0,0,0,0,0,0,5e-07,0.0015,0.0015,4.4e-05,0.48,0.48,0.094,0.13,0.13,0.086,0.0016,0.0016,2.4e-05,0.04,0.04,0.026,0,0,0,0,0,0,0,0 -3690000,1,-0.0096,-0.013,0.00038,0.024,-0.0014,-0.15,0.0075,-0.0013,-0.11,-0.0022,-0.004,6.6e-05,0,0,-0.052,0,0,0,0,0,0,0,0,5.4e-07,0.0017,0.0017,4.7e-05,0.59,0.59,0.093,0.18,0.18,0.085,0.0016,0.0016,2.4e-05,0.04,0.04,0.025,0,0,0,0,0,0,0,0 -3790000,1,-0.0095,-0.012,0.00039,0.02,0.0031,-0.15,0.0052,-0.0006,-0.11,-0.0022,-0.0042,6.5e-05,0,0,-0.055,0,0,0,0,0,0,0,0,4.3e-07,0.0014,0.0014,4.1e-05,0.44,0.44,0.093,0.12,0.12,0.086,0.0014,0.0014,2.1e-05,0.04,0.04,0.024,0,0,0,0,0,0,0,0 -3890000,1,-0.0094,-0.013,0.00047,0.022,0.0042,-0.14,0.0074,-0.00025,-0.11,-0.0022,-0.0042,6.5e-05,0,0,-0.059,0,0,0,0,0,0,0,0,4.7e-07,0.0015,0.0015,4.4e-05,0.54,0.54,0.091,0.17,0.17,0.086,0.0014,0.0014,2.1e-05,0.04,0.04,0.022,0,0,0,0,0,0,0,0 -3990000,1,-0.0094,-0.013,0.00053,0.027,0.0038,-0.14,0.0099,7.5e-05,-0.11,-0.0022,-0.0042,6.5e-05,0,0,-0.064,0,0,0,0,0,0,0,0,5.1e-07,0.0016,0.0016,4.7e-05,0.66,0.66,0.089,0.22,0.22,0.085,0.0014,0.0014,2.1e-05,0.04,0.04,0.021,0,0,0,0,0,0,0,0 -4090000,1,-0.0094,-0.012,0.00059,0.023,0.0031,-0.12,0.0074,0.00032,-0.098,-0.0022,-0.0044,6.2e-05,0,0,-0.072,0,0,0,0,0,0,0,0,3.9e-07,0.0013,0.0013,4.2e-05,0.5,0.5,0.087,0.16,0.16,0.085,0.0011,0.0011,1.8e-05,0.04,0.04,0.02,0,0,0,0,0,0,0,0 -4190000,1,-0.0095,-0.012,0.00055,0.025,0.0027,-0.12,0.0098,0.00061,-0.1,-0.0022,-0.0044,6.2e-05,0,0,-0.074,0,0,0,0,0,0,0,0,4.3e-07,0.0015,0.0015,4.4e-05,0.6,0.6,0.086,0.21,0.21,0.086,0.0011,0.0011,1.8e-05,0.04,0.04,0.019,0,0,0,0,0,0,0,0 -4290000,1,-0.0095,-0.012,0.00055,0.023,0.0026,-0.12,0.0071,0.00052,-0.11,-0.0022,-0.0046,6e-05,0,0,-0.077,0,0,0,0,0,0,0,0,3.4e-07,0.0012,0.0012,4e-05,0.46,0.46,0.084,0.15,0.15,0.085,0.00095,0.00095,1.6e-05,0.04,0.04,0.017,0,0,0,0,0,0,0,0 -4390000,1,-0.0095,-0.012,0.0005,0.026,0.00099,-0.11,0.0097,0.00061,-0.094,-0.0022,-0.0046,6e-05,0,0,-0.083,0,0,0,0,0,0,0,0,3.6e-07,0.0013,0.0013,4.2e-05,0.55,0.55,0.081,0.2,0.2,0.084,0.00095,0.00095,1.6e-05,0.04,0.04,0.016,0,0,0,0,0,0,0,0 -4490000,1,-0.0095,-0.012,0.00056,0.022,0.0028,-0.11,0.0071,0.00052,-0.095,-0.0022,-0.0048,5.7e-05,0,0,-0.086,0,0,0,0,0,0,0,0,2.8e-07,0.001,0.001,3.8e-05,0.42,0.42,0.08,0.14,0.14,0.085,0.00078,0.00078,1.4e-05,0.04,0.04,0.015,0,0,0,0,0,0,0,0 -4590000,1,-0.0095,-0.012,0.00062,0.025,0.0015,-0.11,0.0095,0.00072,-0.098,-0.0022,-0.0048,5.7e-05,0,0,-0.089,0,0,0,0,0,0,0,0,3.1e-07,0.0011,0.0011,4e-05,0.51,0.51,0.077,0.19,0.19,0.084,0.00078,0.00078,1.4e-05,0.04,0.04,0.014,0,0,0,0,0,0,0,0 -4690000,1,-0.0095,-0.012,0.00055,0.019,0.0018,-0.1,0.0069,0.00051,-0.09,-0.0022,-0.005,5.5e-05,0,0,-0.093,0,0,0,0,0,0,0,0,2.4e-07,0.00092,0.00092,3.6e-05,0.39,0.39,0.074,0.14,0.14,0.083,0.00064,0.00064,1.3e-05,0.04,0.04,0.013,0,0,0,0,0,0,0,0 -4790000,1,-0.0094,-0.012,0.00064,0.017,0.0039,-0.099,0.0087,0.00084,-0.092,-0.0022,-0.005,5.5e-05,0,0,-0.095,0,0,0,0,0,0,0,0,2.6e-07,0.00099,0.00099,3.8e-05,0.47,0.47,0.073,0.18,0.18,0.084,0.00064,0.00064,1.3e-05,0.04,0.04,0.012,0,0,0,0,0,0,0,0 -4890000,1,-0.0093,-0.012,0.00067,0.012,0.0015,-0.093,0.0059,0.00065,-0.088,-0.0021,-0.0051,5.3e-05,0,0,-0.099,0,0,0,0,0,0,0,0,2e-07,0.0008,0.0008,3.5e-05,0.36,0.36,0.07,0.13,0.13,0.083,0.00052,0.00052,1.1e-05,0.04,0.04,0.011,0,0,0,0,0,0,0,0 -4990000,1,-0.0093,-0.012,0.00065,0.016,0.0021,-0.085,0.0073,0.00085,-0.083,-0.0021,-0.0051,5.3e-05,0,0,-0.1,0,0,0,0,0,0,0,0,2.1e-07,0.00086,0.00086,3.6e-05,0.43,0.43,0.067,0.17,0.17,0.082,0.00052,0.00052,1.1e-05,0.04,0.04,0.01,0,0,0,0,0,0,0,0 -5090000,1,-0.0092,-0.012,0.00072,0.012,0.0026,-0.082,0.0051,0.00061,-0.081,-0.0021,-0.0052,5.1e-05,0,0,-0.1,0,0,0,0,0,0,0,0,1.6e-07,0.00069,0.00069,3.3e-05,0.33,0.33,0.065,0.12,0.12,0.082,0.00042,0.00042,1e-05,0.04,0.04,0.0098,0,0,0,0,0,0,0,0 -5190000,1,-0.009,-0.012,0.00076,0.012,0.006,-0.08,0.0063,0.001,-0.079,-0.0021,-0.0052,5.1e-05,0,0,-0.11,0,0,0,0,0,0,0,0,1.8e-07,0.00075,0.00075,3.5e-05,0.39,0.39,0.063,0.16,0.16,0.081,0.00042,0.00042,1e-05,0.04,0.04,0.0091,0,0,0,0,0,0,0,0 -5290000,1,-0.0089,-0.012,0.00081,0.01,0.0062,-0.068,0.0044,0.00098,-0.072,-0.0021,-0.0053,4.9e-05,0,0,-0.11,0,0,0,0,0,0,0,0,1.3e-07,0.0006,0.0006,3.2e-05,0.3,0.3,0.06,0.12,0.12,0.08,0.00034,0.00034,9.1e-06,0.04,0.04,0.0084,0,0,0,0,0,0,0,0 -5390000,1,-0.0088,-0.012,0.00081,0.0099,0.0098,-0.065,0.0054,0.0017,-0.067,-0.0021,-0.0053,4.9e-05,0,0,-0.11,0,0,0,0,0,0,0,0,1.4e-07,0.00065,0.00065,3.4e-05,0.36,0.36,0.057,0.15,0.15,0.079,0.00034,0.00034,9.1e-06,0.04,0.04,0.0078,0,0,0,0,0,0,0,0 -5490000,1,-0.0089,-0.012,0.0008,0.0091,0.011,-0.06,0.0037,0.0017,-0.065,-0.0021,-0.0054,4.8e-05,0,0,-0.11,0,0,0,0,0,0,0,0,1.1e-07,0.00052,0.00052,3.1e-05,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,8.3e-06,0.04,0.04,0.0073,0,0,0,0,0,0,0,0 -5590000,1,-0.0089,-0.012,0.00072,0.011,0.015,-0.053,0.0048,0.003,-0.058,-0.0021,-0.0054,4.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,1.2e-07,0.00056,0.00056,3.2e-05,0.32,0.32,0.053,0.15,0.15,0.078,0.00028,0.00028,8.3e-06,0.04,0.04,0.0067,0,0,0,0,0,0,0,0 -5690000,1,-0.0089,-0.011,0.00062,0.0095,0.015,-0.052,0.0034,0.0027,-0.055,-0.002,-0.0055,4.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,9.3e-08,0.00045,0.00045,3e-05,0.25,0.25,0.051,0.11,0.11,0.076,0.00022,0.00022,7.5e-06,0.04,0.04,0.0062,0,0,0,0,0,0,0,0 -5790000,1,-0.0088,-0.011,0.00057,0.011,0.017,-0.049,0.0045,0.0042,-0.053,-0.002,-0.0055,4.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,9.8e-08,0.00048,0.00048,3.1e-05,0.29,0.29,0.05,0.14,0.14,0.077,0.00022,0.00022,7.5e-06,0.04,0.04,0.0058,0,0,0,0,0,0,0,0 -5890000,1,-0.0088,-0.011,0.0006,0.011,0.015,-0.048,0.0034,0.0035,-0.056,-0.002,-0.0055,4.4e-05,0,0,-0.12,0,0,0,0,0,0,0,0,7.7e-08,0.00039,0.00039,2.9e-05,0.23,0.23,0.048,0.1,0.1,0.075,0.00018,0.00018,6.8e-06,0.04,0.04,0.0054,0,0,0,0,0,0,0,0 -5990000,1,-0.0088,-0.012,0.00056,0.013,0.016,-0.041,0.0046,0.005,-0.05,-0.002,-0.0055,4.4e-05,0,0,-0.12,0,0,0,0,0,0,0,0,8.3e-08,0.00041,0.00041,3e-05,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,6.8e-06,0.04,0.04,0.005,0,0,0,0,0,0,0,0 -6090000,1,-0.0088,-0.012,0.00037,0.013,0.017,-0.039,0.0059,0.0067,-0.047,-0.002,-0.0055,4.4e-05,0,0,-0.12,0,0,0,0,0,0,0,0,8.8e-08,0.00044,0.00044,3.1e-05,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,6.8e-06,0.04,0.04,0.0047,0,0,0,0,0,0,0,0 -6190000,0.98,-0.0066,-0.013,0.19,0.0098,0.016,-0.037,0.0045,0.0054,-0.047,-0.0019,-0.0056,4.2e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00034,0.00034,0.0054,0.22,0.22,0.042,0.13,0.13,0.073,0.00015,0.00015,6.3e-06,0.04,0.04,0.0044,0,0,0,0,0,0,0,0 -6290000,0.98,-0.0065,-0.013,0.19,0.0083,0.018,-0.041,0.0055,0.0071,-0.053,-0.0019,-0.0056,4.2e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00034,0.00034,0.0054,0.22,0.22,0.04,0.16,0.16,0.072,0.00015,0.00015,6.3e-06,0.04,0.04,0.0041,0,0,0,0,0,0,0,0 -6390000,0.98,-0.0065,-0.013,0.19,0.011,0.02,-0.042,0.0064,0.009,-0.056,-0.0019,-0.0056,4.2e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00034,0.00034,0.0054,0.23,0.23,0.039,0.19,0.19,0.072,0.00015,0.00015,6.3e-06,0.04,0.04,0.0038,0,0,0,0,0,0,0,0 -6490000,0.98,-0.0064,-0.013,0.19,0.0084,0.019,-0.039,0.0073,0.011,-0.053,-0.0019,-0.0056,4.2e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00035,0.00034,0.0054,0.24,0.24,0.038,0.23,0.23,0.07,0.00015,0.00015,6.3e-06,0.04,0.04,0.0036,0,0,0,0,0,0,0,0 -6590000,0.98,-0.0064,-0.013,0.19,0.0078,0.022,-0.042,0.0082,0.013,-0.056,-0.0019,-0.0056,4.2e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00035,0.00035,0.0054,0.26,0.26,0.036,0.28,0.28,0.069,0.00015,0.00015,6.3e-06,0.04,0.04,0.0033,0,0,0,0,0,0,0,0 -6690000,0.98,-0.0063,-0.013,0.19,0.0052,0.025,-0.044,0.0088,0.015,-0.057,-0.0019,-0.0056,4.2e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00035,0.00035,0.0054,0.28,0.28,0.035,0.33,0.33,0.068,0.00015,0.00015,6.3e-06,0.04,0.04,0.0031,0,0,0,0,0,0,0,0 -6790000,0.98,-0.0063,-0.013,0.19,0.007,0.027,-0.042,0.0093,0.018,-0.058,-0.0019,-0.0056,4.2e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00036,0.00036,0.0054,0.3,0.3,0.034,0.38,0.38,0.068,0.00015,0.00015,6.3e-06,0.04,0.04,0.0029,0,0,0,0,0,0,0,0 -6890000,0.98,-0.0061,-0.013,0.19,0.0066,0.028,-0.038,0.01,0.02,-0.055,-0.0019,-0.0056,4.2e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00036,0.00036,0.0054,0.32,0.32,0.032,0.45,0.45,0.067,0.00015,0.00015,6.3e-06,0.04,0.04,0.0027,0,0,0,0,0,0,0,0 -6990000,0.98,-0.006,-0.013,0.19,0.0066,0.029,-0.037,0.011,0.023,-0.055,-0.0019,-0.0056,4.2e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00037,0.00037,0.0054,0.35,0.35,0.031,0.52,0.52,0.066,0.00015,0.00015,6.3e-06,0.04,0.04,0.0026,0,0,0,0,0,0,0,0 -7090000,0.98,-0.0059,-0.013,0.19,0.0057,0.035,-0.037,0.011,0.027,-0.056,-0.0019,-0.0056,4.2e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00037,0.00037,0.0054,0.39,0.39,0.03,0.6,0.6,0.066,0.00015,0.00015,6.3e-06,0.04,0.04,0.0024,0,0,0,0,0,0,0,0 -7190000,0.98,-0.0058,-0.013,0.19,0.0053,0.038,-0.036,0.012,0.03,-0.058,-0.0019,-0.0056,4.2e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00038,0.00038,0.0054,0.42,0.42,0.029,0.69,0.69,0.065,0.00015,0.00015,6.3e-06,0.04,0.04,0.0023,0,0,0,0,0,0,0,0 -7290000,0.98,-0.0058,-0.013,0.19,0.0062,0.043,-0.034,0.012,0.034,-0.054,-0.0019,-0.0056,4.2e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00039,0.00039,0.0054,0.46,0.46,0.028,0.79,0.79,0.064,0.00015,0.00015,6.3e-06,0.04,0.04,0.0021,0,0,0,0,0,0,0,0 -7390000,0.98,-0.0057,-0.013,0.19,0.0044,0.046,-0.032,0.013,0.038,-0.052,-0.0019,-0.0056,4.2e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.0004,0.0004,0.0054,0.51,0.51,0.027,0.9,0.9,0.064,0.00014,0.00014,6.3e-06,0.04,0.04,0.002,0,0,0,0,0,0,0,0 -7490000,0.98,-0.0057,-0.013,0.19,0.0068,0.05,-0.026,0.013,0.043,-0.046,-0.0019,-0.0056,4.2e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00041,0.00041,0.0054,0.56,0.56,0.026,1,1,0.063,0.00014,0.00014,6.3e-06,0.04,0.04,0.0019,0,0,0,0,0,0,0,0 -7590000,0.98,-0.0057,-0.013,0.19,0.0077,0.053,-0.023,0.014,0.048,-0.041,-0.0019,-0.0056,4.2e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00042,0.00041,0.0054,0.6,0.6,0.025,1.2,1.2,0.062,0.00014,0.00014,6.3e-06,0.04,0.04,0.0018,0,0,0,0,0,0,0,0 -7690000,0.98,-0.0057,-0.013,0.19,0.0075,0.058,-0.022,0.015,0.053,-0.036,-0.0019,-0.0056,4.2e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00043,0.00043,0.0054,0.66,0.66,0.025,1.3,1.3,0.062,0.00014,0.00014,6.3e-06,0.04,0.04,0.0017,0,0,0,0,0,0,0,0 -7790000,0.98,-0.0056,-0.013,0.19,0.009,0.06,-0.024,0.015,0.058,-0.041,-0.0019,-0.0056,4.1e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00044,0.00043,0.0054,0.72,0.72,0.024,1.5,1.5,0.061,0.00014,0.00014,6.3e-06,0.04,0.04,0.0016,0,0,0,0,0,0,0,0 -7890000,0.98,-0.0056,-0.013,0.19,0.0077,0.065,-0.025,0.016,0.065,-0.045,-0.0019,-0.0056,4.1e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00045,0.00045,0.0054,0.78,0.78,0.023,1.7,1.7,0.06,0.00014,0.00014,6.3e-06,0.04,0.04,0.0015,0,0,0,0,0,0,0,0 -7990000,0.98,-0.0056,-0.013,0.19,0.0079,0.068,-0.021,0.016,0.07,-0.041,-0.0019,-0.0056,4.1e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00045,0.00045,0.0054,0.84,0.84,0.022,1.9,1.9,0.059,0.00014,0.00014,6.3e-06,0.04,0.04,0.0014,0,0,0,0,0,0,0,0 -8090000,0.98,-0.0054,-0.013,0.19,0.0092,0.074,-0.022,0.017,0.077,-0.044,-0.0019,-0.0056,4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00047,0.00047,0.0043,0.91,0.92,0.022,2.1,2.1,0.059,0.00014,0.00014,6.3e-06,0.04,0.04,0.0014,0,0,0,0,0,0,0,0 -8190000,0.98,-0.0054,-0.013,0.19,0.0099,0.08,-0.018,0.018,0.085,-0.038,-0.0019,-0.0056,4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00048,0.00048,0.0043,0.99,0.99,0.021,2.4,2.4,0.058,0.00014,0.00014,6.3e-06,0.04,0.04,0.0013,0,0,0,0,0,0,0,0 -8290000,0.98,-0.0054,-0.013,0.19,0.012,0.084,-0.016,0.019,0.091,-0.038,-0.0019,-0.0056,3.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00049,0.00049,0.0043,1.1,1.1,0.02,2.6,2.6,0.057,0.00014,0.00014,6.3e-06,0.04,0.04,0.0012,0,0,0,0,0,0,0,0 -8390000,0.98,-0.0054,-0.013,0.19,0.0098,0.088,-0.015,0.02,0.1,-0.036,-0.0019,-0.0056,3.9e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0005,0.0005,0.0043,1.1,1.1,0.02,2.9,2.9,0.057,0.00014,0.00014,6.3e-06,0.04,0.04,0.0012,0,0,0,0,0,0,0,0 -8490000,0.98,-0.0053,-0.013,0.19,0.0093,0.091,-0.017,0.02,0.11,-0.041,-0.0018,-0.0056,3.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00051,0.00051,0.0043,1.2,1.2,0.019,3.2,3.2,0.056,0.00014,0.00014,6.3e-06,0.04,0.04,0.0011,0,0,0,0,0,0,0,0 -8590000,0.98,-0.0052,-0.013,0.19,0.01,0.095,-0.012,0.021,0.12,-0.036,-0.0018,-0.0056,3.9e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00052,0.00052,0.0043,1.3,1.3,0.018,3.6,3.6,0.055,0.00014,0.00014,6.3e-06,0.04,0.04,0.0011,0,0,0,0,0,0,0,0 -8690000,0.98,-0.0053,-0.013,0.19,0.01,0.096,-0.014,0.021,0.12,-0.037,-0.0018,-0.0056,3.9e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00053,0.00052,0.0043,1.4,1.4,0.018,3.9,3.9,0.055,0.00013,0.00013,6.3e-06,0.04,0.04,0.001,0,0,0,0,0,0,0,0 -8790000,0.98,-0.0052,-0.013,0.19,0.012,0.1,-0.013,0.023,0.13,-0.035,-0.0018,-0.0056,3.9e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00054,0.00054,0.0043,1.5,1.5,0.018,4.3,4.3,0.055,0.00013,0.00013,6.3e-06,0.04,0.04,0.00096,0,0,0,0,0,0,0,0 -8890000,0.98,-0.0053,-0.013,0.19,0.011,0.1,-0.0091,0.023,0.14,-0.029,-0.0018,-0.0056,3.8e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00054,0.00054,0.0043,1.5,1.5,0.017,4.6,4.6,0.054,0.00013,0.00013,6.3e-06,0.04,0.04,0.00091,0,0,0,0,0,0,0,0 -8990000,0.98,-0.0052,-0.013,0.19,0.01,0.11,-0.0083,0.024,0.15,-0.032,-0.0018,-0.0056,3.8e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00056,0.00056,0.0043,1.6,1.6,0.017,5.2,5.2,0.054,0.00013,0.00013,6.3e-06,0.04,0.04,0.00088,0,0,0,0,0,0,0,0 -9090000,0.98,-0.0053,-0.013,0.19,0.01,0.11,-0.0093,0.024,0.15,-0.032,-0.0018,-0.0056,3.7e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00055,0.00055,0.0043,1.7,1.7,0.016,5.4,5.4,0.053,0.00013,0.00013,6.3e-06,0.04,0.04,0.00084,0,0,0,0,0,0,0,0 -9190000,0.98,-0.0053,-0.013,0.19,0.014,0.11,-0.0088,0.025,0.16,-0.032,-0.0018,-0.0056,3.7e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00057,0.00057,0.0043,1.8,1.8,0.016,6,6.1,0.052,0.00013,0.00013,6.3e-06,0.04,0.04,0.0008,0,0,0,0,0,0,0,0 -9290000,0.98,-0.0052,-0.013,0.19,0.016,0.11,-0.0072,0.025,0.16,-0.03,-0.0018,-0.0056,3.7e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00056,0.00055,0.0044,1.8,1.8,0.015,6.3,6.3,0.052,0.00012,0.00012,6.3e-06,0.04,0.04,0.00076,0,0,0,0,0,0,0,0 -9390000,0.98,-0.0051,-0.013,0.19,0.016,0.12,-0.006,0.026,0.17,-0.03,-0.0018,-0.0056,3.7e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00057,0.00057,0.0044,1.9,1.9,0.015,7,7,0.052,0.00012,0.00012,6.3e-06,0.04,0.04,0.00073,0,0,0,0,0,0,0,0 -9490000,0.98,-0.0052,-0.013,0.19,0.015,0.11,-0.0044,0.026,0.17,-0.027,-0.0017,-0.0056,3.6e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00056,0.00056,0.0044,1.9,1.9,0.015,7.2,7.2,0.051,0.00012,0.00012,6.3e-06,0.04,0.04,0.0007,0,0,0,0,0,0,0,0 -9590000,0.98,-0.0052,-0.013,0.19,0.015,0.12,-0.0043,0.028,0.18,-0.028,-0.0017,-0.0056,3.6e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00057,0.00057,0.0044,2,2,0.014,7.9,7.9,0.05,0.00012,0.00012,6.3e-06,0.04,0.04,0.00067,0,0,0,0,0,0,0,0 -9690000,0.98,-0.0053,-0.013,0.19,0.015,0.11,-0.0014,0.027,0.18,-0.027,-0.0017,-0.0056,3.5e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00055,0.00055,0.0044,2,2,0.014,8,8.1,0.05,0.00012,0.00012,6.3e-06,0.04,0.04,0.00065,0,0,0,0,0,0,0,0 -9790000,0.98,-0.0053,-0.013,0.19,0.016,0.12,-0.0027,0.028,0.19,-0.028,-0.0017,-0.0056,3.5e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00057,0.00057,0.0044,2.1,2.1,0.014,8.9,8.9,0.05,0.00012,0.00012,6.3e-06,0.04,0.04,0.00062,0,0,0,0,0,0,0,0 -9890000,0.98,-0.0054,-0.013,0.19,0.018,0.11,-0.0014,0.027,0.19,-0.029,-0.0016,-0.0056,3.4e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00054,0.00054,0.0044,2.1,2.1,0.013,8.9,8.9,0.049,0.00011,0.00011,6.3e-06,0.04,0.04,0.0006,0,0,0,0,0,0,0,0 -9990000,0.98,-0.0054,-0.013,0.19,0.019,0.12,-0.00072,0.029,0.2,-0.031,-0.0016,-0.0056,3.4e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00056,0.00056,0.0044,2.2,2.2,0.013,9.8,9.8,0.049,0.00011,0.00011,6.3e-06,0.04,0.04,0.00058,0,0,0,0,0,0,0,0 -10090000,0.98,-0.0054,-0.013,0.19,0.017,0.11,0.00048,0.028,0.19,-0.029,-0.0016,-0.0057,3.3e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00053,0.00053,0.0044,2.1,2.1,0.013,9.7,9.7,0.048,0.00011,0.00011,6.3e-06,0.04,0.04,0.00056,0,0,0,0,0,0,0,0 -10190000,0.98,-0.0054,-0.013,0.19,0.015,0.11,0.0014,0.03,0.2,-0.03,-0.0016,-0.0057,3.3e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00055,0.00055,0.0044,2.3,2.3,0.012,11,11,0.048,0.00011,0.00011,6.3e-06,0.04,0.04,0.00054,0,0,0,0,0,0,0,0 -10290000,0.98,-0.0054,-0.013,0.19,0.016,0.11,0.0003,0.031,0.21,-0.029,-0.0016,-0.0057,3.3e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00057,0.00057,0.0044,2.4,2.4,0.012,12,12,0.048,0.00011,0.00011,6.3e-06,0.04,0.04,0.00052,0,0,0,0,0,0,0,0 -10390000,0.98,-0.0054,-0.013,0.19,0.007,0.0052,-0.0025,0.00076,0.00015,-0.028,-0.0016,-0.0057,3.3e-05,-3.6e-08,2.5e-08,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00059,0.00058,0.0044,0.25,0.25,0.56,0.25,0.25,0.048,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10490000,0.98,-0.0053,-0.013,0.19,0.0085,0.0077,0.007,0.0015,0.00076,-0.023,-0.0016,-0.0057,3.3e-05,-1.2e-06,8.3e-07,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0006,0.0006,0.0044,0.26,0.26,0.55,0.26,0.26,0.057,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10590000,0.98,-0.0053,-0.012,0.19,-0.0012,0.0055,0.013,-0.0012,-0.0054,-0.021,-0.0016,-0.0057,3.2e-05,0.00032,8.5e-06,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00061,0.00061,0.0044,0.13,0.13,0.27,0.13,0.13,0.055,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10690000,0.98,-0.0052,-0.012,0.19,-8.2e-05,0.0068,0.016,-0.0012,-0.0048,-0.017,-0.0016,-0.0057,3.2e-05,0.00032,9.2e-06,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00063,0.00063,0.0044,0.15,0.15,0.26,0.14,0.14,0.065,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10790000,0.98,-0.0053,-0.013,0.19,0.0017,0.0031,0.014,-0.00078,-0.0047,-0.015,-0.0016,-0.0057,3.1e-05,0.00052,0.00048,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00062,0.00062,0.0044,0.1,0.1,0.17,0.091,0.091,0.062,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10890000,0.98,-0.0053,-0.013,0.19,0.0018,0.0066,0.01,-0.00059,-0.0042,-0.018,-0.0016,-0.0057,3.1e-05,0.00053,0.00048,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00064,0.00064,0.0044,0.12,0.12,0.16,0.098,0.098,0.068,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10990000,0.98,-0.0054,-0.013,0.19,0.0013,0.012,0.016,-0.00045,-0.003,-0.011,-0.0015,-0.0057,3e-05,0.00068,0.00072,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0006,0.0006,0.0044,0.096,0.096,0.12,0.073,0.073,0.065,9.9e-05,9.9e-05,6.3e-06,0.039,0.039,0.0005,0,0,0,0,0,0,0,0 -11090000,0.98,-0.0055,-0.013,0.19,0.0023,0.017,0.02,-0.00031,-0.0016,-0.0074,-0.0015,-0.0057,3e-05,0.00068,0.00072,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00062,0.00062,0.0044,0.12,0.12,0.11,0.08,0.08,0.069,9.9e-05,9.9e-05,6.3e-06,0.039,0.039,0.0005,0,0,0,0,0,0,0,0 -11190000,0.98,-0.0058,-0.013,0.19,0.004,0.017,0.026,0.0011,-0.0018,-0.00035,-0.0015,-0.0057,2.8e-05,0.00067,0.0016,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00055,0.00055,0.0044,0.096,0.096,0.083,0.063,0.063,0.066,9.1e-05,9.1e-05,6.3e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 -11290000,0.98,-0.0058,-0.013,0.19,0.0042,0.018,0.026,0.0015,-1.6e-05,-0.00012,-0.0015,-0.0057,2.8e-05,0.00067,0.0016,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00057,0.00057,0.0044,0.12,0.12,0.077,0.07,0.07,0.069,9.1e-05,9.1e-05,6.3e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 -11390000,0.98,-0.006,-0.013,0.19,0.0025,0.015,0.016,0.00089,-0.00087,-0.0086,-0.0014,-0.0058,2.6e-05,0.0012,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00049,0.00049,0.0044,0.097,0.097,0.062,0.057,0.057,0.066,8.3e-05,8.3e-05,6.3e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 -11490000,0.98,-0.0059,-0.013,0.19,0.0016,0.017,0.02,0.001,0.00073,-0.0025,-0.0014,-0.0058,2.6e-05,0.0012,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0005,0.0005,0.0044,0.12,0.12,0.057,0.065,0.065,0.067,8.3e-05,8.3e-05,6.3e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 -11590000,0.98,-0.0062,-0.012,0.19,0.0034,0.013,0.018,0.00084,-0.00036,-0.0036,-0.0013,-0.0058,2.4e-05,0.0015,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00042,0.00042,0.0044,0.096,0.096,0.048,0.054,0.054,0.065,7.5e-05,7.5e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0 -11690000,0.98,-0.0062,-0.012,0.19,0.0038,0.017,0.018,0.0012,0.0011,-0.0049,-0.0013,-0.0058,2.4e-05,0.0015,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00044,0.00044,0.0044,0.12,0.12,0.044,0.062,0.062,0.066,7.5e-05,7.5e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0 -11790000,0.98,-0.0066,-0.012,0.19,0.0025,0.011,0.019,0.0007,-0.0018,-0.002,-0.0012,-0.0059,2e-05,0.002,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00037,0.00037,0.0044,0.092,0.092,0.037,0.052,0.052,0.063,6.8e-05,6.8e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -11890000,0.98,-0.0067,-0.012,0.19,0.0052,0.012,0.017,0.001,-0.00069,-0.0013,-0.0012,-0.0059,2e-05,0.002,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00038,0.00038,0.0044,0.11,0.11,0.034,0.061,0.061,0.063,6.8e-05,6.8e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -11990000,0.98,-0.0069,-0.012,0.19,0.0081,0.012,0.015,0.0021,-0.0018,-0.0049,-0.0012,-0.0059,2e-05,0.002,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00032,0.00032,0.0044,0.088,0.088,0.03,0.051,0.051,0.061,6.2e-05,6.2e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12090000,0.98,-0.0068,-0.012,0.19,0.0097,0.012,0.018,0.003,-0.00063,0.0011,-0.0012,-0.0059,2e-05,0.002,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00033,0.00033,0.0044,0.11,0.11,0.027,0.06,0.06,0.06,6.2e-05,6.2e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12190000,0.98,-0.0067,-0.012,0.19,0.0078,0.011,0.017,0.0018,0.00039,0.0029,-0.0012,-0.0059,2e-05,0.0023,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00029,0.00029,0.0044,0.083,0.083,0.024,0.05,0.05,0.058,5.7e-05,5.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12290000,0.98,-0.0068,-0.012,0.19,0.0055,0.011,0.016,0.0025,0.0015,0.0039,-0.0012,-0.0059,2e-05,0.0023,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0003,0.0003,0.0044,0.098,0.098,0.022,0.059,0.059,0.058,5.7e-05,5.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12390000,0.98,-0.0069,-0.012,0.19,0.004,0.0072,0.014,0.0017,0.00049,-0.0021,-0.0012,-0.006,1.8e-05,0.0025,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00026,0.00026,0.0044,0.078,0.078,0.02,0.05,0.05,0.056,5.3e-05,5.3e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12490000,0.98,-0.0069,-0.012,0.19,0.004,0.0082,0.018,0.0021,0.0013,-6.6e-05,-0.0012,-0.006,1.8e-05,0.0025,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00027,0.00027,0.0044,0.091,0.091,0.018,0.059,0.059,0.055,5.3e-05,5.3e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12590000,0.98,-0.0071,-0.012,0.19,0.0078,0.0015,0.02,0.0033,-0.0013,0.0017,-0.0011,-0.006,1.7e-05,0.0025,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00024,0.00024,0.0044,0.072,0.072,0.017,0.049,0.049,0.054,5e-05,5e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12690000,0.98,-0.007,-0.012,0.19,0.0083,-0.00063,0.019,0.0041,-0.0013,0.0033,-0.0011,-0.006,1.7e-05,0.0025,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00025,0.00025,0.0044,0.084,0.084,0.016,0.058,0.058,0.053,5e-05,5e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12790000,0.98,-0.0073,-0.012,0.19,0.0099,-0.004,0.021,0.0041,-0.0044,0.0054,-0.0011,-0.006,1.6e-05,0.0026,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00023,0.00023,0.0044,0.068,0.068,0.014,0.049,0.049,0.052,4.7e-05,4.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12890000,0.98,-0.0073,-0.012,0.19,0.01,-0.005,0.022,0.0052,-0.0049,0.0085,-0.0011,-0.006,1.6e-05,0.0026,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00024,0.00024,0.0044,0.078,0.078,0.013,0.058,0.058,0.051,4.7e-05,4.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12990000,0.98,-0.0072,-0.012,0.19,0.0079,-0.0029,0.022,0.0036,-0.0036,0.0096,-0.0011,-0.006,1.6e-05,0.0026,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00022,0.00022,0.0044,0.064,0.064,0.012,0.049,0.049,0.05,4.5e-05,4.5e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13090000,0.98,-0.0073,-0.012,0.19,0.0088,-0.0028,0.02,0.0044,-0.0038,0.0085,-0.0011,-0.006,1.6e-05,0.0027,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00023,0.00023,0.0044,0.073,0.073,0.012,0.057,0.057,0.049,4.5e-05,4.5e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13190000,0.98,-0.0073,-0.012,0.19,0.0038,-0.0045,0.019,0.00094,-0.0046,0.0091,-0.0011,-0.006,1.6e-05,0.0028,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00021,0.00021,0.0044,0.06,0.06,0.011,0.049,0.049,0.047,4.3e-05,4.3e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13290000,0.98,-0.0073,-0.012,0.19,0.0034,-0.0055,0.016,0.0013,-0.005,0.0085,-0.0011,-0.006,1.6e-05,0.0028,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00022,0.00022,0.0044,0.068,0.068,0.01,0.057,0.057,0.047,4.3e-05,4.3e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13390000,0.98,-0.0072,-0.012,0.19,0.0026,-0.0035,0.016,0.00083,-0.0037,0.0091,-0.0011,-0.006,1.6e-05,0.0028,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00021,0.00021,0.0044,0.056,0.056,0.0097,0.049,0.049,0.046,4e-05,4e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13490000,0.98,-0.0072,-0.012,0.19,0.003,-0.0018,0.015,0.0011,-0.0039,0.0053,-0.0011,-0.006,1.6e-05,0.0029,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00022,0.00021,0.0044,0.064,0.064,0.0093,0.057,0.057,0.045,4e-05,4e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13590000,0.98,-0.0072,-0.012,0.19,0.0075,-0.002,0.017,0.004,-0.0032,0.0038,-0.0011,-0.006,1.6e-05,0.0031,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0002,0.0002,0.0044,0.053,0.053,0.0088,0.048,0.048,0.044,3.8e-05,3.8e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13690000,0.98,-0.0072,-0.012,0.19,0.0075,-0.0035,0.017,0.0047,-0.0034,0.0064,-0.0011,-0.006,1.6e-05,0.0031,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00021,0.00021,0.0044,0.061,0.061,0.0085,0.056,0.056,0.044,3.8e-05,3.8e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13790000,0.98,-0.0071,-0.012,0.19,0.014,0.00071,0.017,0.0083,-0.00094,0.0059,-0.0011,-0.0059,1.7e-05,0.0035,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0002,0.0002,0.0044,0.051,0.051,0.0082,0.048,0.048,0.043,3.7e-05,3.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13890000,0.98,-0.007,-0.012,0.19,0.016,0.0014,0.018,0.0098,-0.00082,0.0081,-0.0011,-0.0059,1.7e-05,0.0035,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00021,0.00021,0.0044,0.058,0.058,0.008,0.056,0.056,0.042,3.7e-05,3.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13990000,0.98,-0.0071,-0.012,0.19,0.015,0.0015,0.017,0.0074,-0.0023,0.007,-0.0011,-0.006,1.6e-05,0.0033,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0002,0.0002,0.0044,0.049,0.049,0.0077,0.048,0.048,0.041,3.5e-05,3.5e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -14090000,0.98,-0.0071,-0.012,0.19,0.013,-0.0029,0.018,0.0088,-0.0024,0.0034,-0.0011,-0.006,1.6e-05,0.0034,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00021,0.00021,0.0044,0.055,0.055,0.0076,0.055,0.055,0.041,3.5e-05,3.5e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -14190000,0.98,-0.0071,-0.012,0.19,0.0099,-0.0016,0.018,0.008,-0.0018,0.0036,-0.0011,-0.006,1.7e-05,0.0035,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0002,0.0002,0.0044,0.047,0.047,0.0074,0.048,0.048,0.04,3.3e-05,3.3e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -14290000,0.98,-0.007,-0.011,0.19,0.012,-0.0017,0.016,0.009,-0.002,0.0079,-0.0011,-0.006,1.7e-05,0.0035,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0002,0.0002,0.0044,0.053,0.053,0.0073,0.055,0.055,0.04,3.3e-05,3.3e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -14390000,0.98,-0.0071,-0.011,0.19,0.012,-0.0047,0.017,0.0084,-0.0031,0.012,-0.0011,-0.006,1.6e-05,0.0033,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0002,0.0002,0.0044,0.045,0.045,0.0071,0.048,0.048,0.039,3.1e-05,3.1e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14490000,0.98,-0.0072,-0.011,0.19,0.01,-0.0045,0.021,0.0094,-0.0036,0.015,-0.0011,-0.006,1.6e-05,0.0033,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0002,0.0002,0.0044,0.051,0.051,0.0071,0.055,0.055,0.038,3.1e-05,3.1e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14590000,0.98,-0.0073,-0.011,0.19,0.0078,-0.0046,0.019,0.0059,-0.0042,0.011,-0.0011,-0.006,1.6e-05,0.0031,0.0033,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00019,0.00019,0.0044,0.044,0.044,0.007,0.047,0.047,0.038,2.9e-05,2.9e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14690000,0.98,-0.0073,-0.011,0.19,0.0071,-0.0046,0.019,0.0066,-0.0047,0.011,-0.0011,-0.006,1.5e-05,0.0031,0.0032,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0002,0.0002,0.0044,0.05,0.05,0.007,0.054,0.054,0.037,2.9e-05,2.9e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14790000,0.98,-0.0072,-0.011,0.19,0.0087,0.0025,0.019,0.0053,0.00078,0.014,-0.0012,-0.006,1.8e-05,0.0032,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00019,0.00019,0.0044,0.043,0.043,0.0069,0.047,0.047,0.037,2.7e-05,2.7e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14890000,0.98,-0.0071,-0.011,0.19,0.0074,3.9e-05,0.023,0.006,0.00092,0.014,-0.0012,-0.006,1.8e-05,0.0032,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0002,0.0002,0.0044,0.049,0.049,0.007,0.054,0.054,0.037,2.7e-05,2.7e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14990000,0.98,-0.0072,-0.011,0.19,0.0061,-0.0016,0.026,0.0047,-0.0007,0.017,-0.0012,-0.0061,1.7e-05,0.0031,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00019,0.00019,0.0045,0.042,0.042,0.0069,0.047,0.047,0.036,2.6e-05,2.6e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -15090000,0.98,-0.0072,-0.011,0.19,0.0062,-0.00054,0.03,0.0053,-0.00085,0.019,-0.0012,-0.0061,1.7e-05,0.0031,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0002,0.0002,0.0045,0.048,0.048,0.007,0.054,0.054,0.036,2.6e-05,2.6e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -15190000,0.98,-0.0073,-0.011,0.19,0.0043,-0.0016,0.03,0.0042,-0.00076,0.021,-0.0012,-0.0061,1.7e-05,0.003,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00019,0.00019,0.0045,0.041,0.041,0.007,0.047,0.047,0.036,2.4e-05,2.4e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -15290000,0.98,-0.0074,-0.011,0.19,0.0049,-0.0027,0.03,0.0047,-0.00096,0.018,-0.0012,-0.0061,1.7e-05,0.0033,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00019,0.00019,0.0045,0.047,0.047,0.0071,0.054,0.054,0.035,2.4e-05,2.4e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -15390000,0.98,-0.0075,-0.011,0.19,0.0051,-0.00029,0.029,0.0037,-0.00065,0.018,-0.0012,-0.0061,1.7e-05,0.0034,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00018,0.00018,0.0045,0.041,0.041,0.0071,0.047,0.047,0.035,2.2e-05,2.2e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15490000,0.98,-0.0075,-0.011,0.19,0.0045,-0.0028,0.029,0.0042,-0.00078,0.019,-0.0012,-0.0061,1.7e-05,0.0035,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00019,0.00019,0.0045,0.046,0.046,0.0072,0.053,0.053,0.035,2.2e-05,2.2e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15590000,0.98,-0.0077,-0.011,0.19,0.0081,-0.0067,0.029,0.0062,-0.0047,0.018,-0.0011,-0.0061,1.5e-05,0.0038,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00018,0.00018,0.0045,0.04,0.04,0.0072,0.047,0.047,0.035,2.1e-05,2.1e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15690000,0.98,-0.0077,-0.011,0.19,0.0099,-0.0098,0.029,0.0072,-0.0055,0.019,-0.0011,-0.0061,1.5e-05,0.0039,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00019,0.00019,0.0045,0.045,0.045,0.0073,0.053,0.053,0.034,2.1e-05,2.1e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15790000,0.98,-0.0077,-0.011,0.19,0.0065,-0.0091,0.029,0.0055,-0.0043,0.02,-0.0011,-0.0061,1.6e-05,0.0039,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00018,0.00018,0.0045,0.04,0.04,0.0073,0.046,0.046,0.034,1.9e-05,1.9e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15890000,0.98,-0.0078,-0.011,0.19,0.0053,-0.0076,0.03,0.0061,-0.0052,0.02,-0.0011,-0.0061,1.6e-05,0.0041,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00018,0.00018,0.0045,0.045,0.045,0.0074,0.053,0.053,0.034,1.9e-05,1.9e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15990000,0.98,-0.0076,-0.011,0.19,0.0033,-0.0061,0.027,0.0048,-0.004,0.019,-0.0012,-0.0061,1.6e-05,0.0043,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00017,0.00017,0.0045,0.039,0.039,0.0074,0.046,0.046,0.034,1.7e-05,1.7e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -16090000,0.98,-0.0075,-0.011,0.19,0.0026,-0.0074,0.024,0.0051,-0.0046,0.019,-0.0012,-0.0061,1.6e-05,0.0044,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00018,0.00018,0.0045,0.044,0.044,0.0076,0.053,0.053,0.034,1.7e-05,1.7e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -16190000,0.98,-0.0074,-0.011,0.19,-0.0013,-0.005,0.023,0.0027,-0.0034,0.016,-0.0012,-0.0061,1.7e-05,0.0045,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00017,0.00017,0.0045,0.039,0.039,0.0076,0.046,0.046,0.034,1.6e-05,1.6e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16290000,0.98,-0.0075,-0.011,0.19,-0.00097,-0.0066,0.023,0.0026,-0.004,0.017,-0.0012,-0.0061,1.7e-05,0.0046,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00017,0.00017,0.0045,0.043,0.043,0.0077,0.053,0.053,0.034,1.6e-05,1.6e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16390000,0.98,-0.0074,-0.011,0.19,0.0015,-0.0058,0.023,0.0036,-0.0031,0.017,-0.0012,-0.0061,1.7e-05,0.0051,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00017,0.00017,0.0045,0.038,0.038,0.0077,0.046,0.046,0.034,1.5e-05,1.5e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16490000,0.98,-0.0075,-0.011,0.19,0.0035,-0.0074,0.026,0.0039,-0.0038,0.021,-0.0012,-0.0061,1.7e-05,0.005,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00017,0.00017,0.0045,0.043,0.043,0.0079,0.053,0.053,0.034,1.5e-05,1.5e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16590000,0.98,-0.0075,-0.011,0.19,0.0075,-0.0074,0.029,0.0034,-0.0029,0.021,-0.0012,-0.0061,1.8e-05,0.0052,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00016,0.00016,0.0045,0.037,0.037,0.0079,0.046,0.046,0.034,1.3e-05,1.3e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16690000,0.98,-0.0076,-0.011,0.19,0.009,-0.012,0.029,0.0042,-0.0039,0.022,-0.0012,-0.0061,1.8e-05,0.0053,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00017,0.00016,0.0045,0.042,0.042,0.008,0.053,0.053,0.034,1.3e-05,1.3e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16790000,0.98,-0.0074,-0.011,0.19,0.0099,-0.011,0.028,0.0033,-0.0028,0.022,-0.0012,-0.0061,1.8e-05,0.0054,0.0027,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00016,0.00016,0.0045,0.037,0.037,0.008,0.046,0.046,0.034,1.2e-05,1.2e-05,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -16890000,0.98,-0.0074,-0.011,0.19,0.0089,-0.011,0.029,0.0043,-0.0039,0.02,-0.0012,-0.0061,1.8e-05,0.0057,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00016,0.00016,0.0045,0.041,0.041,0.0082,0.052,0.052,0.034,1.2e-05,1.2e-05,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -16990000,0.98,-0.0074,-0.011,0.19,0.0086,-0.011,0.029,0.004,-0.0029,0.019,-0.0013,-0.0061,1.9e-05,0.0063,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00015,0.00015,0.0045,0.036,0.036,0.0082,0.046,0.046,0.034,1.1e-05,1.1e-05,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -17090000,0.98,-0.0075,-0.011,0.19,0.01,-0.013,0.028,0.005,-0.0041,0.018,-0.0013,-0.0061,1.9e-05,0.0065,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00016,0.00015,0.0045,0.04,0.041,0.0083,0.052,0.052,0.034,1.1e-05,1.1e-05,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -17190000,0.98,-0.0076,-0.011,0.19,0.009,-0.018,0.03,0.0033,-0.0076,0.021,-0.0012,-0.0061,1.9e-05,0.0063,0.0021,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00015,0.00015,0.0045,0.036,0.036,0.0083,0.046,0.046,0.034,9.9e-06,9.9e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -17290000,0.98,-0.0076,-0.011,0.19,0.0099,-0.019,0.03,0.0043,-0.0094,0.021,-0.0012,-0.0061,1.9e-05,0.0065,0.0019,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00015,0.00015,0.0045,0.04,0.04,0.0084,0.052,0.052,0.034,9.9e-06,9.9e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -17390000,0.98,-0.0074,-0.011,0.19,0.0066,-0.018,0.029,0.0057,-0.0059,0.021,-0.0013,-0.006,2e-05,0.0073,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00014,0.00014,0.0045,0.035,0.035,0.0084,0.046,0.046,0.034,8.9e-06,8.9e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -17490000,0.98,-0.0074,-0.011,0.19,0.0047,-0.019,0.029,0.0062,-0.0078,0.023,-0.0013,-0.006,2e-05,0.0074,0.0024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00015,0.00015,0.0045,0.039,0.039,0.0085,0.052,0.052,0.034,8.9e-06,8.9e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -17590000,0.98,-0.0073,-0.011,0.19,0.00086,-0.015,0.028,0.0024,-0.0058,0.02,-0.0013,-0.0061,2.1e-05,0.0072,0.0029,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00014,0.00014,0.0045,0.034,0.034,0.0085,0.046,0.046,0.034,8.1e-06,8.1e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -17690000,0.98,-0.0074,-0.011,0.19,-8.7e-05,-0.016,0.029,0.0025,-0.0074,0.023,-0.0013,-0.0061,2.1e-05,0.0073,0.0029,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00014,0.00014,0.0045,0.038,0.038,0.0086,0.052,0.052,0.034,8.1e-06,8.1e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -17790000,0.98,-0.0074,-0.011,0.19,0.0026,-0.014,0.029,0.0035,-0.0062,0.028,-0.0014,-0.006,2.2e-05,0.0076,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00014,0.00014,0.0045,0.034,0.034,0.0086,0.046,0.046,0.034,7.3e-06,7.3e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -17890000,0.98,-0.0073,-0.011,0.19,0.0047,-0.016,0.029,0.0039,-0.0077,0.032,-0.0014,-0.006,2.2e-05,0.0075,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00014,0.00014,0.0045,0.037,0.037,0.0086,0.052,0.052,0.035,7.3e-06,7.3e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -17990000,0.98,-0.0071,-0.011,0.19,0.0041,-0.0093,0.029,0.0031,-0.002,0.033,-0.0014,-0.006,2.4e-05,0.0079,0.0046,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00013,0.00013,0.0045,0.033,0.033,0.0086,0.045,0.045,0.034,6.6e-06,6.6e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -18090000,0.98,-0.0072,-0.011,0.19,0.0036,-0.0099,0.028,0.0035,-0.003,0.031,-0.0014,-0.006,2.4e-05,0.0082,0.0044,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00013,0.00013,0.0045,0.036,0.036,0.0087,0.052,0.052,0.035,6.6e-06,6.6e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -18190000,0.98,-0.0072,-0.011,0.19,0.0036,-0.0088,0.028,0.0041,-0.0022,0.029,-0.0014,-0.006,2.4e-05,0.0087,0.0043,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00013,0.00013,0.0045,0.032,0.032,0.0086,0.045,0.045,0.035,6e-06,6e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -18290000,0.98,-0.0072,-0.011,0.19,0.0045,-0.0093,0.027,0.0045,-0.0031,0.027,-0.0014,-0.006,2.4e-05,0.009,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00013,0.00013,0.0046,0.036,0.036,0.0087,0.051,0.051,0.035,6e-06,6e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -18390000,0.98,-0.0071,-0.011,0.19,0.0054,-0.008,0.027,0.0061,-0.0023,0.026,-0.0014,-0.006,2.4e-05,0.0096,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00013,0.00012,0.0046,0.031,0.031,0.0086,0.045,0.045,0.035,5.4e-06,5.4e-06,6.3e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0 -18490000,0.98,-0.0072,-0.011,0.19,0.0082,-0.008,0.026,0.0069,-0.0032,0.028,-0.0014,-0.006,2.4e-05,0.0096,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00013,0.00013,0.0046,0.035,0.035,0.0087,0.051,0.051,0.035,5.4e-06,5.4e-06,6.3e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0 -18590000,0.98,-0.007,-0.011,0.19,0.0066,-0.0074,0.026,0.0055,-0.0024,0.031,-0.0015,-0.006,2.5e-05,0.0095,0.0043,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00012,0.00012,0.0046,0.031,0.031,0.0087,0.045,0.045,0.035,4.9e-06,4.9e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -18690000,0.98,-0.007,-0.011,0.19,0.0066,-0.0063,0.024,0.0062,-0.0031,0.029,-0.0015,-0.006,2.5e-05,0.0097,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00012,0.00012,0.0046,0.034,0.034,0.0087,0.051,0.051,0.035,4.9e-06,4.9e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -18790000,0.98,-0.0069,-0.011,0.19,0.0056,-0.006,0.024,0.0062,-0.0025,0.027,-0.0015,-0.006,2.5e-05,0.01,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00012,0.00012,0.0046,0.03,0.03,0.0087,0.045,0.045,0.035,4.4e-06,4.4e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -18890000,0.98,-0.0069,-0.011,0.19,0.0043,-0.0057,0.021,0.0067,-0.0032,0.023,-0.0015,-0.006,2.5e-05,0.01,0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00012,0.00012,0.0046,0.033,0.033,0.0087,0.051,0.051,0.035,4.4e-06,4.4e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -18990000,0.98,-0.0069,-0.011,0.19,0.0026,-0.0058,0.022,0.0055,-0.0025,0.026,-0.0015,-0.006,2.5e-05,0.01,0.0039,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00012,0.00012,0.0046,0.029,0.029,0.0086,0.045,0.045,0.035,4e-06,4e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19090000,0.98,-0.007,-0.011,0.19,0.00064,-0.0063,0.023,0.0058,-0.0031,0.022,-0.0015,-0.006,2.5e-05,0.011,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00012,0.00012,0.0046,0.032,0.032,0.0087,0.051,0.051,0.036,4e-06,4e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19190000,0.98,-0.0069,-0.011,0.19,-0.00084,-0.0059,0.022,0.0048,-0.0025,0.022,-0.0015,-0.006,2.5e-05,0.011,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00011,0.00011,0.0046,0.028,0.028,0.0086,0.045,0.045,0.036,3.7e-06,3.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19290000,0.98,-0.0068,-0.011,0.19,-0.0017,-0.0058,0.023,0.0047,-0.0031,0.021,-0.0015,-0.006,2.5e-05,0.011,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00012,0.00011,0.0046,0.031,0.031,0.0087,0.05,0.051,0.036,3.7e-06,3.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19390000,0.98,-0.0069,-0.011,0.19,-0.0022,-0.0023,0.024,0.004,-0.0012,0.019,-0.0015,-0.006,2.6e-05,0.011,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00011,0.00011,0.0046,0.028,0.028,0.0086,0.045,0.045,0.036,3.3e-06,3.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19490000,0.98,-0.0069,-0.011,0.19,-0.003,-0.0023,0.023,0.0038,-0.0014,0.019,-0.0015,-0.006,2.6e-05,0.011,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00011,0.00011,0.0046,0.03,0.03,0.0087,0.05,0.05,0.036,3.3e-06,3.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19590000,0.98,-0.0069,-0.011,0.19,-0.0041,-0.0052,0.025,0.0044,-0.0024,0.019,-0.0015,-0.006,2.6e-05,0.012,0.0032,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00011,0.00011,0.0046,0.027,0.027,0.0086,0.044,0.044,0.036,3e-06,3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19690000,0.98,-0.0069,-0.011,0.19,-0.0057,-0.0037,0.023,0.0039,-0.0028,0.019,-0.0015,-0.006,2.6e-05,0.012,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00011,0.00011,0.0046,0.03,0.03,0.0086,0.05,0.05,0.036,3e-06,3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19790000,0.98,-0.007,-0.011,0.19,-0.0058,-0.0023,0.022,0.0063,-0.0023,0.014,-0.0015,-0.006,2.6e-05,0.012,0.0028,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00011,0.00011,0.0046,0.026,0.026,0.0086,0.044,0.044,0.036,2.8e-06,2.8e-06,6.3e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0 -19890000,0.98,-0.007,-0.011,0.19,-0.0058,-0.002,0.022,0.0057,-0.0025,0.013,-0.0015,-0.006,2.6e-05,0.013,0.0027,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00011,0.00011,0.0046,0.029,0.029,0.0086,0.05,0.05,0.036,2.8e-06,2.8e-06,6.3e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0 -19990000,0.98,-0.007,-0.011,0.19,-0.0055,-0.002,0.019,0.0061,-0.00093,0.0097,-0.0015,-0.0059,2.6e-05,0.013,0.0026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00011,0.0001,0.0046,0.026,0.026,0.0085,0.044,0.044,0.036,2.5e-06,2.5e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20090000,0.98,-0.0071,-0.011,0.19,-0.005,-0.0042,0.019,0.0055,-0.0012,0.013,-0.0015,-0.0059,2.6e-05,0.013,0.0026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00011,0.0001,0.0046,0.028,0.028,0.0086,0.05,0.05,0.036,2.5e-06,2.5e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20190000,0.98,-0.0071,-0.011,0.19,-0.0039,-0.0016,0.02,0.0065,-0.00092,0.013,-0.0015,-0.0059,2.6e-05,0.013,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.0001,0.0001,0.0046,0.025,0.025,0.0085,0.044,0.044,0.036,2.3e-06,2.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20290000,0.98,-0.007,-0.011,0.19,-0.0071,-0.0027,0.02,0.006,-0.0011,0.013,-0.0015,-0.0059,2.6e-05,0.013,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.0001,0.0001,0.0046,0.027,0.027,0.0085,0.049,0.049,0.036,2.3e-06,2.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20390000,0.98,-0.007,-0.011,0.19,-0.0078,-0.0015,0.021,0.0069,-0.00079,0.014,-0.0015,-0.0059,2.7e-05,0.014,0.0024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.0001,0.0001,0.0046,0.024,0.024,0.0084,0.044,0.044,0.036,2.1e-06,2.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20490000,0.98,-0.007,-0.011,0.19,-0.012,-0.0025,0.02,0.0059,-0.00097,0.012,-0.0015,-0.0059,2.7e-05,0.014,0.0023,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.0001,0.0001,0.0046,0.027,0.027,0.0085,0.049,0.049,0.036,2.1e-06,2.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20590000,0.98,-0.007,-0.011,0.19,-0.011,-0.0035,0.02,0.0069,-0.00081,0.011,-0.0015,-0.0059,2.7e-05,0.014,0.0021,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.0001,9.9e-05,0.0046,0.024,0.024,0.0084,0.044,0.044,0.036,2e-06,2e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20690000,0.98,-0.0069,-0.011,0.19,-0.013,-0.0022,0.021,0.0057,-0.001,0.011,-0.0015,-0.0059,2.7e-05,0.014,0.0021,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.0001,9.9e-05,0.0046,0.026,0.026,0.0084,0.049,0.049,0.036,2e-06,2e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20790000,0.98,-0.0063,-0.011,0.19,-0.016,0.00032,0.0055,0.0048,-0.00083,0.0097,-0.0015,-0.0059,2.7e-05,0.015,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,9.9e-05,9.7e-05,0.0047,0.023,0.023,0.0084,0.043,0.043,0.036,1.8e-06,1.8e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20890000,0.98,0.0028,-0.0073,0.19,-0.022,0.012,-0.11,0.0029,-0.00016,0.0034,-0.0015,-0.0059,2.7e-05,0.015,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,9.9e-05,9.8e-05,0.0047,0.026,0.026,0.0084,0.049,0.049,0.036,1.8e-06,1.8e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20990000,0.98,0.0061,-0.0038,0.19,-0.032,0.03,-0.25,0.0022,0.00049,-0.011,-0.0015,-0.0059,2.7e-05,0.015,0.0018,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,9.7e-05,9.6e-05,0.0047,0.023,0.023,0.0083,0.043,0.043,0.036,1.7e-06,1.7e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21090000,0.98,0.0045,-0.0042,0.19,-0.046,0.046,-0.37,-0.0017,0.0044,-0.042,-0.0015,-0.0059,2.7e-05,0.015,0.0018,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,9.8e-05,9.7e-05,0.0047,0.026,0.026,0.0084,0.048,0.048,0.036,1.7e-06,1.7e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21190000,0.98,0.0017,-0.0059,0.19,-0.049,0.05,-0.5,-0.0013,0.0034,-0.078,-0.0014,-0.0059,2.6e-05,0.015,0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,9.6e-05,9.4e-05,0.0047,0.023,0.023,0.0083,0.043,0.043,0.036,1.6e-06,1.6e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21290000,0.98,-0.0005,-0.0072,0.19,-0.049,0.054,-0.63,-0.0062,0.0087,-0.14,-0.0014,-0.0059,2.6e-05,0.015,0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,9.6e-05,9.5e-05,0.0047,0.026,0.026,0.0083,0.048,0.048,0.036,1.6e-06,1.6e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21390000,0.98,-0.002,-0.0079,0.19,-0.045,0.05,-0.75,-0.0051,0.011,-0.2,-0.0014,-0.0059,2.6e-05,0.015,0.00077,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,9.4e-05,9.2e-05,0.0047,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21490000,0.98,-0.0028,-0.0083,0.19,-0.04,0.047,-0.89,-0.0094,0.016,-0.29,-0.0014,-0.0059,2.6e-05,0.015,0.00067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,9.5e-05,9.3e-05,0.0047,0.026,0.026,0.0083,0.048,0.048,0.036,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21590000,0.98,-0.0033,-0.0083,0.19,-0.032,0.043,-1,-0.008,0.016,-0.38,-0.0014,-0.0059,2.6e-05,0.015,0.00063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,9.2e-05,9.1e-05,0.0047,0.023,0.023,0.0082,0.043,0.043,0.036,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21690000,0.98,-0.0036,-0.0082,0.19,-0.03,0.039,-1.1,-0.011,0.02,-0.49,-0.0014,-0.0059,2.6e-05,0.015,0.00046,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,9.3e-05,9.1e-05,0.0047,0.025,0.025,0.0083,0.048,0.048,0.036,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21790000,0.98,-0.004,-0.0084,0.19,-0.021,0.032,-1.3,-0.0038,0.018,-0.61,-0.0014,-0.0058,2.7e-05,0.016,0.00026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,9e-05,8.9e-05,0.0047,0.023,0.023,0.0082,0.043,0.043,0.036,1.2e-06,1.2e-06,6.3e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 -21890000,0.98,-0.0043,-0.0085,0.19,-0.018,0.028,-1.4,-0.0058,0.021,-0.75,-0.0014,-0.0058,2.7e-05,0.016,0.00013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.1e-05,8.9e-05,0.0047,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-06,1.2e-06,6.3e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 -21990000,0.98,-0.005,-0.0088,0.19,-0.014,0.022,-1.4,-0.00041,0.017,-0.89,-0.0014,-0.0058,2.6e-05,0.015,0.00038,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.8e-05,8.7e-05,0.0047,0.022,0.022,0.0082,0.043,0.043,0.036,1.1e-06,1.1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22090000,0.98,-0.0057,-0.0096,0.19,-0.012,0.019,-1.4,-0.0017,0.019,-1,-0.0014,-0.0058,2.6e-05,0.016,0.00025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.9e-05,8.7e-05,0.0047,0.024,0.024,0.0082,0.048,0.048,0.036,1.2e-06,1.1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22190000,0.98,-0.0061,-0.0099,0.19,-0.0035,0.013,-1.4,0.006,0.013,-1.2,-0.0014,-0.0058,2.6e-05,0.016,0.00029,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.7e-05,8.5e-05,0.0047,0.021,0.021,0.0081,0.043,0.043,0.036,1.1e-06,1.1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22290000,0.98,-0.0069,-0.01,0.19,0.0016,0.0079,-1.4,0.0059,0.014,-1.3,-0.0014,-0.0058,2.6e-05,0.016,0.00019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.7e-05,8.6e-05,0.0047,0.023,0.023,0.0081,0.048,0.048,0.036,1.1e-06,1.1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22390000,0.98,-0.0072,-0.01,0.19,0.0067,-0.0017,-1.4,0.013,0.0041,-1.5,-0.0014,-0.0058,2.6e-05,0.016,-0.00015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.5e-05,8.4e-05,0.0047,0.021,0.021,0.0081,0.043,0.043,0.036,1e-06,1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22490000,0.98,-0.0074,-0.011,0.19,0.011,-0.0076,-1.4,0.014,0.0036,-1.6,-0.0014,-0.0058,2.6e-05,0.016,-0.0002,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.6e-05,8.4e-05,0.0047,0.022,0.022,0.0081,0.047,0.047,0.036,1e-06,1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22590000,0.98,-0.0073,-0.011,0.19,0.02,-0.017,-1.4,0.026,-0.0053,-1.7,-0.0014,-0.0058,2.6e-05,0.016,-0.00036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.4e-05,8.2e-05,0.0047,0.02,0.02,0.0081,0.042,0.042,0.036,9.4e-07,9.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22690000,0.98,-0.0072,-0.012,0.19,0.022,-0.021,-1.4,0.028,-0.0072,-1.9,-0.0014,-0.0058,2.6e-05,0.016,-0.00044,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.4e-05,8.3e-05,0.0047,0.021,0.021,0.0081,0.047,0.047,0.036,9.5e-07,9.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22790000,0.98,-0.0072,-0.012,0.19,0.028,-0.029,-1.4,0.038,-0.017,-2,-0.0014,-0.0058,2.6e-05,0.016,-0.00056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.3e-05,8.1e-05,0.0047,0.019,0.019,0.0081,0.042,0.042,0.036,8.9e-07,8.9e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22890000,0.98,-0.0074,-0.012,0.19,0.032,-0.034,-1.4,0.041,-0.02,-2.2,-0.0014,-0.0058,2.6e-05,0.016,-0.00063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.3e-05,8.1e-05,0.0047,0.021,0.021,0.0081,0.047,0.047,0.036,8.9e-07,8.9e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22990000,0.98,-0.0073,-0.013,0.19,0.036,-0.04,-1.4,0.051,-0.031,-2.3,-0.0014,-0.0058,2.6e-05,0.017,-0.00077,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.2e-05,8e-05,0.0047,0.019,0.019,0.0081,0.042,0.042,0.036,8.4e-07,8.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23090000,0.98,-0.0074,-0.013,0.19,0.041,-0.044,-1.4,0.055,-0.035,-2.5,-0.0014,-0.0058,2.6e-05,0.017,-0.0008,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.2e-05,8e-05,0.0047,0.02,0.02,0.0081,0.046,0.046,0.036,8.4e-07,8.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23190000,0.98,-0.0074,-0.013,0.19,0.047,-0.046,-1.4,0.066,-0.045,-2.6,-0.0014,-0.0058,2.7e-05,0.017,-0.00095,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,7.9e-05,0.0048,0.018,0.018,0.008,0.042,0.042,0.035,8e-07,8e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23290000,0.98,-0.0079,-0.013,0.19,0.052,-0.051,-1.4,0.071,-0.05,-2.8,-0.0014,-0.0058,2.7e-05,0.017,-0.001,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,7.9e-05,0.0048,0.02,0.02,0.0081,0.046,0.046,0.036,8e-07,8e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23390000,0.98,-0.0078,-0.014,0.19,0.057,-0.053,-1.4,0.082,-0.055,-2.9,-0.0014,-0.0058,2.6e-05,0.017,-0.00075,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.8e-05,0.0048,0.018,0.018,0.008,0.041,0.041,0.036,7.6e-07,7.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23490000,0.98,-0.0079,-0.014,0.19,0.062,-0.055,-1.4,0.088,-0.061,-3,-0.0014,-0.0058,2.6e-05,0.017,-0.00079,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,7.9e-05,0.0048,0.019,0.019,0.0081,0.046,0.046,0.036,7.6e-07,7.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23590000,0.98,-0.0081,-0.014,0.19,0.064,-0.058,-1.4,0.095,-0.07,-3.2,-0.0014,-0.0058,2.7e-05,0.017,-0.00091,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.8e-05,0.0048,0.017,0.017,0.008,0.041,0.041,0.035,7.2e-07,7.2e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23690000,0.98,-0.0088,-0.014,0.19,0.062,-0.06,-1.3,0.1,-0.076,-3.3,-0.0014,-0.0058,2.7e-05,0.017,-0.00093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.8e-05,0.0048,0.018,0.018,0.0081,0.046,0.046,0.036,7.2e-07,7.2e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23790000,0.98,-0.011,-0.017,0.19,0.057,-0.058,-0.96,0.11,-0.081,-3.4,-0.0014,-0.0058,2.7e-05,0.017,-0.00093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.7e-05,0.0048,0.016,0.016,0.008,0.041,0.041,0.035,6.9e-07,6.9e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23890000,0.98,-0.014,-0.021,0.19,0.053,-0.058,-0.52,0.12,-0.087,-3.5,-0.0014,-0.0058,2.7e-05,0.017,-0.00094,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.1e-05,7.8e-05,0.0048,0.017,0.017,0.008,0.045,0.045,0.035,6.9e-07,6.9e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23990000,0.98,-0.016,-0.024,0.19,0.054,-0.058,-0.14,0.13,-0.089,-3.6,-0.0014,-0.0058,2.7e-05,0.018,-0.0015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,7.8e-05,0.0048,0.015,0.015,0.008,0.041,0.041,0.036,6.6e-07,6.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24090000,0.98,-0.016,-0.023,0.19,0.061,-0.066,0.09,0.13,-0.095,-3.6,-0.0014,-0.0058,2.7e-05,0.018,-0.0015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,7.8e-05,0.0048,0.017,0.017,0.0081,0.045,0.045,0.036,6.6e-07,6.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24190000,0.98,-0.013,-0.019,0.19,0.072,-0.071,0.077,0.14,-0.1,-3.6,-0.0014,-0.0058,2.7e-05,0.019,-0.0022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.7e-05,0.0048,0.015,0.015,0.008,0.04,0.04,0.035,6.3e-07,6.3e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24290000,0.98,-0.01,-0.016,0.19,0.076,-0.074,0.055,0.15,-0.11,-3.6,-0.0014,-0.0058,2.7e-05,0.019,-0.0022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.7e-05,0.0048,0.016,0.016,0.0081,0.044,0.044,0.036,6.4e-07,6.3e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24390000,0.98,-0.0095,-0.015,0.19,0.069,-0.069,0.071,0.15,-0.11,-3.6,-0.0014,-0.0058,2.6e-05,0.019,-0.003,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.7e-05,0.0048,0.015,0.015,0.008,0.04,0.04,0.035,6.1e-07,6.1e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24490000,0.98,-0.0098,-0.015,0.19,0.065,-0.066,0.069,0.16,-0.11,-3.6,-0.0014,-0.0058,2.6e-05,0.019,-0.003,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.7e-05,0.0048,0.016,0.016,0.008,0.044,0.044,0.035,6.1e-07,6.1e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24590000,0.98,-0.01,-0.015,0.19,0.061,-0.062,0.065,0.16,-0.11,-3.6,-0.0014,-0.0058,2.6e-05,0.019,-0.0037,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.7e-05,0.0048,0.015,0.015,0.008,0.04,0.04,0.036,5.9e-07,5.9e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24690000,0.98,-0.011,-0.015,0.19,0.059,-0.061,0.064,0.17,-0.12,-3.6,-0.0014,-0.0058,2.6e-05,0.019,-0.0037,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.7e-05,0.0048,0.016,0.016,0.0081,0.044,0.044,0.036,5.9e-07,5.9e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24790000,0.98,-0.011,-0.014,0.19,0.056,-0.059,0.056,0.17,-0.11,-3.6,-0.0015,-0.0058,2.6e-05,0.019,-0.0043,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.7e-05,0.0048,0.015,0.015,0.008,0.039,0.039,0.035,5.7e-07,5.7e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24890000,0.98,-0.011,-0.013,0.19,0.054,-0.062,0.045,0.18,-0.12,-3.6,-0.0015,-0.0058,2.6e-05,0.019,-0.0043,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,0.0048,0.016,0.016,0.008,0.043,0.043,0.035,5.7e-07,5.7e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24990000,0.98,-0.011,-0.013,0.19,0.046,-0.058,0.038,0.18,-0.11,-3.6,-0.0015,-0.0058,2.6e-05,0.019,-0.005,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,0.0048,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-07,5.5e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -25090000,0.98,-0.011,-0.013,0.19,0.042,-0.057,0.035,0.18,-0.12,-3.6,-0.0015,-0.0058,2.6e-05,0.019,-0.005,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,0.0048,0.016,0.016,0.0081,0.043,0.043,0.035,5.5e-07,5.5e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -25190000,0.98,-0.011,-0.013,0.19,0.037,-0.05,0.035,0.18,-0.11,-3.6,-0.0015,-0.0058,2.5e-05,0.018,-0.0055,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,0.0048,0.015,0.015,0.008,0.039,0.039,0.035,5.3e-07,5.3e-07,6.3e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -25290000,0.98,-0.011,-0.012,0.19,0.032,-0.052,0.029,0.18,-0.11,-3.6,-0.0015,-0.0058,2.5e-05,0.018,-0.0055,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.8e-05,0.0049,0.016,0.016,0.0081,0.043,0.043,0.036,5.3e-07,5.3e-07,6.3e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -25390000,0.98,-0.011,-0.012,0.19,0.024,-0.045,0.028,0.18,-0.1,-3.6,-0.0015,-0.0058,2.6e-05,0.018,-0.0062,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.8e-05,0.0049,0.015,0.015,0.008,0.039,0.039,0.035,5.2e-07,5.1e-07,6.3e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -25490000,0.98,-0.011,-0.012,0.19,0.019,-0.044,0.027,0.18,-0.11,-3.6,-0.0015,-0.0058,2.6e-05,0.018,-0.0062,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.8e-05,0.0049,0.016,0.016,0.008,0.043,0.043,0.035,5.2e-07,5.2e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -25590000,0.98,-0.011,-0.012,0.19,0.014,-0.04,0.028,0.18,-0.098,-3.6,-0.0015,-0.0058,2.6e-05,0.018,-0.0065,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.8e-05,0.0049,0.014,0.014,0.008,0.039,0.039,0.035,5e-07,5e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -25690000,0.98,-0.011,-0.011,0.19,0.013,-0.039,0.017,0.18,-0.1,-3.6,-0.0015,-0.0058,2.6e-05,0.018,-0.0066,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.8e-05,0.0049,0.015,0.015,0.0081,0.043,0.043,0.035,5e-07,5e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -25790000,0.98,-0.011,-0.011,0.19,0.0022,-0.031,0.017,0.17,-0.093,-3.6,-0.0016,-0.0058,2.7e-05,0.018,-0.007,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.8e-05,0.0049,0.014,0.014,0.008,0.039,0.039,0.035,4.9e-07,4.8e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -25890000,0.98,-0.011,-0.011,0.19,-0.0036,-0.029,0.019,0.17,-0.096,-3.6,-0.0016,-0.0058,2.7e-05,0.018,-0.007,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.9e-05,0.0049,0.015,0.015,0.0081,0.043,0.043,0.036,4.9e-07,4.9e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -25990000,0.98,-0.011,-0.011,0.19,-0.013,-0.022,0.013,0.16,-0.086,-3.6,-0.0016,-0.0058,2.8e-05,0.018,-0.0074,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.8e-05,0.0049,0.014,0.014,0.008,0.039,0.039,0.035,4.7e-07,4.7e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26090000,0.98,-0.01,-0.011,0.19,-0.018,-0.022,0.011,0.16,-0.088,-3.6,-0.0016,-0.0058,2.8e-05,0.019,-0.0075,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.9e-05,0.0049,0.015,0.015,0.0081,0.042,0.042,0.035,4.7e-07,4.7e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26190000,0.98,-0.01,-0.011,0.19,-0.024,-0.015,0.0063,0.15,-0.081,-3.6,-0.0016,-0.0058,2.8e-05,0.019,-0.0077,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.9e-05,0.0049,0.014,0.014,0.008,0.039,0.039,0.035,4.6e-07,4.6e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26290000,0.98,-0.01,-0.012,0.19,-0.026,-0.014,0.00052,0.15,-0.083,-3.6,-0.0016,-0.0058,2.8e-05,0.019,-0.0077,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.1e-05,7.9e-05,0.0049,0.015,0.015,0.0081,0.042,0.042,0.036,4.6e-07,4.6e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26390000,0.98,-0.0098,-0.012,0.19,-0.032,-0.0067,0.0045,0.13,-0.075,-3.6,-0.0016,-0.0058,2.8e-05,0.019,-0.008,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.9e-05,0.0049,0.014,0.014,0.008,0.038,0.038,0.035,4.5e-07,4.5e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26490000,0.98,-0.0095,-0.011,0.19,-0.035,-0.0036,0.014,0.13,-0.075,-3.6,-0.0016,-0.0058,2.8e-05,0.019,-0.0079,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.1e-05,7.9e-05,0.0049,0.015,0.015,0.0081,0.042,0.042,0.035,4.5e-07,4.5e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26590000,0.98,-0.009,-0.012,0.19,-0.036,0.0044,0.014,0.12,-0.068,-3.6,-0.0016,-0.0058,2.8e-05,0.019,-0.0081,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.1e-05,7.9e-05,0.0049,0.014,0.014,0.008,0.038,0.038,0.035,4.4e-07,4.3e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26690000,0.98,-0.0088,-0.011,0.19,-0.038,0.0095,0.013,0.12,-0.067,-3.6,-0.0016,-0.0058,2.8e-05,0.019,-0.0081,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.1e-05,7.9e-05,0.0049,0.015,0.015,0.0081,0.042,0.042,0.035,4.4e-07,4.4e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26790000,0.98,-0.0086,-0.011,0.19,-0.046,0.013,0.012,0.11,-0.062,-3.6,-0.0016,-0.0058,2.8e-05,0.019,-0.0083,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.1e-05,7.9e-05,0.0049,0.014,0.014,0.008,0.038,0.038,0.035,4.3e-07,4.2e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26890000,0.98,-0.008,-0.011,0.19,-0.051,0.016,0.007,0.1,-0.06,-3.6,-0.0016,-0.0058,2.8e-05,0.019,-0.0083,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.1e-05,7.9e-05,0.0049,0.015,0.015,0.0081,0.042,0.042,0.036,4.3e-07,4.2e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26990000,0.98,-0.0074,-0.011,0.19,-0.058,0.023,0.0061,0.088,-0.054,-3.6,-0.0016,-0.0058,2.8e-05,0.019,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.1e-05,7.9e-05,0.0049,0.014,0.014,0.008,0.038,0.038,0.035,4.2e-07,4.1e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -27090000,0.98,-0.0073,-0.012,0.19,-0.06,0.03,0.0089,0.082,-0.052,-3.6,-0.0016,-0.0058,2.8e-05,0.019,-0.0087,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.1e-05,7.9e-05,0.005,0.015,0.015,0.0081,0.042,0.042,0.035,4.2e-07,4.1e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -27190000,0.98,-0.0073,-0.012,0.19,-0.066,0.035,0.011,0.071,-0.046,-3.6,-0.0016,-0.0058,2.8e-05,0.019,-0.0089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.1e-05,7.9e-05,0.005,0.014,0.014,0.008,0.038,0.038,0.035,4.1e-07,4e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -27290000,0.98,-0.0075,-0.013,0.19,-0.073,0.041,0.12,0.064,-0.042,-3.6,-0.0016,-0.0058,2.8e-05,0.019,-0.0089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.1e-05,7.9e-05,0.005,0.015,0.015,0.0081,0.042,0.042,0.035,4.1e-07,4e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -27390000,0.98,-0.0089,-0.015,0.19,-0.078,0.047,0.45,0.055,-0.035,-3.5,-0.0016,-0.0058,3e-05,0.02,-0.0092,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.2e-05,7.9e-05,0.005,0.013,0.013,0.008,0.038,0.038,0.035,4e-07,3.9e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -27490000,0.98,-0.01,-0.017,0.19,-0.082,0.053,0.76,0.047,-0.03,-3.5,-0.0016,-0.0058,3e-05,0.02,-0.0093,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.2e-05,8e-05,0.005,0.014,0.014,0.008,0.042,0.042,0.035,4e-07,4e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -27590000,0.98,-0.01,-0.016,0.19,-0.076,0.055,0.85,0.038,-0.026,-3.4,-0.0016,-0.0058,3e-05,0.02,-0.0094,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.2e-05,8e-05,0.005,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-07,3.9e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -27690000,0.98,-0.0089,-0.013,0.19,-0.072,0.052,0.76,0.031,-0.02,-3.3,-0.0016,-0.0058,3e-05,0.02,-0.0095,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.2e-05,8e-05,0.005,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-07,3.9e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -27790000,0.98,-0.0076,-0.011,0.19,-0.071,0.049,0.75,0.025,-0.018,-3.3,-0.0016,-0.0058,3e-05,0.02,-0.0089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.2e-05,8e-05,0.005,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-07,3.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27890000,0.98,-0.0072,-0.012,0.19,-0.078,0.056,0.79,0.017,-0.012,-3.2,-0.0016,-0.0058,3e-05,0.02,-0.009,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.2e-05,8e-05,0.005,0.014,0.014,0.0081,0.041,0.041,0.036,3.8e-07,3.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27990000,0.98,-0.0077,-0.012,0.19,-0.079,0.058,0.78,0.012,-0.011,-3.1,-0.0016,-0.0058,3.1e-05,0.019,-0.0087,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.2e-05,8e-05,0.005,0.013,0.013,0.008,0.038,0.038,0.035,3.7e-07,3.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28090000,0.98,-0.0079,-0.012,0.19,-0.082,0.059,0.78,0.0041,-0.0049,-3,-0.0016,-0.0058,3.1e-05,0.019,-0.0087,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.2e-05,8e-05,0.005,0.014,0.014,0.008,0.041,0.041,0.035,3.8e-07,3.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28190000,0.98,-0.0074,-0.012,0.19,-0.083,0.055,0.79,-0.0024,-0.0044,-3,-0.0016,-0.0058,3.1e-05,0.019,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.2e-05,8e-05,0.005,0.013,0.013,0.008,0.038,0.038,0.035,3.7e-07,3.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28290000,0.98,-0.0069,-0.012,0.19,-0.088,0.059,0.79,-0.011,0.0013,-2.9,-0.0016,-0.0058,3.1e-05,0.019,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.3e-05,8e-05,0.005,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-07,3.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28390000,0.98,-0.0069,-0.013,0.19,-0.088,0.061,0.79,-0.015,0.0043,-2.8,-0.0015,-0.0058,3.3e-05,0.019,-0.0083,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.3e-05,8e-05,0.005,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.6e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28490000,0.98,-0.0072,-0.014,0.19,-0.09,0.065,0.79,-0.024,0.011,-2.8,-0.0015,-0.0058,3.3e-05,0.019,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.3e-05,8.1e-05,0.005,0.014,0.014,0.0081,0.041,0.041,0.036,3.6e-07,3.6e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28590000,0.98,-0.0072,-0.014,0.19,-0.083,0.06,0.79,-0.028,0.0083,-2.7,-0.0015,-0.0058,3.3e-05,0.019,-0.0082,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.3e-05,8.1e-05,0.005,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.5e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28690000,0.98,-0.007,-0.013,0.19,-0.083,0.061,0.79,-0.036,0.014,-2.6,-0.0015,-0.0058,3.3e-05,0.019,-0.0083,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.3e-05,8.1e-05,0.005,0.014,0.014,0.008,0.041,0.041,0.035,3.6e-07,3.5e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28790000,0.98,-0.0063,-0.013,0.19,-0.08,0.061,0.79,-0.038,0.016,-2.5,-0.0015,-0.0058,3.5e-05,0.019,-0.0083,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.3e-05,8.1e-05,0.005,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-07,3.5e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28890000,0.98,-0.0062,-0.012,0.19,-0.084,0.064,0.78,-0.046,0.022,-2.5,-0.0015,-0.0058,3.5e-05,0.019,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.3e-05,8.1e-05,0.005,0.014,0.014,0.0081,0.041,0.041,0.036,3.5e-07,3.5e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28990000,0.98,-0.006,-0.013,0.19,-0.079,0.06,0.78,-0.046,0.022,-2.4,-0.0015,-0.0058,3.7e-05,0.019,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.3e-05,8.1e-05,0.005,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.4e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29090000,0.98,-0.0058,-0.013,0.19,-0.082,0.062,0.78,-0.054,0.028,-2.3,-0.0015,-0.0058,3.7e-05,0.02,-0.0086,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.3e-05,8.1e-05,0.005,0.014,0.014,0.008,0.041,0.041,0.035,3.5e-07,3.4e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29190000,0.98,-0.0058,-0.013,0.19,-0.078,0.061,0.78,-0.051,0.027,-2.2,-0.0015,-0.0058,4e-05,0.02,-0.0088,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.3e-05,8.1e-05,0.0051,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.4e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29290000,0.98,-0.006,-0.013,0.19,-0.08,0.067,0.78,-0.059,0.033,-2.2,-0.0015,-0.0058,4e-05,0.02,-0.0088,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.4e-05,8.1e-05,0.0051,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-07,3.4e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29390000,0.98,-0.0065,-0.012,0.19,-0.076,0.065,0.78,-0.057,0.034,-2.1,-0.0015,-0.0058,4.2e-05,0.02,-0.009,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.3e-05,8.1e-05,0.0051,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29490000,0.98,-0.0065,-0.012,0.19,-0.078,0.066,0.78,-0.065,0.041,-2,-0.0015,-0.0058,4.2e-05,0.02,-0.009,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.4e-05,8.1e-05,0.0051,0.014,0.014,0.0081,0.041,0.041,0.036,3.4e-07,3.3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29590000,0.98,-0.0064,-0.012,0.19,-0.074,0.064,0.78,-0.062,0.04,-1.9,-0.0015,-0.0058,4.4e-05,0.02,-0.0092,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.3e-05,8.1e-05,0.0051,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29690000,0.98,-0.0064,-0.012,0.19,-0.078,0.063,0.78,-0.07,0.046,-1.9,-0.0015,-0.0058,4.4e-05,0.02,-0.0093,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.4e-05,8.1e-05,0.0051,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-07,3.3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29790000,0.98,-0.0063,-0.013,0.19,-0.074,0.056,0.78,-0.065,0.043,-1.8,-0.0014,-0.0058,4.6e-05,0.02,-0.0096,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.4e-05,8.1e-05,0.0051,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29890000,0.98,-0.0057,-0.013,0.19,-0.074,0.057,0.77,-0.073,0.049,-1.7,-0.0014,-0.0058,4.6e-05,0.02,-0.0097,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.4e-05,8.1e-05,0.0051,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29990000,0.98,-0.0059,-0.013,0.19,-0.069,0.052,0.77,-0.068,0.044,-1.6,-0.0014,-0.0058,4.7e-05,0.02,-0.01,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.4e-05,8.1e-05,0.0051,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30090000,0.98,-0.006,-0.013,0.19,-0.069,0.053,0.77,-0.075,0.05,-1.6,-0.0014,-0.0058,4.7e-05,0.02,-0.01,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.4e-05,8.1e-05,0.0051,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30190000,0.98,-0.006,-0.013,0.19,-0.063,0.05,0.77,-0.068,0.048,-1.5,-0.0014,-0.0057,5e-05,0.02,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.4e-05,8.1e-05,0.0051,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.1e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30290000,0.98,-0.006,-0.013,0.19,-0.062,0.05,0.77,-0.074,0.053,-1.4,-0.0014,-0.0057,5e-05,0.02,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.4e-05,8.1e-05,0.0051,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30390000,0.98,-0.0061,-0.013,0.19,-0.055,0.044,0.76,-0.066,0.049,-1.4,-0.0014,-0.0057,5.2e-05,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.4e-05,8.1e-05,0.0051,0.013,0.013,0.0079,0.037,0.037,0.035,3.1e-07,3.1e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30490000,0.98,-0.0061,-0.013,0.19,-0.058,0.044,0.77,-0.072,0.054,-1.3,-0.0014,-0.0057,5.2e-05,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.4e-05,8.1e-05,0.0051,0.014,0.014,0.008,0.041,0.041,0.036,3.1e-07,3.1e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30590000,0.98,-0.0064,-0.013,0.19,-0.053,0.041,0.76,-0.065,0.05,-1.2,-0.0014,-0.0057,5.4e-05,0.021,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.4e-05,8.1e-05,0.0051,0.013,0.013,0.008,0.037,0.037,0.035,3.1e-07,3.1e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30690000,0.98,-0.0068,-0.014,0.19,-0.051,0.04,0.76,-0.07,0.054,-1.1,-0.0014,-0.0057,5.4e-05,0.021,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.4e-05,8.1e-05,0.0051,0.014,0.013,0.008,0.041,0.041,0.035,3.1e-07,3.1e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30790000,0.98,-0.0065,-0.013,0.19,-0.044,0.035,0.76,-0.063,0.052,-1.1,-0.0014,-0.0057,5.6e-05,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.3e-05,8.1e-05,0.0051,0.013,0.013,0.008,0.037,0.037,0.035,3e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30890000,0.98,-0.0058,-0.013,0.19,-0.044,0.032,0.76,-0.067,0.056,-1,-0.0014,-0.0057,5.6e-05,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.4e-05,8.1e-05,0.0051,0.013,0.013,0.008,0.041,0.041,0.035,3.1e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30990000,0.98,-0.006,-0.013,0.19,-0.037,0.026,0.76,-0.057,0.049,-0.94,-0.0014,-0.0057,5.7e-05,0.022,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.3e-05,8.1e-05,0.0052,0.013,0.013,0.0079,0.037,0.037,0.035,3e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31090000,0.98,-0.0062,-0.013,0.19,-0.036,0.025,0.76,-0.061,0.051,-0.86,-0.0014,-0.0057,5.7e-05,0.022,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.3e-05,8.1e-05,0.0052,0.013,0.013,0.008,0.041,0.04,0.036,3e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31190000,0.98,-0.0064,-0.013,0.19,-0.031,0.02,0.76,-0.052,0.046,-0.79,-0.0014,-0.0057,5.8e-05,0.022,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.3e-05,8.1e-05,0.0052,0.013,0.013,0.008,0.037,0.037,0.035,3e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31290000,0.98,-0.0066,-0.014,0.19,-0.028,0.018,0.76,-0.055,0.048,-0.72,-0.0014,-0.0057,5.8e-05,0.022,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.3e-05,8.1e-05,0.0052,0.013,0.013,0.008,0.04,0.04,0.035,3e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31390000,0.98,-0.0064,-0.013,0.19,-0.022,0.012,0.76,-0.046,0.042,-0.65,-0.0014,-0.0057,5.9e-05,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.3e-05,8.1e-05,0.0052,0.013,0.013,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31490000,0.98,-0.0061,-0.014,0.19,-0.022,0.0088,0.76,-0.049,0.043,-0.58,-0.0014,-0.0057,5.9e-05,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.3e-05,8.1e-05,0.0052,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31590000,0.98,-0.006,-0.014,0.19,-0.018,0.0066,0.76,-0.038,0.039,-0.51,-0.0014,-0.0057,6e-05,0.023,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.3e-05,8e-05,0.0052,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31690000,0.98,-0.006,-0.015,0.19,-0.02,0.0055,0.76,-0.04,0.039,-0.44,-0.0014,-0.0057,6e-05,0.023,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.3e-05,8.1e-05,0.0052,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31790000,0.98,-0.0062,-0.015,0.19,-0.011,0.0029,0.76,-0.028,0.037,-0.36,-0.0014,-0.0057,6.1e-05,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.3e-05,8e-05,0.0052,0.012,0.012,0.008,0.037,0.037,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31890000,0.98,-0.0059,-0.015,0.19,-0.008,0.00064,0.76,-0.029,0.038,-0.3,-0.0014,-0.0057,6.1e-05,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.3e-05,8e-05,0.0052,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31990000,0.98,-0.0062,-0.015,0.19,-0.00015,-2.2e-05,0.75,-0.017,0.034,-0.23,-0.0014,-0.0057,6.1e-05,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.3e-05,8e-05,0.0052,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32090000,0.98,-0.0065,-0.014,0.19,-0.00069,-0.0034,0.76,-0.017,0.034,-0.16,-0.0014,-0.0057,6.1e-05,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.3e-05,8e-05,0.0052,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32190000,0.98,-0.0067,-0.015,0.19,0.0046,-0.0066,0.76,-0.006,0.033,-0.092,-0.0013,-0.0057,6.2e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.2e-05,8e-05,0.0052,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32290000,0.98,-0.0066,-0.015,0.19,0.0062,-0.0094,0.75,-0.0055,0.032,-0.024,-0.0013,-0.0057,6.2e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.3e-05,8e-05,0.0052,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32390000,0.98,-0.0068,-0.015,0.19,0.012,-0.011,0.75,0.0057,0.03,0.051,-0.0013,-0.0057,6.2e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.2e-05,8e-05,0.0053,0.012,0.012,0.008,0.037,0.037,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32490000,0.98,-0.0096,-0.013,0.19,0.039,-0.074,-0.12,0.0089,0.023,0.054,-0.0013,-0.0057,6.2e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.2e-05,8e-05,0.0053,0.015,0.015,0.0078,0.04,0.04,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32590000,0.98,-0.0095,-0.013,0.19,0.039,-0.075,-0.12,0.021,0.02,0.035,-0.0014,-0.0057,6.2e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.1e-05,7.9e-05,0.0053,0.016,0.016,0.0075,0.037,0.037,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32690000,0.98,-0.0095,-0.013,0.19,0.035,-0.08,-0.12,0.025,0.012,0.02,-0.0014,-0.0057,6.2e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.1e-05,7.9e-05,0.0053,0.019,0.019,0.0074,0.041,0.041,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32790000,0.98,-0.0092,-0.013,0.19,0.034,-0.078,-0.12,0.034,0.01,0.0044,-0.0014,-0.0056,6.3e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,7.8e-05,7.6e-05,0.0053,0.02,0.02,0.0071,0.037,0.037,0.035,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32890000,0.98,-0.0092,-0.013,0.19,0.033,-0.084,-0.13,0.038,0.002,-0.011,-0.0014,-0.0056,6.3e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,7.8e-05,7.7e-05,0.0053,0.023,0.024,0.007,0.041,0.041,0.035,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32990000,0.98,-0.0089,-0.013,0.19,0.03,-0.08,-0.13,0.045,-0.0012,-0.024,-0.0014,-0.0056,6.3e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,7.4e-05,7.2e-05,0.0053,0.024,0.024,0.0067,0.038,0.038,0.035,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33090000,0.98,-0.0089,-0.013,0.19,0.026,-0.084,-0.12,0.048,-0.0093,-0.031,-0.0014,-0.0056,6.3e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,7.4e-05,7.2e-05,0.0053,0.029,0.029,0.0066,0.042,0.042,0.035,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33190000,0.98,-0.0085,-0.013,0.19,0.022,-0.079,-0.12,0.054,-0.011,-0.037,-0.0014,-0.0056,6.3e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,6.8e-05,6.7e-05,0.0053,0.029,0.029,0.0064,0.038,0.038,0.035,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33290000,0.98,-0.0086,-0.013,0.19,0.019,-0.08,-0.12,0.056,-0.019,-0.045,-0.0014,-0.0056,6.3e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,6.8e-05,6.7e-05,0.0053,0.035,0.035,0.0063,0.043,0.043,0.034,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33390000,0.98,-0.0081,-0.013,0.19,0.014,-0.066,-0.12,0.059,-0.014,-0.053,-0.0014,-0.0056,6.4e-05,0.025,-0.017,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,6.1e-05,6e-05,0.0053,0.035,0.035,0.0062,0.039,0.039,0.034,2.6e-07,2.6e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33490000,0.98,-0.0081,-0.013,0.19,0.0096,-0.067,-0.12,0.06,-0.021,-0.063,-0.0014,-0.0056,6.4e-05,0.025,-0.017,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00019,6.2e-05,6e-05,0.0053,0.042,0.042,0.0061,0.044,0.044,0.034,2.7e-07,2.6e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33590000,0.98,-0.0077,-0.013,0.19,0.0057,-0.058,-0.11,0.063,-0.017,-0.069,-0.0014,-0.0056,6.4e-05,0.024,-0.019,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0002,5.4e-05,5.3e-05,0.0053,0.04,0.041,0.006,0.04,0.04,0.034,2.6e-07,2.6e-07,6.4e-06,0.026,0.027,0.0005,0,0,0,0,0,0,0,0 -33690000,0.98,-0.0077,-0.013,0.19,0.001,-0.058,-0.11,0.063,-0.023,-0.077,-0.0014,-0.0056,6.4e-05,0.024,-0.019,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0002,5.5e-05,5.3e-05,0.0053,0.048,0.048,0.0059,0.046,0.046,0.034,2.6e-07,2.6e-07,6.4e-06,0.026,0.027,0.0005,0,0,0,0,0,0,0,0 -33790000,0.98,-0.0075,-0.013,0.19,-0.0022,-0.048,-0.11,0.067,-0.018,-0.083,-0.0014,-0.0056,6.4e-05,0.023,-0.022,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0002,4.8e-05,4.7e-05,0.0053,0.045,0.045,0.0059,0.041,0.041,0.034,2.6e-07,2.6e-07,6.4e-06,0.026,0.026,0.0005,0,0,0,0,0,0,0,0 -33890000,0.98,-0.0075,-0.013,0.19,-0.0064,-0.045,-0.11,0.066,-0.023,-0.089,-0.0014,-0.0056,6.4e-05,0.023,-0.022,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0002,4.8e-05,4.7e-05,0.0053,0.052,0.053,0.0058,0.047,0.047,0.033,2.6e-07,2.6e-07,6.4e-06,0.026,0.026,0.0005,0,0,0,0,0,0,0,0 -33990000,0.98,-0.0072,-0.013,0.19,-0.006,-0.031,-0.1,0.069,-0.015,-0.092,-0.0014,-0.0056,6.5e-05,0.02,-0.025,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0002,4.2e-05,4.1e-05,0.0054,0.047,0.047,0.0058,0.042,0.042,0.033,2.6e-07,2.6e-07,6.4e-06,0.025,0.025,0.0005,0,0,0,0,0,0,0,0 -34090000,0.98,-0.0072,-0.013,0.19,-0.01,-0.031,-0.1,0.069,-0.018,-0.096,-0.0014,-0.0056,6.5e-05,0.02,-0.025,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0002,4.2e-05,4.1e-05,0.0054,0.054,0.055,0.0058,0.049,0.049,0.033,2.6e-07,2.6e-07,6.4e-06,0.025,0.025,0.0005,0,0,0,0,0,0,0,0 -34190000,0.98,-0.0071,-0.013,0.19,-0.011,-0.02,-0.098,0.072,-0.013,-0.099,-0.0014,-0.0056,6.5e-05,0.018,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0002,3.8e-05,3.7e-05,0.0054,0.048,0.048,0.0058,0.043,0.043,0.033,2.6e-07,2.6e-07,6.4e-06,0.024,0.024,0.0005,0,0,0,0,0,0,0,0 -34290000,0.98,-0.0069,-0.013,0.19,-0.011,-0.02,-0.097,0.071,-0.015,-0.1,-0.0014,-0.0056,6.5e-05,0.018,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0002,3.8e-05,3.7e-05,0.0054,0.055,0.055,0.0058,0.05,0.05,0.033,2.6e-07,2.6e-07,6.4e-06,0.024,0.024,0.0005,0,0,0,0,0,0,0,0 -34390000,0.98,-0.0068,-0.013,0.19,-0.013,-0.01,-0.092,0.073,-0.01,-0.11,-0.0014,-0.0056,6.5e-05,0.017,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0002,3.4e-05,3.3e-05,0.0054,0.047,0.047,0.0058,0.044,0.044,0.033,2.6e-07,2.6e-07,6.4e-06,0.023,0.023,0.0005,0,0,0,0,0,0,0,0 -34490000,0.98,-0.0069,-0.013,0.19,-0.015,-0.0092,-0.089,0.071,-0.011,-0.11,-0.0014,-0.0056,6.5e-05,0.017,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0002,3.5e-05,3.3e-05,0.0054,0.053,0.054,0.0059,0.051,0.051,0.032,2.6e-07,2.6e-07,6.4e-06,0.023,0.023,0.0005,0,0,0,0,0,0,0,0 -34590000,0.98,-0.0069,-0.013,0.19,-0.014,-0.0049,0.71,0.073,-0.0088,-0.081,-0.0014,-0.0056,6.5e-05,0.015,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0002,3.2e-05,3.1e-05,0.0054,0.044,0.044,0.0059,0.045,0.045,0.032,2.7e-07,2.6e-07,6.4e-06,0.022,0.022,0.0005,0,0,0,0,0,0,0,0 -34690000,0.98,-0.0068,-0.012,0.19,-0.017,-0.0027,1.7,0.071,-0.0092,0.038,-0.0014,-0.0056,6.5e-05,0.015,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0002,3.2e-05,3.1e-05,0.0054,0.047,0.048,0.006,0.052,0.052,0.032,2.7e-07,2.6e-07,6.4e-06,0.022,0.022,0.0005,0,0,0,0,0,0,0,0 -34790000,0.98,-0.0068,-0.012,0.19,-0.018,0.0019,2.7,0.072,-0.0068,0.21,-0.0014,-0.0056,6.5e-05,0.017,-0.03,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0002,3.1e-05,3e-05,0.0054,0.04,0.04,0.0061,0.045,0.045,0.032,2.7e-07,2.7e-07,6.4e-06,0.021,0.021,0.0005,0,0,0,0,0,0,0,0 -34890000,0.98,-0.0068,-0.012,0.19,-0.022,0.0044,3.6,0.07,-0.0063,0.5,-0.0014,-0.0056,6.5e-05,0.017,-0.03,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0002,3.1e-05,3e-05,0.0054,0.044,0.044,0.0061,0.052,0.052,0.032,2.7e-07,2.7e-07,6.4e-06,0.021,0.021,0.0005,0,0,0,0,0,0,0,0 +10000,1,-0.011,-0.01,0.00023,0.00033,-0.00013,-0.01,1e-05,-3.8e-06,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00018,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +90000,1,-0.011,-0.01,0.00033,-0.001,-0.0031,-0.024,-3.8e-05,-0.00013,-0.0021,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00046,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +190000,1,-0.012,-0.011,0.00044,-0.0023,-0.003,-0.037,-0.00017,-0.00043,-0.017,4.7e-10,-5e-10,-1.5e-11,0,0,-6.8e-08,0,0,0,0,0,0,0,0,0.011,0.011,0.00094,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +290000,1,-0.012,-0.011,0.00045,-0.0033,-0.0044,-0.046,-0.00024,-0.00025,-0.018,3.9e-09,-5.9e-09,-4.7e-10,0,0,-2.9e-06,0,0,0,0,0,0,0,0,0.011,0.012,0.00077,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +390000,1,-0.012,-0.011,0.0005,-0.0025,-0.006,-0.063,-0.00056,-0.00072,-0.013,-7.2e-09,-5.8e-09,-1.3e-09,0,0,8.8e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +490000,1,-0.012,-0.012,0.00056,-0.0007,-0.0063,-0.069,-0.00015,-0.00047,-0.011,-1.2e-06,7.5e-07,-1.7e-07,0,0,1.6e-05,0,0,0,0,0,0,0,0,0.013,0.013,0.00073,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +590000,1,-0.012,-0.012,0.00058,-0.002,-0.009,-0.12,-0.00028,-0.0013,-0.029,-1.3e-06,7.8e-07,-1.8e-07,0,0,6.4e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.001,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +690000,1,-0.012,-0.012,0.00062,5.3e-05,-0.0089,-0.05,-8e-05,-0.00079,-0.0088,-5.6e-06,1.6e-06,-5.2e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,0.016,0.016,0.00062,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +790000,1,-0.012,-0.012,0.00062,0.0022,-0.011,-0.054,-2.3e-05,-0.0017,-0.011,-5.4e-06,1.7e-06,-5.1e-07,0,0,-0.00013,0,0,0,0,0,0,0,0,0.018,0.018,0.00079,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.0012,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +890000,1,-0.012,-0.013,0.00063,0.0031,-0.0085,-0.093,0.00015,-0.0011,-0.031,-2.2e-05,1.2e-06,-7.5e-07,0,0,-3.3e-05,0,0,0,0,0,0,0,0,0.019,0.019,0.00052,1.3,1.3,1.3,0.2,0.2,0.25,0.0099,0.0099,0.00067,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +990000,1,-0.012,-0.013,0.0006,0.006,-0.0099,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1.2e-06,-7.5e-07,0,0,1.3e-05,0,0,0,0,0,0,0,0,0.021,0.021,0.00064,1.5,1.5,0.95,0.3,0.3,0.23,0.0099,0.0099,0.00067,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1090000,1,-0.012,-0.013,0.00056,0.011,-0.013,-0.13,0.00077,-0.0015,-0.062,-6e-05,-1.5e-05,-1.8e-07,0,0,4.5e-05,0,0,0,0,0,0,0,0,0.023,0.023,0.00045,0.92,0.92,0.69,0.17,0.17,0.2,0.0098,0.0098,0.00042,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1190000,1,-0.012,-0.013,0.0005,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.8e-05,-1.3e-05,-2.2e-07,0,0,-0.00048,0,0,0,0,0,0,0,0,0.025,0.025,0.00053,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.00042,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1290000,1,-0.012,-0.014,0.00045,0.019,-0.018,-0.11,0.002,-0.0024,-0.048,-0.00017,-9.5e-05,3e-06,0,0,-0.00075,0,0,0,0,0,0,0,0,0.025,0.026,0.0004,0.87,0.87,0.41,0.15,0.15,0.18,0.0095,0.0095,0.00028,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1390000,1,-0.012,-0.014,0.00042,0.026,-0.023,-0.097,0.0043,-0.0045,-0.038,-0.00016,-9e-05,2.8e-06,0,0,-0.0014,0,0,0,0,0,0,0,0,0.028,0.028,0.00046,1.1,1.1,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00028,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1490000,1,-0.012,-0.014,0.0004,0.024,-0.021,-0.12,0.0034,-0.0033,-0.053,-0.00039,-0.00033,1.1e-05,0,0,-0.0012,0,0,0,0,0,0,0,0,0.027,0.027,0.00036,0.95,0.94,0.27,0.14,0.14,0.15,0.0088,0.0088,0.0002,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1590000,1,-0.012,-0.014,0.00042,0.031,-0.025,-0.13,0.0062,-0.0056,-0.063,-0.00039,-0.00033,1.1e-05,0,0,-0.0014,0,0,0,0,0,0,0,0,0.029,0.029,0.00041,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.0002,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1690000,1,-0.012,-0.014,0.00046,0.028,-0.02,-0.13,0.0044,-0.0038,-0.068,-0.00074,-0.00073,2.4e-05,0,0,-0.0018,0,0,0,0,0,0,0,0,0.025,0.025,0.00033,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.00015,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1790000,1,-0.012,-0.014,0.00041,0.036,-0.025,-0.13,0.0076,-0.006,-0.067,-0.00073,-0.00072,2.4e-05,0,0,-0.0028,0,0,0,0,0,0,0,0,0.028,0.028,0.00037,1.3,1.3,0.16,0.2,0.2,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +1890000,1,-0.012,-0.014,0.0004,0.043,-0.026,-0.14,0.012,-0.0085,-0.075,-0.00073,-0.00072,2.4e-05,0,0,-0.0032,0,0,0,0,0,0,0,0,0.03,0.03,0.00041,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +1990000,1,-0.011,-0.014,0.0004,0.035,-0.018,-0.14,0.0082,-0.0055,-0.074,-0.0011,-0.0013,3.9e-05,0,0,-0.0046,0,0,0,0,0,0,0,0,0.024,0.024,0.00033,1.3,1.3,0.13,0.2,0.2,0.11,0.0066,0.0066,0.00011,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +2090000,1,-0.011,-0.014,0.00042,0.042,-0.021,-0.14,0.012,-0.0076,-0.071,-0.0011,-0.0012,3.8e-05,0,0,-0.0065,0,0,0,0,0,0,0,0,0.026,0.026,0.00037,1.7,1.7,0.12,0.31,0.31,0.11,0.0066,0.0066,0.00011,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +2190000,1,-0.011,-0.014,0.00036,0.033,-0.014,-0.14,0.0081,-0.0045,-0.077,-0.0015,-0.0018,5.1e-05,0,0,-0.0075,0,0,0,0,0,0,0,0,0.02,0.02,0.0003,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,8.8e-05,0.04,0.04,0.038,0,0,0,0,0,0,0,0 +2290000,1,-0.011,-0.014,0.00035,0.038,-0.015,-0.14,0.012,-0.0059,-0.075,-0.0014,-0.0018,5.1e-05,0,0,-0.0098,0,0,0,0,0,0,0,0,0.022,0.022,0.00033,1.5,1.5,0.11,0.29,0.29,0.1,0.0055,0.0055,8.8e-05,0.04,0.04,0.038,0,0,0,0,0,0,0,0 +2390000,1,-0.011,-0.013,0.00035,0.029,-0.01,-0.14,0.0075,-0.0034,-0.072,-0.0017,-0.0023,6e-05,0,0,-0.012,0,0,0,0,0,0,0,0,0.016,0.016,0.00027,1,1,0.1,0.19,0.19,0.098,0.0045,0.0045,7e-05,0.04,0.04,0.038,0,0,0,0,0,0,0,0 +2490000,1,-0.011,-0.014,0.00042,0.033,-0.0092,-0.14,0.011,-0.0044,-0.079,-0.0017,-0.0023,6e-05,0,0,-0.013,0,0,0,0,0,0,0,0,0.017,0.017,0.0003,1.3,1.3,0.1,0.28,0.28,0.097,0.0045,0.0045,7e-05,0.04,0.04,0.037,0,0,0,0,0,0,0,0 +2590000,1,-0.01,-0.013,0.00032,0.023,-0.0062,-0.15,0.0066,-0.0025,-0.085,-0.0019,-0.0027,6.5e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.013,0.013,0.00025,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,5.7e-05,0.04,0.04,0.036,0,0,0,0,0,0,0,0 +2690000,1,-0.01,-0.013,0.00036,0.027,-0.0055,-0.15,0.0091,-0.0031,-0.084,-0.0019,-0.0027,6.5e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.014,0.014,0.00027,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,5.7e-05,0.04,0.04,0.036,0,0,0,0,0,0,0,0 +2790000,1,-0.01,-0.013,0.00029,0.022,-0.0031,-0.14,0.0059,-0.0017,-0.081,-0.002,-0.003,6.7e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.011,0.011,0.00023,0.76,0.77,0.096,0.16,0.16,0.089,0.0032,0.0032,4.7e-05,0.04,0.04,0.035,0,0,0,0,0,0,0,0 +2890000,1,-0.01,-0.013,0.00021,0.026,-0.0049,-0.14,0.0083,-0.0022,-0.081,-0.002,-0.003,6.7e-05,0,0,-0.025,0,0,0,0,0,0,0,0,0.012,0.012,0.00025,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,4.7e-05,0.04,0.04,0.034,0,0,0,0,0,0,0,0 +2990000,1,-0.01,-0.013,0.00022,0.02,-0.0038,-0.15,0.0054,-0.0013,-0.086,-0.002,-0.0033,6.8e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.009,0.009,0.00022,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,3.9e-05,0.04,0.04,0.033,0,0,0,0,0,0,0,0 +3090000,1,-0.01,-0.013,0.00042,0.025,-0.0067,-0.15,0.0077,-0.0019,-0.087,-0.002,-0.0033,6.8e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.01,0.01,0.00023,0.82,0.82,0.095,0.22,0.22,0.086,0.0027,0.0027,3.9e-05,0.04,0.04,0.032,0,0,0,0,0,0,0,0 +3190000,1,-0.01,-0.013,0.00045,0.021,-0.0065,-0.15,0.0051,-0.0014,-0.097,-0.0021,-0.0036,6.9e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.0078,0.0078,0.0002,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,3.3e-05,0.04,0.04,0.031,0,0,0,0,0,0,0,0 +3290000,1,-0.01,-0.013,0.00047,0.024,-0.0067,-0.15,0.0074,-0.0021,-0.11,-0.0021,-0.0036,6.9e-05,0,0,-0.034,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00022,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,3.3e-05,0.04,0.04,0.03,0,0,0,0,0,0,0,0 +3390000,1,-0.0098,-0.013,0.00047,0.019,-0.0036,-0.15,0.005,-0.0014,-0.1,-0.0021,-0.0038,6.9e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00019,0.53,0.53,0.095,0.14,0.14,0.085,0.0019,0.0019,2.8e-05,0.04,0.04,0.029,0,0,0,0,0,0,0,0 +3490000,1,-0.0097,-0.013,0.00045,0.025,-0.0024,-0.15,0.0073,-0.0017,-0.1,-0.0021,-0.0038,6.9e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.0076,0.0076,0.0002,0.65,0.65,0.095,0.19,0.19,0.086,0.0019,0.0019,2.8e-05,0.04,0.04,0.028,0,0,0,0,0,0,0,0 +3590000,1,-0.0096,-0.013,0.0004,0.022,-0.0019,-0.15,0.0051,-0.001,-0.11,-0.0022,-0.004,6.8e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.0061,0.0061,0.00018,0.48,0.48,0.094,0.13,0.13,0.086,0.0016,0.0016,2.4e-05,0.04,0.04,0.026,0,0,0,0,0,0,0,0 +3690000,1,-0.0096,-0.013,0.00038,0.024,-0.0014,-0.15,0.0075,-0.0013,-0.11,-0.0022,-0.004,6.8e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.0067,0.0068,0.00019,0.59,0.59,0.093,0.18,0.18,0.085,0.0016,0.0016,2.4e-05,0.04,0.04,0.025,0,0,0,0,0,0,0,0 +3790000,1,-0.0095,-0.012,0.00039,0.02,0.0031,-0.15,0.0052,-0.0006,-0.11,-0.0022,-0.0042,6.7e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.0055,0.0055,0.00017,0.44,0.44,0.093,0.12,0.12,0.086,0.0014,0.0014,2.1e-05,0.04,0.04,0.024,0,0,0,0,0,0,0,0 +3890000,1,-0.0094,-0.013,0.00047,0.022,0.0042,-0.14,0.0074,-0.00025,-0.11,-0.0022,-0.0042,6.6e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.006,0.006,0.00018,0.54,0.54,0.091,0.17,0.17,0.086,0.0014,0.0014,2.1e-05,0.04,0.04,0.022,0,0,0,0,0,0,0,0 +3990000,1,-0.0094,-0.013,0.00053,0.027,0.0038,-0.14,0.0099,7.7e-05,-0.11,-0.0022,-0.0042,6.6e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.0066,0.0066,0.00019,0.66,0.66,0.089,0.22,0.22,0.085,0.0014,0.0014,2.1e-05,0.04,0.04,0.021,0,0,0,0,0,0,0,0 +4090000,1,-0.0094,-0.012,0.00059,0.023,0.0031,-0.12,0.0074,0.00033,-0.098,-0.0022,-0.0044,6.4e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.0053,0.0053,0.00017,0.5,0.5,0.087,0.16,0.16,0.085,0.0011,0.0011,1.8e-05,0.04,0.04,0.02,0,0,0,0,0,0,0,0 +4190000,1,-0.0095,-0.012,0.00055,0.025,0.0027,-0.12,0.0098,0.00061,-0.1,-0.0022,-0.0044,6.4e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.0058,0.0058,0.00018,0.6,0.6,0.086,0.21,0.21,0.086,0.0011,0.0011,1.8e-05,0.04,0.04,0.019,0,0,0,0,0,0,0,0 +4290000,1,-0.0095,-0.012,0.00055,0.023,0.0026,-0.12,0.0071,0.00053,-0.11,-0.0022,-0.0046,6.2e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.46,0.46,0.084,0.15,0.15,0.085,0.00095,0.00095,1.6e-05,0.04,0.04,0.017,0,0,0,0,0,0,0,0 +4390000,1,-0.0095,-0.012,0.0005,0.026,0.00099,-0.11,0.0097,0.00061,-0.094,-0.0022,-0.0046,6.2e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.0052,0.0052,0.00017,0.55,0.55,0.081,0.2,0.2,0.084,0.00095,0.00095,1.6e-05,0.04,0.04,0.016,0,0,0,0,0,0,0,0 +4490000,1,-0.0095,-0.012,0.00056,0.022,0.0028,-0.11,0.0071,0.00052,-0.095,-0.0022,-0.0048,5.9e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.0042,0.0042,0.00015,0.42,0.42,0.08,0.14,0.14,0.085,0.00078,0.00078,1.4e-05,0.04,0.04,0.015,0,0,0,0,0,0,0,0 +4590000,1,-0.0095,-0.012,0.00062,0.025,0.0015,-0.11,0.0095,0.00072,-0.098,-0.0022,-0.0048,5.9e-05,0,0,-0.089,0,0,0,0,0,0,0,0,0.0045,0.0045,0.00016,0.51,0.51,0.077,0.19,0.19,0.084,0.00078,0.00078,1.4e-05,0.04,0.04,0.014,0,0,0,0,0,0,0,0 +4690000,1,-0.0095,-0.012,0.00055,0.019,0.0018,-0.1,0.0069,0.00052,-0.09,-0.0022,-0.005,5.7e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00015,0.39,0.39,0.074,0.14,0.14,0.083,0.00064,0.00064,1.3e-05,0.04,0.04,0.013,0,0,0,0,0,0,0,0 +4790000,1,-0.0094,-0.012,0.00064,0.017,0.0039,-0.099,0.0087,0.00084,-0.092,-0.0022,-0.005,5.7e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.004,0.004,0.00015,0.47,0.47,0.073,0.18,0.18,0.084,0.00064,0.00064,1.3e-05,0.04,0.04,0.012,0,0,0,0,0,0,0,0 +4890000,1,-0.0093,-0.012,0.00067,0.012,0.0015,-0.093,0.0059,0.00065,-0.088,-0.0021,-0.0051,5.5e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,0.07,0.13,0.13,0.083,0.00052,0.00052,1.1e-05,0.04,0.04,0.011,0,0,0,0,0,0,0,0 +4990000,1,-0.0093,-0.012,0.00065,0.016,0.0021,-0.085,0.0073,0.00085,-0.083,-0.0021,-0.0051,5.5e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0035,0.0035,0.00015,0.43,0.43,0.067,0.17,0.17,0.082,0.00052,0.00052,1.1e-05,0.04,0.04,0.01,0,0,0,0,0,0,0,0 +5090000,1,-0.0092,-0.012,0.00071,0.012,0.0026,-0.082,0.0051,0.00061,-0.081,-0.0021,-0.0052,5.3e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,0.065,0.12,0.12,0.082,0.00042,0.00042,1e-05,0.04,0.04,0.0098,0,0,0,0,0,0,0,0 +5190000,1,-0.009,-0.012,0.00076,0.012,0.006,-0.08,0.0063,0.001,-0.079,-0.0021,-0.0052,5.3e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.003,0.003,0.00014,0.39,0.39,0.063,0.16,0.16,0.081,0.00042,0.00042,1e-05,0.04,0.04,0.0091,0,0,0,0,0,0,0,0 +5290000,1,-0.0089,-0.012,0.00081,0.01,0.0062,-0.068,0.0044,0.00098,-0.072,-0.0021,-0.0053,5.1e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0024,0.0024,0.00013,0.3,0.3,0.06,0.12,0.12,0.08,0.00034,0.00034,9.1e-06,0.04,0.04,0.0084,0,0,0,0,0,0,0,0 +5390000,1,-0.0088,-0.012,0.0008,0.0099,0.0098,-0.065,0.0054,0.0017,-0.067,-0.0021,-0.0053,5.1e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0026,0.0026,0.00014,0.36,0.36,0.057,0.15,0.15,0.079,0.00034,0.00034,9.1e-06,0.04,0.04,0.0078,0,0,0,0,0,0,0,0 +5490000,1,-0.0089,-0.012,0.0008,0.0091,0.011,-0.06,0.0037,0.0017,-0.065,-0.0021,-0.0054,5e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,8.3e-06,0.04,0.04,0.0073,0,0,0,0,0,0,0,0 +5590000,1,-0.0089,-0.012,0.00072,0.011,0.015,-0.053,0.0048,0.003,-0.058,-0.0021,-0.0054,5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00013,0.32,0.32,0.053,0.15,0.15,0.078,0.00028,0.00028,8.3e-06,0.04,0.04,0.0067,0,0,0,0,0,0,0,0 +5690000,1,-0.0089,-0.011,0.00061,0.0095,0.015,-0.052,0.0034,0.0027,-0.055,-0.002,-0.0055,4.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.25,0.25,0.051,0.11,0.11,0.076,0.00022,0.00022,7.5e-06,0.04,0.04,0.0062,0,0,0,0,0,0,0,0 +5790000,1,-0.0088,-0.011,0.00056,0.011,0.017,-0.049,0.0045,0.0042,-0.053,-0.002,-0.0055,4.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0019,0.0019,0.00013,0.29,0.29,0.05,0.14,0.14,0.077,0.00022,0.00022,7.5e-06,0.04,0.04,0.0058,0,0,0,0,0,0,0,0 +5890000,1,-0.0088,-0.011,0.00059,0.011,0.015,-0.048,0.0034,0.0035,-0.056,-0.002,-0.0055,4.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00012,0.23,0.23,0.048,0.1,0.1,0.075,0.00018,0.00018,6.9e-06,0.04,0.04,0.0054,0,0,0,0,0,0,0,0 +5990000,1,-0.0088,-0.012,0.00056,0.013,0.016,-0.041,0.0046,0.005,-0.05,-0.002,-0.0055,4.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00012,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.005,0,0,0,0,0,0,0,0 +6090000,1,-0.0088,-0.012,0.00037,0.013,0.017,-0.039,0.0059,0.0067,-0.047,-0.002,-0.0055,4.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00013,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.0047,0,0,0,0,0,0,0,0 +6190000,0.98,-0.0066,-0.013,0.19,0.0098,0.016,-0.037,0.0045,0.0054,-0.047,-0.0019,-0.0056,4.4e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.22,0.22,0.042,0.13,0.13,0.073,0.00015,0.00015,6.3e-06,0.04,0.04,0.0044,0,0,0,0,0,0,0,0 +6290000,0.98,-0.0065,-0.013,0.19,0.0083,0.018,-0.041,0.0055,0.0071,-0.053,-0.0019,-0.0056,4.4e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.22,0.22,0.04,0.16,0.16,0.072,0.00015,0.00015,6.3e-06,0.04,0.04,0.0041,0,0,0,0,0,0,0,0 +6390000,0.98,-0.0065,-0.013,0.19,0.011,0.02,-0.042,0.0064,0.009,-0.056,-0.0019,-0.0056,4.4e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.23,0.23,0.039,0.19,0.19,0.072,0.00015,0.00015,6.3e-06,0.04,0.04,0.0038,0,0,0,0,0,0,0,0 +6490000,0.98,-0.0064,-0.013,0.19,0.0084,0.019,-0.039,0.0073,0.011,-0.053,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.24,0.24,0.038,0.23,0.23,0.07,0.00015,0.00015,6.3e-06,0.04,0.04,0.0036,0,0,0,0,0,0,0,0 +6590000,0.98,-0.0064,-0.013,0.19,0.0078,0.022,-0.042,0.0082,0.013,-0.056,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.26,0.26,0.036,0.28,0.28,0.069,0.00015,0.00015,6.3e-06,0.04,0.04,0.0033,0,0,0,0,0,0,0,0 +6690000,0.98,-0.0063,-0.013,0.19,0.0052,0.025,-0.044,0.0088,0.015,-0.057,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.28,0.28,0.035,0.33,0.33,0.068,0.00015,0.00015,6.3e-06,0.04,0.04,0.0031,0,0,0,0,0,0,0,0 +6790000,0.98,-0.0063,-0.013,0.19,0.007,0.027,-0.042,0.0093,0.018,-0.058,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.3,0.3,0.034,0.38,0.38,0.068,0.00015,0.00015,6.3e-06,0.04,0.04,0.0029,0,0,0,0,0,0,0,0 +6890000,0.98,-0.0061,-0.013,0.19,0.0066,0.028,-0.038,0.01,0.02,-0.055,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0015,0.0015,0.018,0.32,0.32,0.032,0.45,0.45,0.067,0.00015,0.00015,6.3e-06,0.04,0.04,0.0027,0,0,0,0,0,0,0,0 +6990000,0.98,-0.006,-0.013,0.19,0.0066,0.029,-0.037,0.011,0.023,-0.055,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0015,0.0015,0.018,0.35,0.35,0.031,0.52,0.52,0.066,0.00015,0.00015,6.3e-06,0.04,0.04,0.0026,0,0,0,0,0,0,0,0 +7090000,0.98,-0.0059,-0.013,0.19,0.0058,0.035,-0.037,0.011,0.027,-0.056,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0015,0.0015,0.018,0.39,0.39,0.03,0.6,0.6,0.066,0.00015,0.00015,6.3e-06,0.04,0.04,0.0024,0,0,0,0,0,0,0,0 +7190000,0.98,-0.0058,-0.013,0.19,0.0054,0.038,-0.036,0.012,0.03,-0.058,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0015,0.0015,0.018,0.42,0.42,0.029,0.69,0.69,0.065,0.00015,0.00015,6.3e-06,0.04,0.04,0.0023,0,0,0,0,0,0,0,0 +7290000,0.98,-0.0058,-0.013,0.19,0.0062,0.043,-0.034,0.012,0.034,-0.054,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.0016,0.018,0.46,0.46,0.028,0.79,0.79,0.064,0.00015,0.00015,6.3e-06,0.04,0.04,0.0021,0,0,0,0,0,0,0,0 +7390000,0.98,-0.0057,-0.013,0.19,0.0045,0.046,-0.032,0.013,0.038,-0.052,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.0016,0.018,0.51,0.51,0.027,0.9,0.9,0.064,0.00014,0.00014,6.3e-06,0.04,0.04,0.002,0,0,0,0,0,0,0,0 +7490000,0.98,-0.0057,-0.013,0.19,0.0068,0.05,-0.026,0.013,0.043,-0.046,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.0016,0.018,0.56,0.56,0.026,1,1,0.063,0.00014,0.00014,6.3e-06,0.04,0.04,0.0019,0,0,0,0,0,0,0,0 +7590000,0.98,-0.0057,-0.013,0.19,0.0078,0.053,-0.023,0.014,0.048,-0.041,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0017,0.0017,0.018,0.6,0.6,0.025,1.2,1.2,0.062,0.00014,0.00014,6.3e-06,0.04,0.04,0.0018,0,0,0,0,0,0,0,0 +7690000,0.98,-0.0057,-0.013,0.19,0.0075,0.058,-0.022,0.015,0.053,-0.036,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0017,0.0017,0.018,0.66,0.66,0.025,1.3,1.3,0.062,0.00014,0.00014,6.3e-06,0.04,0.04,0.0017,0,0,0,0,0,0,0,0 +7790000,0.98,-0.0056,-0.013,0.19,0.0091,0.06,-0.024,0.015,0.058,-0.041,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0017,0.0017,0.018,0.72,0.72,0.024,1.5,1.5,0.061,0.00014,0.00014,6.3e-06,0.04,0.04,0.0016,0,0,0,0,0,0,0,0 +7890000,0.98,-0.0056,-0.013,0.19,0.0078,0.066,-0.025,0.016,0.065,-0.045,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0018,0.0018,0.018,0.78,0.78,0.023,1.7,1.7,0.06,0.00014,0.00014,6.3e-06,0.04,0.04,0.0015,0,0,0,0,0,0,0,0 +7990000,0.98,-0.0056,-0.013,0.19,0.0079,0.068,-0.021,0.017,0.07,-0.041,-0.0019,-0.0056,4.3e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0018,0.0018,0.018,0.84,0.84,0.022,1.9,1.9,0.059,0.00014,0.00014,6.3e-06,0.04,0.04,0.0014,0,0,0,0,0,0,0,0 +8090000,0.98,-0.0054,-0.013,0.19,0.0095,0.074,-0.022,0.017,0.077,-0.044,-0.0019,-0.0056,4.3e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0019,0.0019,0.018,0.91,0.91,0.022,2.1,2.1,0.059,0.00014,0.00014,6.3e-06,0.04,0.04,0.0014,0,0,0,0,0,0,0,0 +8190000,0.98,-0.0055,-0.013,0.19,0.01,0.08,-0.018,0.018,0.085,-0.038,-0.0019,-0.0056,4.3e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0019,0.0019,0.018,0.99,0.99,0.021,2.4,2.4,0.058,0.00014,0.00014,6.3e-06,0.04,0.04,0.0013,0,0,0,0,0,0,0,0 +8290000,0.98,-0.0055,-0.013,0.19,0.012,0.084,-0.016,0.019,0.091,-0.038,-0.0019,-0.0056,4.3e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.002,0.002,0.018,1.1,1.1,0.02,2.6,2.6,0.057,0.00014,0.00014,6.3e-06,0.04,0.04,0.0012,0,0,0,0,0,0,0,0 +8390000,0.98,-0.0054,-0.013,0.19,0.01,0.088,-0.015,0.02,0.1,-0.036,-0.0019,-0.0056,4.3e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.002,0.002,0.018,1.1,1.1,0.02,2.9,2.9,0.057,0.00014,0.00014,6.3e-06,0.04,0.04,0.0012,0,0,0,0,0,0,0,0 +8490000,0.98,-0.0053,-0.013,0.19,0.0097,0.091,-0.017,0.021,0.11,-0.041,-0.0018,-0.0056,4.3e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.002,0.002,0.018,1.2,1.2,0.019,3.2,3.2,0.056,0.00014,0.00014,6.3e-06,0.04,0.04,0.0011,0,0,0,0,0,0,0,0 +8590000,0.98,-0.0053,-0.013,0.19,0.011,0.095,-0.012,0.022,0.12,-0.036,-0.0018,-0.0056,4.3e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0021,0.0021,0.018,1.3,1.3,0.018,3.6,3.6,0.055,0.00014,0.00014,6.3e-06,0.04,0.04,0.0011,0,0,0,0,0,0,0,0 +8690000,0.98,-0.0053,-0.013,0.19,0.011,0.096,-0.014,0.022,0.12,-0.037,-0.0018,-0.0056,4.2e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0021,0.0021,0.018,1.4,1.4,0.018,3.9,3.9,0.055,0.00013,0.00013,6.3e-06,0.04,0.04,0.001,0,0,0,0,0,0,0,0 +8790000,0.98,-0.0053,-0.013,0.19,0.012,0.1,-0.013,0.023,0.13,-0.035,-0.0018,-0.0056,4.2e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0022,0.018,1.5,1.5,0.018,4.3,4.3,0.055,0.00013,0.00013,6.3e-06,0.04,0.04,0.00096,0,0,0,0,0,0,0,0 +8890000,0.98,-0.0054,-0.013,0.19,0.012,0.1,-0.0091,0.023,0.14,-0.029,-0.0018,-0.0056,4.2e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0022,0.018,1.5,1.5,0.017,4.6,4.6,0.054,0.00013,0.00013,6.3e-06,0.04,0.04,0.00091,0,0,0,0,0,0,0,0 +8990000,0.98,-0.0053,-0.013,0.19,0.011,0.11,-0.0083,0.024,0.15,-0.032,-0.0018,-0.0056,4.2e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0022,0.018,1.6,1.6,0.017,5.2,5.2,0.054,0.00013,0.00013,6.3e-06,0.04,0.04,0.00088,0,0,0,0,0,0,0,0 +9090000,0.98,-0.0053,-0.013,0.19,0.011,0.11,-0.0093,0.024,0.15,-0.032,-0.0018,-0.0056,4.1e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0022,0.018,1.7,1.7,0.016,5.4,5.4,0.053,0.00013,0.00013,6.3e-06,0.04,0.04,0.00084,0,0,0,0,0,0,0,0 +9190000,0.98,-0.0053,-0.013,0.19,0.014,0.11,-0.0088,0.025,0.16,-0.032,-0.0018,-0.0056,4.1e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0023,0.018,1.8,1.8,0.016,6,6.1,0.052,0.00013,0.00013,6.3e-06,0.04,0.04,0.0008,0,0,0,0,0,0,0,0 +9290000,0.98,-0.0052,-0.013,0.19,0.016,0.11,-0.0072,0.025,0.16,-0.03,-0.0018,-0.0056,4e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0022,0.018,1.8,1.8,0.015,6.3,6.3,0.052,0.00012,0.00012,6.3e-06,0.04,0.04,0.00076,0,0,0,0,0,0,0,0 +9390000,0.98,-0.0051,-0.013,0.19,0.016,0.12,-0.006,0.027,0.17,-0.03,-0.0018,-0.0056,4e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0023,0.018,1.9,1.9,0.015,7,7,0.052,0.00012,0.00012,6.3e-06,0.04,0.04,0.00073,0,0,0,0,0,0,0,0 +9490000,0.98,-0.0052,-0.013,0.19,0.016,0.11,-0.0044,0.027,0.17,-0.027,-0.0017,-0.0056,3.9e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0022,0.018,1.9,1.9,0.015,7.2,7.2,0.051,0.00012,0.00012,6.3e-06,0.04,0.04,0.0007,0,0,0,0,0,0,0,0 +9590000,0.98,-0.0052,-0.013,0.19,0.016,0.12,-0.0043,0.028,0.18,-0.028,-0.0017,-0.0056,3.9e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0023,0.018,2,2,0.014,7.9,7.9,0.05,0.00012,0.00012,6.3e-06,0.04,0.04,0.00067,0,0,0,0,0,0,0,0 +9690000,0.98,-0.0053,-0.013,0.19,0.015,0.11,-0.0014,0.028,0.18,-0.027,-0.0017,-0.0056,3.8e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0022,0.018,2,2,0.014,8,8.1,0.05,0.00012,0.00012,6.3e-06,0.04,0.04,0.00065,0,0,0,0,0,0,0,0 +9790000,0.98,-0.0053,-0.013,0.19,0.016,0.12,-0.0027,0.029,0.19,-0.028,-0.0017,-0.0056,3.8e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0023,0.018,2.1,2.1,0.014,8.9,8.9,0.05,0.00012,0.00012,6.3e-06,0.04,0.04,0.00062,0,0,0,0,0,0,0,0 +9890000,0.98,-0.0054,-0.013,0.19,0.018,0.11,-0.0014,0.028,0.19,-0.029,-0.0016,-0.0056,3.7e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0022,0.018,2.1,2.1,0.013,8.9,8.9,0.049,0.00011,0.00011,6.3e-06,0.04,0.04,0.0006,0,0,0,0,0,0,0,0 +9990000,0.98,-0.0054,-0.013,0.19,0.02,0.12,-0.00072,0.03,0.2,-0.031,-0.0016,-0.0056,3.7e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0022,0.018,2.2,2.2,0.013,9.8,9.8,0.049,0.00011,0.00011,6.3e-06,0.04,0.04,0.00058,0,0,0,0,0,0,0,0 +10090000,0.98,-0.0055,-0.013,0.19,0.017,0.11,0.00048,0.029,0.19,-0.029,-0.0016,-0.0057,3.6e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0021,0.0021,0.018,2.1,2.1,0.013,9.7,9.7,0.048,0.00011,0.00011,6.3e-06,0.04,0.04,0.00056,0,0,0,0,0,0,0,0 +10190000,0.98,-0.0054,-0.013,0.19,0.016,0.11,0.0014,0.03,0.2,-0.03,-0.0016,-0.0057,3.6e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0022,0.018,2.3,2.3,0.012,11,11,0.048,0.00011,0.00011,6.3e-06,0.04,0.04,0.00054,0,0,0,0,0,0,0,0 +10290000,0.98,-0.0055,-0.013,0.19,0.016,0.11,0.0003,0.032,0.21,-0.029,-0.0016,-0.0057,3.6e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0023,0.018,2.4,2.4,0.012,12,12,0.048,0.00011,0.00011,6.3e-06,0.04,0.04,0.00052,0,0,0,0,0,0,0,0 +10390000,0.98,-0.0054,-0.013,0.19,0.0071,0.0052,-0.0025,0.00076,0.00015,-0.028,-0.0016,-0.0057,3.6e-05,-3.6e-08,2.5e-08,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0023,0.018,0.25,0.25,0.56,0.25,0.25,0.048,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10490000,0.98,-0.0053,-0.012,0.19,0.0085,0.0077,0.007,0.0015,0.00076,-0.023,-0.0016,-0.0057,3.6e-05,-1.2e-06,8.3e-07,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0024,0.018,0.26,0.26,0.55,0.26,0.26,0.057,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10590000,0.98,-0.0053,-0.012,0.19,-0.0012,0.0055,0.013,-0.0012,-0.0054,-0.021,-0.0016,-0.0057,3.6e-05,0.00032,9.5e-06,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.0025,0.018,0.13,0.13,0.27,0.13,0.13,0.055,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10690000,0.98,-0.0052,-0.012,0.19,-5.2e-05,0.0068,0.016,-0.0012,-0.0048,-0.017,-0.0016,-0.0057,3.6e-05,0.00032,1e-05,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.0025,0.018,0.15,0.15,0.26,0.14,0.14,0.065,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10790000,0.98,-0.0054,-0.013,0.19,0.0018,0.0031,0.014,-0.00078,-0.0047,-0.015,-0.0016,-0.0057,3.4e-05,0.00052,0.00048,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.0025,0.018,0.1,0.1,0.17,0.091,0.091,0.062,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10890000,0.98,-0.0053,-0.013,0.19,0.0019,0.0066,0.01,-0.00059,-0.0042,-0.018,-0.0016,-0.0057,3.4e-05,0.00053,0.00048,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0026,0.018,0.12,0.12,0.16,0.098,0.098,0.068,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10990000,0.98,-0.0054,-0.013,0.19,0.0014,0.012,0.016,-0.00045,-0.003,-0.011,-0.0015,-0.0057,3.4e-05,0.00068,0.00072,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0024,0.018,0.096,0.096,0.12,0.073,0.073,0.065,9.9e-05,9.9e-05,6.3e-06,0.039,0.039,0.0005,0,0,0,0,0,0,0,0 +11090000,0.98,-0.0055,-0.013,0.19,0.0024,0.017,0.02,-0.0003,-0.0016,-0.0074,-0.0015,-0.0057,3.4e-05,0.00068,0.00072,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.0025,0.018,0.12,0.12,0.11,0.08,0.08,0.069,9.9e-05,9.9e-05,6.3e-06,0.039,0.039,0.0005,0,0,0,0,0,0,0,0 +11190000,0.98,-0.0058,-0.013,0.19,0.0041,0.017,0.026,0.0011,-0.0018,-0.00035,-0.0015,-0.0057,3.1e-05,0.00067,0.0016,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0022,0.018,0.096,0.096,0.083,0.063,0.063,0.066,9.1e-05,9.1e-05,6.3e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 +11290000,0.98,-0.0058,-0.013,0.19,0.0043,0.018,0.026,0.0015,-1.7e-05,-0.00012,-0.0015,-0.0057,3.1e-05,0.00067,0.0016,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0023,0.018,0.12,0.12,0.077,0.07,0.07,0.069,9.1e-05,9.1e-05,6.3e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 +11390000,0.98,-0.006,-0.013,0.19,0.0026,0.015,0.016,0.00089,-0.00087,-0.0086,-0.0014,-0.0058,2.9e-05,0.0012,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.002,0.0019,0.018,0.097,0.097,0.062,0.057,0.057,0.066,8.3e-05,8.3e-05,6.3e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 +11490000,0.98,-0.0059,-0.013,0.19,0.0017,0.017,0.02,0.001,0.00073,-0.0025,-0.0014,-0.0058,2.9e-05,0.0012,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.002,0.002,0.018,0.12,0.12,0.057,0.065,0.065,0.067,8.3e-05,8.3e-05,6.3e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 +11590000,0.98,-0.0062,-0.012,0.19,0.0034,0.013,0.018,0.00085,-0.00036,-0.0036,-0.0013,-0.0058,2.7e-05,0.0015,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0017,0.0017,0.018,0.096,0.096,0.048,0.054,0.054,0.065,7.5e-05,7.5e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0 +11690000,0.98,-0.0062,-0.012,0.19,0.0039,0.017,0.018,0.0012,0.0011,-0.0049,-0.0013,-0.0058,2.7e-05,0.0015,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0018,0.0018,0.018,0.12,0.12,0.044,0.062,0.062,0.066,7.5e-05,7.5e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0 +11790000,0.98,-0.0066,-0.012,0.19,0.0025,0.011,0.019,0.0007,-0.0018,-0.002,-0.0012,-0.0059,2.3e-05,0.002,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0015,0.0015,0.018,0.092,0.092,0.037,0.052,0.052,0.063,6.8e-05,6.8e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +11890000,0.98,-0.0067,-0.012,0.19,0.0052,0.012,0.017,0.001,-0.00069,-0.0013,-0.0012,-0.0059,2.3e-05,0.002,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0015,0.0015,0.018,0.11,0.11,0.034,0.061,0.061,0.063,6.8e-05,6.8e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +11990000,0.98,-0.0069,-0.012,0.19,0.0081,0.012,0.015,0.0021,-0.0018,-0.0049,-0.0012,-0.0059,2.3e-05,0.002,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0013,0.0013,0.018,0.088,0.088,0.03,0.051,0.051,0.061,6.2e-05,6.2e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12090000,0.98,-0.0068,-0.012,0.19,0.0097,0.012,0.018,0.003,-0.00063,0.0011,-0.0012,-0.0059,2.3e-05,0.002,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0013,0.0013,0.018,0.11,0.11,0.027,0.06,0.06,0.06,6.2e-05,6.2e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12190000,0.98,-0.0067,-0.012,0.19,0.0078,0.011,0.017,0.0018,0.00039,0.0029,-0.0012,-0.0059,2.2e-05,0.0023,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0012,0.0012,0.018,0.083,0.083,0.024,0.05,0.05,0.058,5.7e-05,5.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12290000,0.98,-0.0068,-0.012,0.19,0.0055,0.011,0.016,0.0025,0.0015,0.0039,-0.0012,-0.0059,2.2e-05,0.0023,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0012,0.0012,0.018,0.098,0.098,0.022,0.059,0.059,0.058,5.7e-05,5.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12390000,0.98,-0.0069,-0.012,0.19,0.0041,0.0072,0.014,0.0017,0.00049,-0.0021,-0.0012,-0.006,2.1e-05,0.0025,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0011,0.0011,0.018,0.078,0.078,0.02,0.05,0.05,0.056,5.3e-05,5.3e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12490000,0.98,-0.0069,-0.012,0.19,0.0041,0.0082,0.018,0.0021,0.0013,-6.6e-05,-0.0012,-0.006,2.1e-05,0.0025,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0011,0.0011,0.018,0.091,0.091,0.018,0.059,0.059,0.055,5.3e-05,5.3e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12590000,0.98,-0.0071,-0.012,0.19,0.0078,0.0015,0.02,0.0033,-0.0014,0.0017,-0.0011,-0.006,2e-05,0.0025,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00098,0.00098,0.018,0.072,0.072,0.017,0.049,0.049,0.054,5e-05,5e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12690000,0.98,-0.007,-0.012,0.19,0.0083,-0.00064,0.019,0.0041,-0.0013,0.0033,-0.0011,-0.006,2e-05,0.0025,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.001,0.001,0.018,0.084,0.084,0.016,0.058,0.058,0.053,5e-05,5e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12790000,0.98,-0.0073,-0.012,0.19,0.0099,-0.0041,0.021,0.0041,-0.0044,0.0054,-0.0011,-0.006,1.8e-05,0.0026,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00093,0.00093,0.018,0.068,0.068,0.014,0.049,0.049,0.052,4.7e-05,4.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12890000,0.98,-0.0073,-0.012,0.19,0.01,-0.005,0.022,0.0052,-0.0049,0.0085,-0.0011,-0.006,1.8e-05,0.0026,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00096,0.00096,0.018,0.078,0.078,0.013,0.058,0.058,0.051,4.7e-05,4.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12990000,0.98,-0.0072,-0.012,0.19,0.0079,-0.0029,0.022,0.0036,-0.0036,0.0096,-0.0011,-0.006,1.9e-05,0.0026,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00089,0.00089,0.018,0.064,0.064,0.012,0.049,0.049,0.05,4.5e-05,4.5e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13090000,0.98,-0.0073,-0.012,0.19,0.0088,-0.0028,0.02,0.0044,-0.0038,0.0085,-0.0011,-0.006,1.9e-05,0.0027,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00092,0.00092,0.018,0.073,0.073,0.012,0.057,0.057,0.049,4.5e-05,4.5e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13190000,0.98,-0.0073,-0.012,0.19,0.0038,-0.0045,0.019,0.00094,-0.0046,0.0091,-0.0011,-0.006,1.8e-05,0.0028,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00086,0.00086,0.018,0.06,0.06,0.011,0.049,0.049,0.047,4.3e-05,4.3e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13290000,0.98,-0.0073,-0.012,0.19,0.0034,-0.0055,0.016,0.0013,-0.005,0.0085,-0.0011,-0.006,1.8e-05,0.0028,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00089,0.00089,0.018,0.068,0.068,0.01,0.057,0.057,0.047,4.3e-05,4.3e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13390000,0.98,-0.0072,-0.012,0.19,0.0026,-0.0035,0.016,0.00083,-0.0037,0.0091,-0.0011,-0.006,1.9e-05,0.0028,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00084,0.00084,0.018,0.056,0.056,0.0097,0.049,0.049,0.046,4e-05,4e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13490000,0.98,-0.0072,-0.012,0.19,0.003,-0.0018,0.015,0.0011,-0.0039,0.0053,-0.0011,-0.006,1.9e-05,0.0029,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00086,0.00086,0.018,0.064,0.064,0.0093,0.057,0.057,0.045,4e-05,4e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13590000,0.98,-0.0072,-0.012,0.19,0.0075,-0.002,0.017,0.004,-0.0032,0.0038,-0.0011,-0.006,1.9e-05,0.0031,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00082,0.00082,0.018,0.053,0.053,0.0088,0.048,0.048,0.044,3.8e-05,3.9e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13690000,0.98,-0.0072,-0.012,0.19,0.0075,-0.0035,0.017,0.0047,-0.0034,0.0064,-0.0011,-0.006,1.9e-05,0.0031,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00085,0.00085,0.018,0.061,0.061,0.0085,0.056,0.056,0.044,3.8e-05,3.9e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13790000,0.98,-0.0071,-0.012,0.19,0.014,0.0007,0.017,0.0083,-0.00094,0.0059,-0.0011,-0.0059,2e-05,0.0035,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00081,0.00081,0.018,0.051,0.051,0.0082,0.048,0.048,0.043,3.7e-05,3.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13890000,0.98,-0.007,-0.012,0.19,0.016,0.0014,0.018,0.0098,-0.00083,0.0081,-0.0011,-0.0059,2e-05,0.0035,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00084,0.00084,0.018,0.058,0.058,0.008,0.056,0.056,0.042,3.7e-05,3.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13990000,0.98,-0.0071,-0.012,0.19,0.015,0.0015,0.017,0.0074,-0.0023,0.007,-0.0011,-0.006,1.9e-05,0.0033,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0008,0.0008,0.018,0.049,0.049,0.0077,0.048,0.048,0.041,3.5e-05,3.5e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +14090000,0.98,-0.0071,-0.012,0.19,0.013,-0.0029,0.018,0.0088,-0.0024,0.0034,-0.0011,-0.006,1.9e-05,0.0034,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00083,0.00083,0.018,0.055,0.055,0.0076,0.055,0.055,0.041,3.5e-05,3.5e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +14190000,0.98,-0.0071,-0.011,0.19,0.0099,-0.0016,0.018,0.008,-0.0018,0.0036,-0.0011,-0.006,1.9e-05,0.0035,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0008,0.00079,0.018,0.047,0.047,0.0074,0.048,0.048,0.04,3.3e-05,3.3e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +14290000,0.98,-0.007,-0.011,0.19,0.012,-0.0017,0.016,0.009,-0.002,0.0079,-0.0011,-0.006,1.9e-05,0.0035,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00082,0.00082,0.018,0.053,0.053,0.0073,0.055,0.055,0.04,3.3e-05,3.3e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +14390000,0.98,-0.0071,-0.011,0.19,0.012,-0.0047,0.017,0.0084,-0.0031,0.012,-0.0011,-0.006,1.9e-05,0.0033,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00079,0.00079,0.018,0.045,0.045,0.0071,0.048,0.048,0.039,3.1e-05,3.1e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14490000,0.98,-0.0072,-0.011,0.19,0.01,-0.0045,0.021,0.0094,-0.0036,0.015,-0.0011,-0.006,1.9e-05,0.0033,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00081,0.00081,0.018,0.051,0.051,0.0071,0.055,0.055,0.038,3.1e-05,3.1e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14590000,0.98,-0.0073,-0.011,0.19,0.0078,-0.0046,0.019,0.0059,-0.0042,0.011,-0.0011,-0.006,1.8e-05,0.0031,0.0033,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00078,0.00078,0.018,0.044,0.044,0.007,0.047,0.047,0.038,2.9e-05,2.9e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14690000,0.98,-0.0073,-0.011,0.19,0.007,-0.0046,0.019,0.0066,-0.0047,0.011,-0.0011,-0.006,1.8e-05,0.0031,0.0032,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0008,0.0008,0.018,0.05,0.05,0.007,0.054,0.054,0.037,2.9e-05,2.9e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14790000,0.98,-0.0072,-0.011,0.19,0.0087,0.0024,0.019,0.0053,0.00078,0.014,-0.0012,-0.006,2.1e-05,0.0032,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00077,0.00077,0.018,0.043,0.043,0.0069,0.047,0.047,0.037,2.7e-05,2.7e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14890000,0.98,-0.0071,-0.011,0.19,0.0074,2.6e-05,0.023,0.006,0.00091,0.014,-0.0012,-0.006,2.1e-05,0.0032,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0008,0.0008,0.018,0.049,0.049,0.007,0.054,0.054,0.037,2.7e-05,2.7e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14990000,0.98,-0.0073,-0.011,0.19,0.0061,-0.0016,0.026,0.0047,-0.0007,0.017,-0.0012,-0.0061,2e-05,0.0031,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00076,0.00076,0.018,0.042,0.042,0.0069,0.047,0.047,0.036,2.6e-05,2.6e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +15090000,0.98,-0.0072,-0.011,0.19,0.0062,-0.00055,0.03,0.0053,-0.00085,0.019,-0.0012,-0.0061,2e-05,0.0031,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00079,0.00079,0.019,0.048,0.048,0.007,0.054,0.054,0.036,2.6e-05,2.6e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +15190000,0.98,-0.0073,-0.011,0.19,0.0043,-0.0016,0.03,0.0042,-0.00077,0.021,-0.0012,-0.0061,2e-05,0.003,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00075,0.00075,0.019,0.041,0.041,0.007,0.047,0.047,0.036,2.4e-05,2.4e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +15290000,0.98,-0.0074,-0.011,0.19,0.0049,-0.0027,0.03,0.0047,-0.00096,0.018,-0.0012,-0.0061,2e-05,0.0033,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00078,0.00078,0.019,0.047,0.047,0.0071,0.054,0.054,0.035,2.4e-05,2.4e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +15390000,0.98,-0.0075,-0.011,0.19,0.0051,-0.0003,0.029,0.0037,-0.00066,0.018,-0.0012,-0.0061,2e-05,0.0034,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00074,0.00074,0.019,0.041,0.041,0.0071,0.047,0.047,0.035,2.2e-05,2.2e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15490000,0.98,-0.0076,-0.011,0.19,0.0045,-0.0029,0.029,0.0042,-0.00079,0.019,-0.0012,-0.0061,2e-05,0.0035,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00076,0.00076,0.019,0.046,0.046,0.0072,0.053,0.053,0.035,2.2e-05,2.2e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15590000,0.98,-0.0078,-0.011,0.19,0.0081,-0.0067,0.029,0.0062,-0.0047,0.018,-0.0011,-0.0061,1.8e-05,0.0039,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00073,0.00073,0.019,0.04,0.04,0.0072,0.047,0.047,0.035,2.1e-05,2.1e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15690000,0.98,-0.0077,-0.011,0.19,0.0099,-0.0099,0.029,0.0072,-0.0055,0.019,-0.0011,-0.0061,1.8e-05,0.004,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00075,0.00075,0.019,0.045,0.045,0.0073,0.053,0.053,0.034,2.1e-05,2.1e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15790000,0.98,-0.0077,-0.011,0.19,0.0064,-0.0092,0.029,0.0055,-0.0043,0.02,-0.0011,-0.0061,1.9e-05,0.0039,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00072,0.00072,0.019,0.04,0.04,0.0073,0.046,0.046,0.034,1.9e-05,1.9e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15890000,0.98,-0.0078,-0.011,0.19,0.0053,-0.0076,0.03,0.0061,-0.0052,0.02,-0.0011,-0.0061,1.9e-05,0.0041,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00073,0.00073,0.019,0.045,0.045,0.0074,0.053,0.053,0.034,1.9e-05,1.9e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15990000,0.98,-0.0076,-0.011,0.19,0.0033,-0.0061,0.027,0.0048,-0.004,0.019,-0.0012,-0.0061,1.9e-05,0.0043,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0007,0.0007,0.019,0.039,0.039,0.0074,0.046,0.046,0.034,1.7e-05,1.7e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +16090000,0.98,-0.0076,-0.011,0.19,0.0026,-0.0074,0.024,0.0051,-0.0046,0.019,-0.0012,-0.0061,1.9e-05,0.0044,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00072,0.00072,0.019,0.044,0.044,0.0076,0.053,0.053,0.034,1.7e-05,1.7e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +16190000,0.98,-0.0075,-0.011,0.19,-0.0013,-0.005,0.023,0.0027,-0.0034,0.016,-0.0012,-0.0061,2e-05,0.0045,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00068,0.00068,0.019,0.039,0.039,0.0076,0.046,0.046,0.034,1.6e-05,1.6e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16290000,0.98,-0.0075,-0.011,0.19,-0.00099,-0.0065,0.023,0.0026,-0.004,0.017,-0.0012,-0.0061,2e-05,0.0046,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0007,0.0007,0.019,0.043,0.043,0.0077,0.053,0.053,0.034,1.6e-05,1.6e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16390000,0.98,-0.0075,-0.011,0.19,0.0015,-0.0058,0.023,0.0036,-0.0031,0.017,-0.0012,-0.0061,2e-05,0.0051,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00067,0.00067,0.019,0.038,0.038,0.0077,0.046,0.046,0.034,1.5e-05,1.5e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16490000,0.98,-0.0076,-0.011,0.19,0.0034,-0.0074,0.026,0.0039,-0.0038,0.021,-0.0012,-0.0061,2e-05,0.005,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00068,0.00068,0.019,0.043,0.043,0.0079,0.053,0.053,0.034,1.5e-05,1.5e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16590000,0.98,-0.0075,-0.011,0.19,0.0075,-0.0074,0.029,0.0034,-0.0029,0.021,-0.0012,-0.0061,2.1e-05,0.0052,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00065,0.00065,0.019,0.037,0.037,0.0079,0.046,0.046,0.034,1.3e-05,1.3e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16690000,0.98,-0.0076,-0.011,0.19,0.009,-0.012,0.029,0.0042,-0.0039,0.022,-0.0012,-0.0061,2.1e-05,0.0053,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00066,0.00066,0.019,0.042,0.042,0.008,0.053,0.053,0.034,1.3e-05,1.3e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16790000,0.98,-0.0074,-0.011,0.19,0.0098,-0.011,0.028,0.0033,-0.0028,0.022,-0.0012,-0.0061,2.1e-05,0.0054,0.0027,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00063,0.00063,0.019,0.037,0.037,0.008,0.046,0.046,0.034,1.2e-05,1.2e-05,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +16890000,0.98,-0.0074,-0.011,0.19,0.0089,-0.011,0.029,0.0042,-0.0039,0.02,-0.0012,-0.0061,2.1e-05,0.0057,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00065,0.00064,0.019,0.041,0.041,0.0082,0.052,0.052,0.034,1.2e-05,1.2e-05,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +16990000,0.98,-0.0074,-0.011,0.19,0.0086,-0.011,0.029,0.004,-0.0029,0.019,-0.0013,-0.0061,2.2e-05,0.0063,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00062,0.00061,0.019,0.036,0.036,0.0082,0.046,0.046,0.034,1.1e-05,1.1e-05,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +17090000,0.98,-0.0075,-0.011,0.19,0.01,-0.013,0.028,0.005,-0.0041,0.018,-0.0013,-0.0061,2.2e-05,0.0065,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00063,0.00063,0.019,0.041,0.041,0.0083,0.052,0.052,0.034,1.1e-05,1.1e-05,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +17190000,0.98,-0.0076,-0.011,0.19,0.0089,-0.018,0.03,0.0033,-0.0076,0.021,-0.0012,-0.0061,2.1e-05,0.0063,0.0021,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.0006,0.0006,0.019,0.036,0.036,0.0083,0.046,0.046,0.034,9.9e-06,9.9e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +17290000,0.98,-0.0076,-0.011,0.19,0.0098,-0.019,0.03,0.0043,-0.0094,0.021,-0.0012,-0.0061,2.1e-05,0.0065,0.0019,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00061,0.00061,0.019,0.04,0.04,0.0084,0.052,0.052,0.034,9.9e-06,9.9e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +17390000,0.98,-0.0074,-0.011,0.19,0.0066,-0.018,0.029,0.0057,-0.0059,0.021,-0.0013,-0.006,2.3e-05,0.0073,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00058,0.00058,0.019,0.035,0.035,0.0084,0.046,0.046,0.034,8.9e-06,8.9e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +17490000,0.98,-0.0075,-0.011,0.19,0.0046,-0.019,0.029,0.0062,-0.0078,0.023,-0.0013,-0.006,2.3e-05,0.0074,0.0024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00059,0.00059,0.019,0.039,0.039,0.0085,0.052,0.052,0.034,8.9e-06,8.9e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +17590000,0.98,-0.0074,-0.011,0.19,0.0008,-0.015,0.028,0.0024,-0.0058,0.02,-0.0013,-0.0061,2.4e-05,0.0072,0.0029,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00056,0.00056,0.019,0.034,0.034,0.0085,0.046,0.046,0.034,8.1e-06,8.1e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17690000,0.98,-0.0075,-0.011,0.19,-0.00015,-0.016,0.029,0.0025,-0.0074,0.023,-0.0013,-0.0061,2.4e-05,0.0073,0.0029,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00057,0.00057,0.019,0.038,0.038,0.0086,0.052,0.052,0.034,8.1e-06,8.1e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17790000,0.98,-0.0074,-0.011,0.19,0.0025,-0.014,0.029,0.0034,-0.0062,0.028,-0.0014,-0.006,2.5e-05,0.0076,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00055,0.00055,0.019,0.034,0.034,0.0086,0.046,0.046,0.034,7.3e-06,7.3e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17890000,0.98,-0.0073,-0.011,0.19,0.0046,-0.016,0.029,0.0039,-0.0077,0.032,-0.0014,-0.006,2.5e-05,0.0075,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00056,0.00056,0.019,0.037,0.037,0.0086,0.052,0.052,0.035,7.3e-06,7.3e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17990000,0.98,-0.0071,-0.011,0.19,0.004,-0.0093,0.029,0.0031,-0.002,0.033,-0.0014,-0.006,2.7e-05,0.0079,0.0046,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00053,0.00053,0.019,0.033,0.033,0.0086,0.045,0.045,0.034,6.6e-06,6.6e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +18090000,0.98,-0.0072,-0.011,0.19,0.0036,-0.0099,0.028,0.0035,-0.003,0.031,-0.0014,-0.006,2.7e-05,0.0082,0.0044,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00054,0.00054,0.019,0.036,0.036,0.0087,0.052,0.052,0.035,6.6e-06,6.6e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +18190000,0.98,-0.0072,-0.011,0.19,0.0036,-0.0088,0.028,0.0041,-0.0022,0.029,-0.0014,-0.006,2.7e-05,0.0087,0.0043,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00052,0.00052,0.019,0.032,0.032,0.0086,0.045,0.045,0.035,6e-06,6e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +18290000,0.98,-0.0072,-0.011,0.19,0.0045,-0.0093,0.027,0.0045,-0.0031,0.027,-0.0014,-0.006,2.7e-05,0.009,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00053,0.00052,0.019,0.036,0.036,0.0087,0.051,0.051,0.035,6e-06,6e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +18390000,0.98,-0.0072,-0.011,0.19,0.0054,-0.008,0.027,0.0061,-0.0023,0.026,-0.0014,-0.006,2.7e-05,0.0096,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00051,0.0005,0.019,0.031,0.031,0.0086,0.045,0.045,0.035,5.4e-06,5.4e-06,6.3e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0 +18490000,0.98,-0.0072,-0.011,0.19,0.0081,-0.0081,0.026,0.0069,-0.0032,0.028,-0.0014,-0.006,2.7e-05,0.0096,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00051,0.00051,0.019,0.035,0.035,0.0087,0.051,0.051,0.035,5.4e-06,5.4e-06,6.3e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0 +18590000,0.98,-0.007,-0.011,0.19,0.0065,-0.0074,0.026,0.0055,-0.0024,0.031,-0.0015,-0.006,2.8e-05,0.0095,0.0043,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00049,0.00049,0.019,0.031,0.031,0.0087,0.045,0.045,0.035,4.9e-06,4.9e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +18690000,0.98,-0.007,-0.011,0.19,0.0066,-0.0064,0.024,0.0062,-0.0031,0.029,-0.0015,-0.006,2.8e-05,0.0097,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0005,0.0005,0.019,0.034,0.034,0.0087,0.051,0.051,0.035,4.9e-06,4.9e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +18790000,0.98,-0.007,-0.011,0.19,0.0056,-0.006,0.024,0.0062,-0.0025,0.027,-0.0015,-0.006,2.8e-05,0.01,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00048,0.00048,0.019,0.03,0.03,0.0087,0.045,0.045,0.035,4.4e-06,4.4e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +18890000,0.98,-0.0069,-0.011,0.19,0.0043,-0.0057,0.021,0.0067,-0.0032,0.023,-0.0015,-0.006,2.8e-05,0.01,0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00049,0.00048,0.019,0.033,0.033,0.0087,0.051,0.051,0.035,4.4e-06,4.4e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +18990000,0.98,-0.0069,-0.011,0.19,0.0026,-0.0058,0.022,0.0055,-0.0025,0.026,-0.0015,-0.006,2.8e-05,0.01,0.0039,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00047,0.00047,0.019,0.029,0.029,0.0086,0.045,0.045,0.035,4e-06,4e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19090000,0.98,-0.007,-0.011,0.19,0.0006,-0.0063,0.023,0.0057,-0.0031,0.022,-0.0015,-0.006,2.8e-05,0.011,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00048,0.00047,0.019,0.032,0.032,0.0087,0.051,0.051,0.036,4e-06,4e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19190000,0.98,-0.0069,-0.011,0.19,-0.00087,-0.0059,0.022,0.0048,-0.0025,0.022,-0.0015,-0.006,2.8e-05,0.011,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00046,0.00046,0.019,0.028,0.028,0.0086,0.045,0.045,0.036,3.7e-06,3.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19290000,0.98,-0.0068,-0.011,0.19,-0.0017,-0.0058,0.023,0.0047,-0.0031,0.021,-0.0015,-0.006,2.8e-05,0.011,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00046,0.00046,0.019,0.031,0.031,0.0087,0.05,0.051,0.036,3.7e-06,3.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19390000,0.98,-0.0069,-0.011,0.19,-0.0022,-0.0023,0.024,0.004,-0.0012,0.019,-0.0015,-0.006,2.9e-05,0.011,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00045,0.00045,0.019,0.028,0.028,0.0086,0.045,0.045,0.036,3.3e-06,3.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19490000,0.98,-0.007,-0.011,0.19,-0.003,-0.0023,0.023,0.0038,-0.0014,0.019,-0.0015,-0.006,2.9e-05,0.011,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00045,0.00045,0.019,0.03,0.03,0.0087,0.05,0.05,0.036,3.3e-06,3.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19590000,0.98,-0.0069,-0.011,0.19,-0.0041,-0.0052,0.025,0.0044,-0.0024,0.019,-0.0015,-0.006,2.9e-05,0.012,0.0032,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00044,0.00044,0.019,0.027,0.027,0.0086,0.044,0.044,0.036,3e-06,3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19690000,0.98,-0.0069,-0.011,0.19,-0.0058,-0.0037,0.023,0.0039,-0.0028,0.019,-0.0015,-0.006,2.9e-05,0.012,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00045,0.00044,0.019,0.03,0.03,0.0086,0.05,0.05,0.036,3e-06,3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19790000,0.98,-0.007,-0.011,0.19,-0.0058,-0.0023,0.022,0.0063,-0.0023,0.014,-0.0015,-0.006,2.9e-05,0.012,0.0028,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00043,0.00043,0.019,0.026,0.026,0.0086,0.044,0.044,0.036,2.8e-06,2.8e-06,6.3e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0 +19890000,0.98,-0.0071,-0.011,0.19,-0.0058,-0.002,0.022,0.0057,-0.0025,0.013,-0.0015,-0.006,2.9e-05,0.013,0.0027,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00044,0.00043,0.019,0.029,0.029,0.0086,0.05,0.05,0.036,2.8e-06,2.8e-06,6.3e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0 +19990000,0.98,-0.0071,-0.011,0.19,-0.0055,-0.0019,0.019,0.0061,-0.00092,0.0097,-0.0015,-0.0059,2.9e-05,0.013,0.0026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00043,0.00042,0.019,0.026,0.026,0.0085,0.044,0.044,0.036,2.5e-06,2.5e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20090000,0.98,-0.0071,-0.011,0.19,-0.005,-0.0042,0.019,0.0055,-0.0012,0.013,-0.0015,-0.0059,2.9e-05,0.013,0.0026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00043,0.00042,0.019,0.028,0.028,0.0086,0.05,0.05,0.036,2.5e-06,2.5e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20190000,0.98,-0.0071,-0.011,0.19,-0.0039,-0.0016,0.02,0.0065,-0.00092,0.013,-0.0015,-0.0059,2.9e-05,0.013,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00042,0.00041,0.019,0.025,0.025,0.0085,0.044,0.044,0.036,2.3e-06,2.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20290000,0.98,-0.0071,-0.011,0.19,-0.0071,-0.0027,0.02,0.006,-0.0011,0.013,-0.0015,-0.0059,2.9e-05,0.013,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00042,0.00042,0.019,0.027,0.027,0.0085,0.049,0.049,0.036,2.3e-06,2.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20390000,0.98,-0.007,-0.011,0.19,-0.0078,-0.0015,0.021,0.0069,-0.00078,0.014,-0.0015,-0.0059,3e-05,0.014,0.0024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00041,0.00041,0.019,0.024,0.024,0.0084,0.044,0.044,0.036,2.1e-06,2.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20490000,0.98,-0.007,-0.011,0.19,-0.012,-0.0025,0.02,0.0059,-0.00096,0.012,-0.0015,-0.0059,3e-05,0.014,0.0023,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00041,0.00041,0.019,0.027,0.027,0.0085,0.049,0.049,0.036,2.1e-06,2.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20590000,0.98,-0.007,-0.011,0.19,-0.011,-0.0034,0.02,0.0069,-0.0008,0.011,-0.0015,-0.0059,3e-05,0.014,0.0021,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00041,0.0004,0.019,0.024,0.024,0.0084,0.044,0.044,0.036,2e-06,2e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20690000,0.98,-0.0069,-0.011,0.19,-0.013,-0.0022,0.021,0.0057,-0.001,0.011,-0.0015,-0.0059,3e-05,0.014,0.0021,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00041,0.0004,0.019,0.026,0.026,0.0084,0.049,0.049,0.036,2e-06,2e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20790000,0.98,-0.0063,-0.011,0.19,-0.016,0.00039,0.0055,0.0048,-0.00082,0.0097,-0.0015,-0.0059,3e-05,0.015,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0004,0.00039,0.019,0.023,0.023,0.0084,0.043,0.043,0.036,1.8e-06,1.8e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20890000,0.98,0.0028,-0.0073,0.19,-0.022,0.012,-0.11,0.0029,-0.00014,0.0034,-0.0015,-0.0059,3e-05,0.015,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0004,0.00039,0.019,0.026,0.026,0.0084,0.049,0.049,0.036,1.8e-06,1.8e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20990000,0.98,0.0061,-0.0038,0.19,-0.032,0.03,-0.25,0.0022,0.00051,-0.011,-0.0015,-0.0059,3e-05,0.015,0.0018,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00039,0.019,0.023,0.023,0.0083,0.043,0.043,0.036,1.7e-06,1.7e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21090000,0.98,0.0045,-0.0042,0.19,-0.046,0.046,-0.37,-0.0017,0.0044,-0.042,-0.0015,-0.0059,3e-05,0.015,0.0018,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00039,0.019,0.026,0.026,0.0084,0.048,0.048,0.036,1.7e-06,1.7e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21190000,0.98,0.0017,-0.0059,0.19,-0.049,0.05,-0.5,-0.0013,0.0035,-0.078,-0.0014,-0.0059,2.9e-05,0.015,0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00038,0.00038,0.019,0.023,0.023,0.0083,0.043,0.043,0.036,1.6e-06,1.6e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21290000,0.98,-0.00051,-0.0072,0.19,-0.049,0.054,-0.63,-0.0062,0.0087,-0.14,-0.0014,-0.0059,2.9e-05,0.015,0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00038,0.019,0.026,0.026,0.0083,0.048,0.048,0.036,1.6e-06,1.6e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21390000,0.98,-0.002,-0.0079,0.19,-0.045,0.05,-0.75,-0.005,0.011,-0.2,-0.0014,-0.0059,2.9e-05,0.015,0.00077,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00038,0.00037,0.019,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21490000,0.98,-0.0028,-0.0083,0.19,-0.04,0.047,-0.89,-0.0093,0.016,-0.29,-0.0014,-0.0059,2.9e-05,0.015,0.00067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00038,0.00037,0.019,0.026,0.026,0.0083,0.048,0.048,0.036,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21590000,0.98,-0.0033,-0.0083,0.19,-0.032,0.043,-1,-0.008,0.016,-0.38,-0.0014,-0.0059,2.9e-05,0.015,0.00063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.019,0.023,0.023,0.0082,0.043,0.043,0.036,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21690000,0.98,-0.0036,-0.0082,0.19,-0.029,0.039,-1.1,-0.011,0.021,-0.49,-0.0014,-0.0059,2.9e-05,0.015,0.00046,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.019,0.025,0.025,0.0083,0.048,0.048,0.036,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21790000,0.98,-0.004,-0.0084,0.19,-0.021,0.033,-1.3,-0.0038,0.018,-0.61,-0.0014,-0.0058,2.9e-05,0.016,0.00027,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00036,0.02,0.023,0.023,0.0082,0.043,0.043,0.036,1.2e-06,1.2e-06,6.3e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 +21890000,0.98,-0.0043,-0.0085,0.19,-0.018,0.028,-1.4,-0.0057,0.021,-0.75,-0.0014,-0.0058,2.9e-05,0.016,0.00013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-06,1.2e-06,6.3e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 +21990000,0.98,-0.005,-0.0088,0.19,-0.014,0.023,-1.4,-0.00038,0.017,-0.89,-0.0014,-0.0058,2.9e-05,0.015,0.00038,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00035,0.02,0.022,0.022,0.0082,0.043,0.043,0.036,1.2e-06,1.1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22090000,0.98,-0.0057,-0.0096,0.19,-0.012,0.019,-1.4,-0.0017,0.019,-1,-0.0014,-0.0058,2.9e-05,0.016,0.00025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00035,0.02,0.024,0.024,0.0082,0.048,0.048,0.036,1.2e-06,1.1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22190000,0.98,-0.0062,-0.0099,0.19,-0.0035,0.013,-1.4,0.006,0.013,-1.2,-0.0014,-0.0058,2.9e-05,0.016,0.00029,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00035,0.02,0.021,0.021,0.0081,0.043,0.043,0.036,1.1e-06,1.1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22290000,0.98,-0.0069,-0.01,0.19,0.0016,0.0079,-1.4,0.0059,0.014,-1.3,-0.0014,-0.0058,2.9e-05,0.016,0.00019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00035,0.02,0.023,0.023,0.0081,0.048,0.048,0.036,1.1e-06,1.1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22390000,0.98,-0.0072,-0.01,0.19,0.0066,-0.0017,-1.4,0.013,0.0042,-1.5,-0.0014,-0.0058,2.8e-05,0.016,-0.00016,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.021,0.021,0.0081,0.043,0.043,0.036,1e-06,1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22490000,0.98,-0.0074,-0.011,0.19,0.011,-0.0077,-1.4,0.014,0.0036,-1.6,-0.0014,-0.0058,2.8e-05,0.016,-0.00021,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00034,0.02,0.022,0.022,0.0081,0.047,0.047,0.036,1e-06,1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22590000,0.98,-0.0073,-0.011,0.19,0.02,-0.017,-1.4,0.026,-0.0053,-1.7,-0.0014,-0.0058,2.8e-05,0.016,-0.00036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.02,0.02,0.0081,0.042,0.042,0.036,9.4e-07,9.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22690000,0.98,-0.0072,-0.012,0.19,0.022,-0.021,-1.4,0.028,-0.0072,-1.9,-0.0014,-0.0058,2.8e-05,0.016,-0.00044,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.021,0.021,0.0081,0.047,0.047,0.036,9.5e-07,9.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22790000,0.98,-0.0072,-0.012,0.19,0.028,-0.029,-1.4,0.038,-0.017,-2,-0.0014,-0.0058,2.8e-05,0.016,-0.00056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.02,0.019,0.019,0.0081,0.042,0.042,0.036,8.9e-07,8.9e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22890000,0.98,-0.0074,-0.012,0.19,0.031,-0.034,-1.4,0.041,-0.02,-2.2,-0.0014,-0.0058,2.8e-05,0.016,-0.00064,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.02,0.021,0.021,0.0081,0.047,0.047,0.036,8.9e-07,8.9e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22990000,0.98,-0.0074,-0.013,0.19,0.036,-0.04,-1.4,0.051,-0.031,-2.3,-0.0014,-0.0058,2.9e-05,0.017,-0.00077,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00033,0.02,0.019,0.019,0.0081,0.042,0.042,0.036,8.4e-07,8.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23090000,0.98,-0.0074,-0.013,0.19,0.041,-0.044,-1.4,0.055,-0.035,-2.5,-0.0014,-0.0058,2.9e-05,0.017,-0.0008,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.02,0.02,0.02,0.0081,0.046,0.046,0.036,8.4e-07,8.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23190000,0.98,-0.0074,-0.013,0.19,0.047,-0.046,-1.4,0.066,-0.045,-2.6,-0.0014,-0.0058,2.9e-05,0.017,-0.00095,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00032,0.02,0.018,0.018,0.008,0.042,0.042,0.035,8e-07,8e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23290000,0.98,-0.0079,-0.013,0.19,0.052,-0.051,-1.4,0.071,-0.05,-2.8,-0.0014,-0.0058,2.9e-05,0.017,-0.001,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00033,0.02,0.02,0.02,0.0081,0.046,0.046,0.036,8e-07,8e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23390000,0.98,-0.0078,-0.014,0.19,0.057,-0.053,-1.4,0.082,-0.055,-2.9,-0.0014,-0.0058,2.9e-05,0.017,-0.00075,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00032,0.02,0.018,0.018,0.008,0.041,0.041,0.036,7.6e-07,7.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23490000,0.98,-0.0079,-0.014,0.19,0.061,-0.055,-1.4,0.088,-0.061,-3,-0.0014,-0.0058,2.9e-05,0.017,-0.00079,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00032,0.02,0.019,0.019,0.0081,0.046,0.046,0.036,7.6e-07,7.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23590000,0.98,-0.0082,-0.014,0.19,0.064,-0.058,-1.4,0.095,-0.07,-3.2,-0.0014,-0.0058,3e-05,0.017,-0.00091,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00032,0.02,0.017,0.017,0.008,0.041,0.041,0.035,7.2e-07,7.2e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23690000,0.98,-0.0088,-0.014,0.19,0.062,-0.061,-1.3,0.1,-0.076,-3.3,-0.0014,-0.0058,3e-05,0.017,-0.00093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00032,0.02,0.018,0.018,0.0081,0.046,0.046,0.036,7.2e-07,7.2e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23790000,0.98,-0.011,-0.017,0.19,0.057,-0.058,-0.96,0.11,-0.081,-3.4,-0.0014,-0.0058,2.9e-05,0.017,-0.00093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00032,0.02,0.016,0.016,0.008,0.041,0.041,0.035,6.9e-07,6.9e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23890000,0.98,-0.014,-0.021,0.19,0.053,-0.058,-0.52,0.12,-0.087,-3.5,-0.0014,-0.0058,2.9e-05,0.017,-0.00094,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.02,0.017,0.017,0.008,0.045,0.045,0.035,6.9e-07,6.9e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23990000,0.98,-0.016,-0.024,0.19,0.054,-0.058,-0.14,0.12,-0.089,-3.6,-0.0014,-0.0058,2.9e-05,0.018,-0.0015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.015,0.015,0.008,0.041,0.041,0.036,6.6e-07,6.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24090000,0.98,-0.016,-0.023,0.19,0.061,-0.066,0.09,0.13,-0.095,-3.6,-0.0014,-0.0058,2.9e-05,0.018,-0.0015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.017,0.017,0.0081,0.045,0.045,0.036,6.6e-07,6.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24190000,0.98,-0.013,-0.019,0.19,0.072,-0.071,0.077,0.14,-0.1,-3.6,-0.0014,-0.0058,3e-05,0.019,-0.0022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00033,0.02,0.015,0.015,0.008,0.04,0.04,0.035,6.4e-07,6.3e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24290000,0.98,-0.01,-0.016,0.19,0.075,-0.075,0.055,0.15,-0.11,-3.6,-0.0014,-0.0058,3e-05,0.019,-0.0022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00032,0.02,0.016,0.016,0.0081,0.044,0.044,0.036,6.4e-07,6.3e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24390000,0.98,-0.0096,-0.015,0.19,0.069,-0.069,0.071,0.15,-0.11,-3.6,-0.0014,-0.0058,2.9e-05,0.019,-0.003,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00032,0.02,0.015,0.015,0.008,0.04,0.04,0.035,6.1e-07,6.1e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24490000,0.98,-0.0098,-0.015,0.19,0.064,-0.066,0.069,0.16,-0.11,-3.6,-0.0014,-0.0058,2.9e-05,0.019,-0.003,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00032,0.02,0.016,0.016,0.008,0.044,0.044,0.035,6.1e-07,6.1e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24590000,0.98,-0.01,-0.015,0.19,0.061,-0.062,0.065,0.16,-0.11,-3.6,-0.0014,-0.0058,2.9e-05,0.019,-0.0037,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00032,0.02,0.015,0.015,0.008,0.04,0.04,0.036,5.9e-07,5.9e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24690000,0.98,-0.011,-0.015,0.19,0.059,-0.061,0.064,0.17,-0.12,-3.6,-0.0014,-0.0058,2.9e-05,0.019,-0.0037,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00032,0.02,0.016,0.016,0.0081,0.044,0.044,0.036,5.9e-07,5.9e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24790000,0.98,-0.011,-0.014,0.19,0.056,-0.059,0.056,0.17,-0.11,-3.6,-0.0015,-0.0058,2.9e-05,0.019,-0.0043,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00032,0.02,0.015,0.015,0.008,0.039,0.039,0.035,5.7e-07,5.7e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24890000,0.98,-0.011,-0.013,0.19,0.054,-0.062,0.045,0.18,-0.12,-3.6,-0.0015,-0.0058,2.9e-05,0.019,-0.0043,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00032,0.02,0.016,0.016,0.008,0.043,0.043,0.035,5.7e-07,5.7e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24990000,0.98,-0.011,-0.013,0.19,0.045,-0.058,0.038,0.18,-0.11,-3.6,-0.0015,-0.0058,2.9e-05,0.019,-0.005,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00032,0.02,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-07,5.5e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +25090000,0.98,-0.011,-0.013,0.19,0.042,-0.057,0.035,0.18,-0.12,-3.6,-0.0015,-0.0058,2.9e-05,0.019,-0.005,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00032,0.02,0.016,0.016,0.0081,0.043,0.043,0.035,5.5e-07,5.5e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +25190000,0.98,-0.011,-0.013,0.19,0.037,-0.05,0.035,0.18,-0.11,-3.6,-0.0015,-0.0058,3e-05,0.018,-0.0055,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00032,0.02,0.015,0.015,0.008,0.039,0.039,0.035,5.3e-07,5.3e-07,6.3e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25290000,0.98,-0.011,-0.012,0.19,0.032,-0.052,0.029,0.18,-0.11,-3.6,-0.0015,-0.0058,3e-05,0.018,-0.0055,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00032,0.02,0.016,0.016,0.0081,0.043,0.043,0.036,5.3e-07,5.3e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25390000,0.98,-0.011,-0.012,0.19,0.024,-0.044,0.028,0.18,-0.1,-3.6,-0.0015,-0.0058,3.1e-05,0.018,-0.0062,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00032,0.02,0.015,0.015,0.008,0.039,0.039,0.035,5.2e-07,5.1e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25490000,0.98,-0.011,-0.012,0.19,0.019,-0.044,0.027,0.18,-0.11,-3.6,-0.0015,-0.0058,3.1e-05,0.018,-0.0062,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00032,0.02,0.016,0.016,0.008,0.043,0.043,0.035,5.2e-07,5.2e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25590000,0.98,-0.011,-0.012,0.19,0.014,-0.04,0.028,0.18,-0.098,-3.6,-0.0015,-0.0058,3.1e-05,0.018,-0.0065,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00032,0.02,0.014,0.014,0.008,0.039,0.039,0.035,5e-07,5e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25690000,0.98,-0.011,-0.011,0.19,0.013,-0.039,0.017,0.18,-0.1,-3.6,-0.0015,-0.0058,3.1e-05,0.018,-0.0066,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00032,0.02,0.015,0.016,0.0081,0.043,0.043,0.035,5e-07,5e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25790000,0.98,-0.011,-0.011,0.19,0.0021,-0.031,0.017,0.17,-0.093,-3.6,-0.0016,-0.0058,3.2e-05,0.018,-0.007,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00032,0.02,0.014,0.014,0.008,0.039,0.039,0.035,4.9e-07,4.8e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25890000,0.98,-0.011,-0.011,0.19,-0.0037,-0.029,0.019,0.17,-0.095,-3.6,-0.0016,-0.0058,3.2e-05,0.018,-0.007,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00032,0.02,0.015,0.015,0.0081,0.043,0.043,0.036,4.9e-07,4.9e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25990000,0.98,-0.011,-0.011,0.19,-0.013,-0.022,0.013,0.16,-0.086,-3.6,-0.0016,-0.0058,3.3e-05,0.018,-0.0075,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00032,0.02,0.014,0.014,0.008,0.039,0.039,0.035,4.7e-07,4.7e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26090000,0.98,-0.01,-0.011,0.19,-0.018,-0.022,0.011,0.16,-0.088,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0075,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00033,0.02,0.015,0.015,0.0081,0.042,0.042,0.035,4.7e-07,4.7e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26190000,0.98,-0.01,-0.011,0.19,-0.024,-0.015,0.0063,0.15,-0.081,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0077,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00033,0.02,0.014,0.014,0.008,0.039,0.039,0.035,4.6e-07,4.6e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26290000,0.98,-0.01,-0.012,0.19,-0.026,-0.014,0.00052,0.15,-0.083,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0077,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00033,0.02,0.015,0.015,0.0081,0.042,0.042,0.036,4.6e-07,4.6e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26390000,0.98,-0.0098,-0.012,0.19,-0.032,-0.0065,0.0045,0.13,-0.075,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.008,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00033,0.02,0.014,0.014,0.008,0.038,0.038,0.035,4.5e-07,4.5e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26490000,0.98,-0.0096,-0.011,0.19,-0.035,-0.0034,0.014,0.13,-0.075,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0079,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00033,0.021,0.015,0.015,0.0081,0.042,0.042,0.035,4.5e-07,4.5e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26590000,0.98,-0.009,-0.012,0.19,-0.036,0.0046,0.014,0.12,-0.068,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0081,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00032,0.021,0.014,0.014,0.008,0.038,0.038,0.035,4.4e-07,4.3e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26690000,0.98,-0.0089,-0.011,0.19,-0.038,0.0097,0.013,0.12,-0.067,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0081,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00032,0.021,0.015,0.015,0.0081,0.042,0.042,0.035,4.4e-07,4.4e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26790000,0.98,-0.0087,-0.011,0.19,-0.045,0.013,0.012,0.1,-0.062,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0083,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00032,0.021,0.014,0.014,0.008,0.038,0.038,0.035,4.3e-07,4.2e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26890000,0.98,-0.008,-0.011,0.19,-0.051,0.016,0.007,0.1,-0.06,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0083,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00032,0.021,0.015,0.015,0.0081,0.042,0.042,0.036,4.3e-07,4.2e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26990000,0.98,-0.0075,-0.011,0.19,-0.058,0.023,0.0061,0.088,-0.054,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00032,0.021,0.014,0.014,0.008,0.038,0.038,0.035,4.2e-07,4.1e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27090000,0.98,-0.0073,-0.012,0.19,-0.06,0.03,0.0089,0.082,-0.052,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0087,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00032,0.021,0.015,0.015,0.0081,0.042,0.042,0.035,4.2e-07,4.1e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27190000,0.98,-0.0074,-0.012,0.19,-0.066,0.035,0.011,0.071,-0.046,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00032,0.021,0.014,0.014,0.008,0.038,0.038,0.035,4.1e-07,4e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27290000,0.98,-0.0075,-0.013,0.19,-0.073,0.041,0.12,0.064,-0.042,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00032,0.021,0.015,0.015,0.0081,0.042,0.042,0.035,4.1e-07,4e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27390000,0.98,-0.0089,-0.015,0.19,-0.078,0.047,0.45,0.055,-0.035,-3.5,-0.0016,-0.0058,3.5e-05,0.02,-0.0092,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.038,0.038,0.035,4e-07,3.9e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27490000,0.98,-0.01,-0.017,0.19,-0.082,0.053,0.76,0.047,-0.029,-3.5,-0.0016,-0.0058,3.5e-05,0.02,-0.0093,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.042,0.042,0.035,4e-07,4e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27590000,0.98,-0.01,-0.016,0.19,-0.075,0.055,0.85,0.038,-0.025,-3.4,-0.0016,-0.0058,3.5e-05,0.02,-0.0094,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-07,3.9e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27690000,0.98,-0.0089,-0.013,0.19,-0.072,0.052,0.76,0.031,-0.02,-3.3,-0.0016,-0.0058,3.5e-05,0.02,-0.0095,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00033,0.021,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-07,3.9e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27790000,0.98,-0.0076,-0.011,0.19,-0.071,0.05,0.75,0.025,-0.018,-3.3,-0.0016,-0.0058,3.5e-05,0.02,-0.0089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00033,0.021,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-07,3.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27890000,0.98,-0.0072,-0.012,0.19,-0.078,0.057,0.79,0.017,-0.012,-3.2,-0.0016,-0.0058,3.5e-05,0.02,-0.009,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00033,0.021,0.014,0.014,0.0081,0.041,0.041,0.036,3.8e-07,3.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27990000,0.98,-0.0077,-0.012,0.19,-0.078,0.058,0.78,0.012,-0.011,-3.1,-0.0016,-0.0058,3.6e-05,0.019,-0.0087,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00033,0.021,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-07,3.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28090000,0.98,-0.008,-0.012,0.19,-0.082,0.059,0.78,0.0042,-0.0047,-3,-0.0016,-0.0058,3.6e-05,0.019,-0.0087,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.8e-07,3.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28190000,0.98,-0.0074,-0.012,0.19,-0.082,0.055,0.79,-0.0023,-0.0043,-3,-0.0016,-0.0058,3.6e-05,0.019,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.038,0.038,0.035,3.7e-07,3.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28290000,0.98,-0.0069,-0.012,0.19,-0.088,0.059,0.79,-0.011,0.0015,-2.9,-0.0016,-0.0058,3.6e-05,0.019,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-07,3.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28390000,0.98,-0.0069,-0.013,0.19,-0.088,0.061,0.79,-0.015,0.0045,-2.8,-0.0015,-0.0058,3.8e-05,0.019,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.6e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28490000,0.98,-0.0072,-0.014,0.19,-0.09,0.066,0.79,-0.024,0.011,-2.8,-0.0015,-0.0058,3.8e-05,0.019,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.0081,0.041,0.041,0.036,3.6e-07,3.6e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28590000,0.98,-0.0073,-0.014,0.18,-0.083,0.061,0.79,-0.027,0.0085,-2.7,-0.0015,-0.0058,3.8e-05,0.019,-0.0082,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.5e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28690000,0.98,-0.007,-0.013,0.19,-0.083,0.062,0.79,-0.036,0.015,-2.6,-0.0015,-0.0058,3.8e-05,0.019,-0.0083,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.6e-07,3.5e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28790000,0.98,-0.0064,-0.013,0.18,-0.079,0.062,0.79,-0.038,0.016,-2.5,-0.0015,-0.0058,4e-05,0.019,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-07,3.5e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28890000,0.98,-0.0062,-0.012,0.18,-0.084,0.064,0.78,-0.046,0.023,-2.5,-0.0015,-0.0058,4e-05,0.019,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.0081,0.041,0.041,0.036,3.5e-07,3.5e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28990000,0.98,-0.006,-0.013,0.18,-0.079,0.06,0.78,-0.046,0.022,-2.4,-0.0015,-0.0058,4.2e-05,0.019,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-07,3.4e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29090000,0.98,-0.0058,-0.013,0.18,-0.082,0.063,0.78,-0.054,0.028,-2.3,-0.0015,-0.0058,4.2e-05,0.019,-0.0086,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.5e-07,3.4e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29190000,0.98,-0.0058,-0.013,0.18,-0.078,0.061,0.78,-0.051,0.027,-2.2,-0.0015,-0.0058,4.5e-05,0.02,-0.0088,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.4e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29290000,0.98,-0.0061,-0.013,0.18,-0.08,0.067,0.78,-0.059,0.034,-2.2,-0.0015,-0.0058,4.5e-05,0.02,-0.0089,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-07,3.4e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29390000,0.98,-0.0065,-0.012,0.18,-0.075,0.066,0.78,-0.057,0.034,-2.1,-0.0015,-0.0058,4.8e-05,0.02,-0.009,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29490000,0.98,-0.0065,-0.012,0.18,-0.078,0.066,0.78,-0.065,0.041,-2,-0.0015,-0.0058,4.8e-05,0.02,-0.009,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.0081,0.041,0.041,0.036,3.4e-07,3.3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29590000,0.98,-0.0064,-0.012,0.18,-0.074,0.064,0.78,-0.062,0.04,-1.9,-0.0015,-0.0058,5e-05,0.02,-0.0092,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29690000,0.98,-0.0065,-0.012,0.18,-0.078,0.063,0.78,-0.07,0.046,-1.9,-0.0015,-0.0058,5e-05,0.02,-0.0094,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-07,3.3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29790000,0.98,-0.0063,-0.013,0.18,-0.073,0.056,0.78,-0.065,0.044,-1.8,-0.0014,-0.0058,5.2e-05,0.02,-0.0096,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29890000,0.98,-0.0058,-0.013,0.18,-0.074,0.057,0.77,-0.072,0.049,-1.7,-0.0014,-0.0058,5.2e-05,0.02,-0.0098,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29990000,0.98,-0.006,-0.013,0.18,-0.069,0.052,0.77,-0.068,0.044,-1.6,-0.0014,-0.0058,5.4e-05,0.02,-0.01,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30090000,0.98,-0.0061,-0.013,0.18,-0.069,0.053,0.77,-0.075,0.05,-1.6,-0.0014,-0.0058,5.4e-05,0.02,-0.01,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30190000,0.98,-0.0061,-0.013,0.18,-0.063,0.05,0.77,-0.068,0.048,-1.5,-0.0014,-0.0057,5.6e-05,0.02,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.1e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30290000,0.98,-0.0061,-0.013,0.18,-0.062,0.05,0.77,-0.074,0.053,-1.4,-0.0014,-0.0057,5.6e-05,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30390000,0.98,-0.0061,-0.013,0.18,-0.055,0.044,0.76,-0.066,0.05,-1.4,-0.0014,-0.0057,5.9e-05,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.0079,0.037,0.037,0.035,3.1e-07,3.1e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30490000,0.98,-0.0061,-0.013,0.18,-0.057,0.044,0.77,-0.072,0.054,-1.3,-0.0014,-0.0057,5.9e-05,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.036,3.1e-07,3.1e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30590000,0.98,-0.0064,-0.013,0.18,-0.053,0.041,0.76,-0.065,0.05,-1.2,-0.0014,-0.0057,6.1e-05,0.021,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.1e-07,3.1e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30690000,0.98,-0.0068,-0.014,0.18,-0.051,0.04,0.76,-0.07,0.054,-1.1,-0.0014,-0.0057,6.1e-05,0.021,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.013,0.008,0.041,0.041,0.035,3.1e-07,3.1e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30790000,0.98,-0.0065,-0.013,0.18,-0.044,0.035,0.76,-0.063,0.052,-1.1,-0.0014,-0.0057,6.3e-05,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.1e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30890000,0.98,-0.0059,-0.013,0.18,-0.044,0.032,0.76,-0.067,0.056,-1,-0.0014,-0.0057,6.3e-05,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.013,0.008,0.041,0.041,0.035,3.1e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30990000,0.98,-0.0061,-0.013,0.18,-0.036,0.026,0.76,-0.057,0.049,-0.94,-0.0014,-0.0057,6.4e-05,0.022,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.0079,0.037,0.037,0.035,3e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31090000,0.98,-0.0062,-0.013,0.18,-0.035,0.025,0.76,-0.06,0.051,-0.86,-0.0014,-0.0057,6.4e-05,0.022,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.041,0.04,0.036,3e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31190000,0.98,-0.0064,-0.013,0.18,-0.031,0.02,0.76,-0.052,0.046,-0.79,-0.0014,-0.0057,6.6e-05,0.022,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.022,0.013,0.013,0.008,0.037,0.037,0.035,3e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31290000,0.98,-0.0066,-0.014,0.18,-0.028,0.018,0.76,-0.055,0.048,-0.72,-0.0014,-0.0057,6.6e-05,0.022,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.022,0.013,0.013,0.008,0.04,0.04,0.035,3e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31390000,0.98,-0.0064,-0.013,0.18,-0.022,0.012,0.76,-0.046,0.042,-0.65,-0.0014,-0.0057,6.7e-05,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.022,0.013,0.013,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31490000,0.98,-0.0061,-0.014,0.18,-0.022,0.0088,0.76,-0.048,0.043,-0.58,-0.0014,-0.0057,6.7e-05,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.022,0.013,0.013,0.008,0.04,0.04,0.035,3e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31590000,0.98,-0.006,-0.014,0.18,-0.018,0.0066,0.76,-0.037,0.039,-0.51,-0.0014,-0.0057,6.8e-05,0.023,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.022,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31690000,0.98,-0.006,-0.015,0.18,-0.02,0.0055,0.76,-0.039,0.039,-0.44,-0.0014,-0.0057,6.8e-05,0.023,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.022,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31790000,0.98,-0.0062,-0.015,0.18,-0.011,0.0029,0.76,-0.028,0.037,-0.36,-0.0014,-0.0057,7e-05,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.022,0.012,0.012,0.008,0.037,0.037,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31890000,0.98,-0.0059,-0.015,0.18,-0.0081,0.00056,0.76,-0.029,0.038,-0.3,-0.0014,-0.0057,7e-05,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.022,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31990000,0.98,-0.0062,-0.015,0.18,-0.00018,-0.00011,0.75,-0.017,0.034,-0.23,-0.0013,-0.0057,7.1e-05,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.022,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32090000,0.98,-0.0066,-0.014,0.18,-0.00074,-0.0035,0.76,-0.017,0.034,-0.16,-0.0013,-0.0057,7.1e-05,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.022,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32190000,0.98,-0.0068,-0.015,0.18,0.0046,-0.0067,0.76,-0.006,0.033,-0.092,-0.0013,-0.0057,7.3e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.022,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32290000,0.98,-0.0067,-0.015,0.18,0.0062,-0.0095,0.75,-0.0055,0.032,-0.024,-0.0013,-0.0057,7.3e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.022,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32390000,0.98,-0.0068,-0.015,0.18,0.012,-0.011,0.75,0.0058,0.03,0.051,-0.0013,-0.0057,7.4e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00033,0.022,0.012,0.012,0.008,0.037,0.037,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32490000,0.98,-0.0096,-0.013,0.18,0.039,-0.074,-0.12,0.0089,0.023,0.054,-0.0013,-0.0057,7.4e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00033,0.022,0.015,0.015,0.0078,0.04,0.04,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32590000,0.98,-0.0096,-0.013,0.18,0.039,-0.075,-0.12,0.021,0.02,0.035,-0.0014,-0.0057,7.5e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00033,0.022,0.016,0.016,0.0075,0.037,0.037,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32690000,0.98,-0.0096,-0.013,0.18,0.035,-0.081,-0.12,0.025,0.012,0.02,-0.0014,-0.0057,7.5e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00033,0.022,0.019,0.019,0.0074,0.041,0.041,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32790000,0.98,-0.0092,-0.013,0.18,0.033,-0.078,-0.12,0.034,0.01,0.0044,-0.0014,-0.0056,7.6e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00032,0.022,0.019,0.02,0.0071,0.037,0.037,0.035,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32890000,0.98,-0.0092,-0.013,0.18,0.033,-0.084,-0.13,0.038,0.0019,-0.011,-0.0014,-0.0056,7.6e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00032,0.022,0.023,0.023,0.007,0.041,0.041,0.035,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32990000,0.98,-0.0089,-0.013,0.18,0.03,-0.08,-0.13,0.045,-0.0013,-0.024,-0.0014,-0.0056,7.7e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.0003,0.022,0.024,0.024,0.0067,0.038,0.038,0.035,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33090000,0.98,-0.0089,-0.013,0.18,0.026,-0.084,-0.12,0.048,-0.0094,-0.031,-0.0014,-0.0056,7.7e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.0003,0.022,0.029,0.029,0.0066,0.042,0.042,0.035,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33190000,0.98,-0.0086,-0.013,0.18,0.022,-0.079,-0.12,0.054,-0.011,-0.037,-0.0014,-0.0056,7.8e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00028,0.00028,0.022,0.029,0.029,0.0064,0.038,0.038,0.035,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33290000,0.98,-0.0086,-0.013,0.18,0.018,-0.081,-0.12,0.056,-0.019,-0.045,-0.0014,-0.0056,7.8e-05,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00028,0.00028,0.022,0.035,0.035,0.0063,0.043,0.043,0.034,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33390000,0.98,-0.0082,-0.013,0.18,0.014,-0.066,-0.12,0.059,-0.014,-0.053,-0.0014,-0.0056,8e-05,0.025,-0.016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00025,0.00025,0.022,0.035,0.035,0.0062,0.039,0.039,0.034,2.7e-07,2.6e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33490000,0.98,-0.0081,-0.013,0.18,0.0091,-0.067,-0.12,0.06,-0.021,-0.063,-0.0014,-0.0056,8e-05,0.025,-0.016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00025,0.00025,0.022,0.042,0.042,0.0061,0.044,0.044,0.034,2.7e-07,2.6e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33590000,0.98,-0.0078,-0.013,0.18,0.0053,-0.058,-0.11,0.063,-0.017,-0.069,-0.0014,-0.0056,8.1e-05,0.024,-0.019,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00022,0.00022,0.022,0.04,0.041,0.006,0.04,0.04,0.034,2.6e-07,2.6e-07,6.4e-06,0.026,0.027,0.0005,0,0,0,0,0,0,0,0 +33690000,0.98,-0.0078,-0.013,0.18,0.00057,-0.058,-0.11,0.063,-0.023,-0.077,-0.0014,-0.0056,8.1e-05,0.024,-0.019,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00022,0.00022,0.022,0.048,0.048,0.0059,0.046,0.046,0.034,2.7e-07,2.6e-07,6.4e-06,0.026,0.027,0.0005,0,0,0,0,0,0,0,0 +33790000,0.98,-0.0075,-0.013,0.18,-0.0025,-0.047,-0.11,0.067,-0.018,-0.083,-0.0014,-0.0056,8.2e-05,0.023,-0.021,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00019,0.022,0.045,0.045,0.0059,0.041,0.041,0.034,2.6e-07,2.6e-07,6.4e-06,0.026,0.026,0.0005,0,0,0,0,0,0,0,0 +33890000,0.98,-0.0075,-0.013,0.18,-0.0067,-0.045,-0.11,0.066,-0.023,-0.089,-0.0014,-0.0056,8.2e-05,0.023,-0.021,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00019,0.022,0.052,0.053,0.0058,0.047,0.047,0.033,2.6e-07,2.6e-07,6.4e-06,0.026,0.026,0.0005,0,0,0,0,0,0,0,0 +33990000,0.98,-0.0072,-0.013,0.18,-0.0063,-0.031,-0.1,0.069,-0.015,-0.092,-0.0014,-0.0056,8.2e-05,0.02,-0.024,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00017,0.022,0.047,0.047,0.0058,0.042,0.042,0.033,2.6e-07,2.6e-07,6.4e-06,0.025,0.025,0.0005,0,0,0,0,0,0,0,0 +34090000,0.98,-0.0072,-0.013,0.18,-0.011,-0.031,-0.1,0.069,-0.018,-0.096,-0.0014,-0.0056,8.2e-05,0.02,-0.024,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00017,0.022,0.054,0.055,0.0058,0.049,0.049,0.033,2.6e-07,2.6e-07,6.4e-06,0.025,0.025,0.0005,0,0,0,0,0,0,0,0 +34190000,0.98,-0.0071,-0.013,0.18,-0.011,-0.02,-0.098,0.072,-0.013,-0.099,-0.0014,-0.0056,8.3e-05,0.019,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00015,0.022,0.048,0.048,0.0058,0.043,0.043,0.033,2.6e-07,2.6e-07,6.4e-06,0.024,0.024,0.0005,0,0,0,0,0,0,0,0 +34290000,0.98,-0.007,-0.013,0.18,-0.012,-0.02,-0.097,0.071,-0.015,-0.1,-0.0014,-0.0056,8.3e-05,0.018,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00015,0.022,0.055,0.055,0.0058,0.05,0.05,0.033,2.7e-07,2.6e-07,6.4e-06,0.024,0.024,0.0005,0,0,0,0,0,0,0,0 +34390000,0.98,-0.0069,-0.013,0.18,-0.013,-0.01,-0.092,0.072,-0.01,-0.11,-0.0014,-0.0056,7e-05,0.017,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00014,0.00014,0.018,0.047,0.047,0.0058,0.044,0.044,0.033,2.6e-07,2.6e-07,6.1e-06,0.023,0.023,0.0005,0,0,0,0,0,0,0,0 +34490000,0.98,-0.0069,-0.013,0.18,-0.016,-0.0091,-0.089,0.071,-0.011,-0.11,-0.0014,-0.0056,7e-05,0.017,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00014,0.00014,0.018,0.053,0.054,0.0059,0.051,0.051,0.032,2.7e-07,2.6e-07,6.1e-06,0.023,0.023,0.0005,0,0,0,0,0,0,0,0 +34590000,0.98,-0.0069,-0.013,0.18,-0.014,-0.0048,0.71,0.073,-0.0088,-0.081,-0.0014,-0.0056,7e-05,0.016,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00013,0.00013,0.018,0.044,0.044,0.0059,0.045,0.045,0.032,2.7e-07,2.6e-07,6.1e-06,0.022,0.022,0.0005,0,0,0,0,0,0,0,0 +34690000,0.98,-0.0069,-0.012,0.18,-0.017,-0.0026,1.7,0.071,-0.0092,0.038,-0.0014,-0.0056,7e-05,0.016,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00013,0.00013,0.018,0.047,0.048,0.006,0.052,0.052,0.032,2.7e-07,2.6e-07,6.1e-06,0.022,0.022,0.0005,0,0,0,0,0,0,0,0 +34790000,0.98,-0.0069,-0.012,0.18,-0.018,0.002,2.7,0.072,-0.0068,0.21,-0.0014,-0.0056,7e-05,0.017,-0.03,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00013,0.00012,0.018,0.04,0.04,0.0061,0.045,0.045,0.032,2.7e-07,2.7e-07,6.1e-06,0.021,0.021,0.0005,0,0,0,0,0,0,0,0 +34890000,0.98,-0.0068,-0.012,0.18,-0.022,0.0045,3.6,0.07,-0.0063,0.5,-0.0014,-0.0056,7e-05,0.017,-0.03,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00013,0.00012,0.018,0.044,0.044,0.0061,0.052,0.052,0.032,2.7e-07,2.7e-07,6.1e-06,0.021,0.021,0.0005,0,0,0,0,0,0,0,0 diff --git a/src/modules/ekf2/test/sensor_simulator/ekf_logger.cpp b/src/modules/ekf2/test/sensor_simulator/ekf_logger.cpp index 713e27434528..d388e0787f46 100644 --- a/src/modules/ekf2/test/sensor_simulator/ekf_logger.cpp +++ b/src/modules/ekf2/test/sensor_simulator/ekf_logger.cpp @@ -52,17 +52,17 @@ void EkfLogger::writeState() _file << time; if (_state_logging_enabled) { - matrix::Vector state = _ekf->getStateAtFusionHorizonAsVector(); + auto state = _ekf->state().vector(); - for (int i = 0; i < 24; i++) { + for (unsigned i = 0; i < state.size(); i++) { _file << "," << std::setprecision(2) << state(i); } } if (_variance_logging_enabled) { - matrix::Vector variance = _ekf->covariances_diagonal(); + matrix::Vector variance = _ekf->covariances_diagonal(); - for (int i = 0; i < 24; i++) { + for (unsigned i = 0; i < State::size; i++) { _file << "," << variance(i); } } diff --git a/src/modules/ekf2/test/test_EKF_airspeed_fusion_generated.cpp b/src/modules/ekf2/test/test_EKF_airspeed_fusion_generated.cpp deleted file mode 100644 index 114a051e189c..000000000000 --- a/src/modules/ekf2/test/test_EKF_airspeed_fusion_generated.cpp +++ /dev/null @@ -1,146 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -#include -#include "EKF/ekf.h" -#include "test_helper/comparison_helper.h" - -#include "../EKF/python/ekf_derivation/generated/compute_airspeed_innov_and_innov_var.h" -#include "../EKF/python/ekf_derivation/generated/compute_airspeed_h_and_k.h" - -using namespace matrix; - -TEST(AirspeedFusionGenerated, SympyVsSymforce) -{ - // Compare calculation of observation Jacobians and Kalman gains for sympy and symforce generated equations - const float R_TAS = sq(1.5f); - - const float vn = 9.0f; - const float ve = 12.0f; - const float vd = -1.5f; - - const float vwn = -4.0f; - const float vwe = 3.0f; - - SquareMatrix24f P = createRandomCovarianceMatrix24f(); - - // First calculate observationjacobians and Kalman gains using sympy generated equations - Vector24f Hfusion_sympy; - Vector24f Kfusion_sympy; - - { - // Intermediate variables - const float HK0 = vn - vwn; - const float HK1 = ve - vwe; - const float HK2 = powf(HK0, 2.f) + powf(HK1, 2.f) + powf(vd, 2.f); - const float v_tas_pred = sqrtf(HK2); // predicted airspeed - //const float HK3 = powf(HK2, -1.0F/2.0F); - // calculation can be badly conditioned for very low airspeed values so don't fuse this time - EXPECT_GT(v_tas_pred, 1.f); - const float HK3 = 1.0f / v_tas_pred; - const float HK4 = HK0 * HK3; - const float HK5 = HK1 * HK3; - const float HK6 = 1.0F / HK2; - const float HK7 = HK0 * P(4, 6) - HK0 * P(6, 22) + HK1 * P(5, 6) - HK1 * P(6, 23) + P(6, 6) * vd; - const float HK8 = HK1 * P(5, 23); - const float HK9 = HK0 * P(4, 5) - HK0 * P(5, 22) + HK1 * P(5, 5) - HK8 + P(5, 6) * vd; - const float HK10 = HK1 * HK6; - const float HK11 = HK0 * P(4, 22); - const float HK12 = HK0 * P(4, 4) - HK1 * P(4, 23) + HK1 * P(4, 5) - HK11 + P(4, 6) * vd; - const float HK13 = HK0 * HK6; - const float HK14 = -HK0 * P(22, 23) + HK0 * P(4, 23) - HK1 * P(23, 23) + HK8 + P(6, 23) * vd; - const float HK15 = -HK0 * P(22, 22) - HK1 * P(22, 23) + HK1 * P(5, 22) + HK11 + P(6, 22) * vd; - const float inn_var = (-HK10 * HK14 + HK10 * HK9 + HK12 * HK13 - HK13 * HK15 + HK6 * HK7 * vd + R_TAS); - const float HK16 = HK3 / inn_var; - - // Observation Jacobians - SparseVector24f<4, 5, 6, 22, 23> Hfusion; - Hfusion.at<4>() = HK4; - Hfusion.at<5>() = HK5; - Hfusion.at<6>() = HK3 * vd; - Hfusion.at<22>() = -HK4; - Hfusion.at<23>() = -HK5; - - Vector24f Kfusion; - - for (unsigned row = 0; row <= 3; row++) { - Kfusion(row) = HK16 * (HK0 * P(4, row) - HK0 * P(row, 22) + HK1 * P(5, row) - HK1 * P(row, 23) + P(6, row) * vd); - } - - Kfusion(4) = HK12 * HK16; - Kfusion(5) = HK16 * HK9; - Kfusion(6) = HK16 * HK7; - - for (unsigned row = 7; row <= 21; row++) { - Kfusion(row) = HK16 * (HK0 * P(4, row) - HK0 * P(row, 22) + HK1 * P(5, row) - HK1 * P(row, 23) + P(6, row) * vd); - } - - Kfusion(22) = HK15 * HK16; - Kfusion(23) = HK14 * HK16; - - // save output - Hfusion_sympy(4) = Hfusion.at<4>(); - Hfusion_sympy(5) = Hfusion.at<5>(); - Hfusion_sympy(6) = Hfusion.at<6>(); - Hfusion_sympy(22) = Hfusion.at<22>(); - Hfusion_sympy(23) = Hfusion.at<23>(); - Kfusion_sympy = Kfusion; - } - - // Then calculate observationjacobians and Kalman gains using symforce generated equations - Vector24f Hfusion_symforce; - Vector24f Kfusion_symforce; - - { - Vector24f state_vector{}; - state_vector(4) = vn; - state_vector(5) = ve; - state_vector(6) = vd; - state_vector(22) = vwn; - state_vector(23) = vwe; - - float innov; - float innov_var; - - sym::ComputeAirspeedInnovAndInnovVar(state_vector, P, 0.f, R_TAS, FLT_EPSILON, &innov, &innov_var); - sym::ComputeAirspeedHAndK(state_vector, P, innov_var, FLT_EPSILON, &Hfusion_symforce, &Kfusion_symforce); - } - - DiffRatioReport report = computeDiffRatioVector24f(Hfusion_sympy, Hfusion_symforce); - EXPECT_LT(report.max_diff_fraction, 1e-5f) << "Airspeed Hfusion max diff fraction = " << report.max_diff_fraction << - " location index = " << report.max_row << " sympy = " << report.max_v1 << " symforce = " << report.max_v2; - - report = computeDiffRatioVector24f(Kfusion_sympy, Kfusion_symforce); - EXPECT_LT(report.max_diff_fraction, 1e-5f) << "Airspeed Kfusion max diff fraction = " << report.max_diff_fraction << - " location index = " << report.max_row << " sympy = " << report.max_v1 << " symforce = " << report.max_v2; -} diff --git a/src/modules/ekf2/test/test_EKF_attitude_variance.cpp b/src/modules/ekf2/test/test_EKF_attitude_variance.cpp deleted file mode 100644 index d851d6a7a65a..000000000000 --- a/src/modules/ekf2/test/test_EKF_attitude_variance.cpp +++ /dev/null @@ -1,272 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2023 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -#include -#include "EKF/ekf.h" -#include "test_helper/comparison_helper.h" - -#include "../EKF/python/ekf_derivation/generated/quat_var_to_rot_var.h" -#include "../EKF/python/ekf_derivation/generated/rot_var_ned_to_lower_triangular_quat_cov.h" -#include "../EKF/python/ekf_derivation/generated/compute_yaw_321_innov_var_and_h.h" -#include "../EKF/python/ekf_derivation/generated/compute_yaw_312_innov_var_and_h.h" - -using namespace matrix; - -Vector3f calcRotVarMatlab(const Quatf &q, const SquareMatrix24f &P) -{ - Vector3f rot_var_vec; - float q0, q1, q2, q3; - - if (q(0) >= 0.0f) { - q0 = q(0); - q1 = q(1); - q2 = q(2); - q3 = q(3); - - } else { - q0 = -q(0); - q1 = -q(1); - q2 = -q(2); - q3 = -q(3); - } - - float t2 = q0 * q0; - float t3 = acosf(q0); - float t4 = -t2 + 1.0f; - float t5 = t2 - 1.0f; - - if ((t4 > 1e-9f) && (t5 < -1e-9f)) { - float t6 = 1.0f / t5; - float t7 = q1 * t6 * 2.0f; - float t8 = 1.0f / powf(t4, 1.5f); - float t9 = q0 * q1 * t3 * t8 * 2.0f; - float t10 = t7 + t9; - float t11 = 1.0f / sqrtf(t4); - float t12 = q2 * t6 * 2.0f; - float t13 = q0 * q2 * t3 * t8 * 2.0f; - float t14 = t12 + t13; - float t15 = q3 * t6 * 2.0f; - float t16 = q0 * q3 * t3 * t8 * 2.0f; - float t17 = t15 + t16; - rot_var_vec(0) = t10 * (P(0, 0) * t10 + P(1, 0) * t3 * t11 * 2.0f) + t3 * t11 * (P(0, 1) * t10 + P(1, - 1) * t3 * t11 * 2.0f) * 2.0f; - rot_var_vec(1) = t14 * (P(0, 0) * t14 + P(2, 0) * t3 * t11 * 2.0f) + t3 * t11 * (P(0, 2) * t14 + P(2, - 2) * t3 * t11 * 2.0f) * 2.0f; - rot_var_vec(2) = t17 * (P(0, 0) * t17 + P(3, 0) * t3 * t11 * 2.0f) + t3 * t11 * (P(0, 3) * t17 + P(3, - 3) * t3 * t11 * 2.0f) * 2.0f; - - } else { - rot_var_vec = 4.0f * P.slice<3, 3>(1, 1).diag(); - } - - return rot_var_vec; -} - -TEST(AttitudeVariance, matlabVsSymforce) -{ - Quatf q(Eulerf(M_PI_F / 4.f, -M_PI_F / 6.f, M_PI_F)); - q = -q; // use non-canonical quaternion to cover special case - - const SquareMatrix24f P = createRandomCovarianceMatrix24f(); - Vector3f rot_var_matlab = calcRotVarMatlab(q, P); - - Vector24f state_vector{}; - state_vector(0) = q(0); - state_vector(1) = q(1); - state_vector(2) = q(2); - state_vector(3) = q(3); - - Vector3f rot_var_symforce; - sym::QuatVarToRotVar(state_vector, P, FLT_EPSILON, &rot_var_symforce); - - EXPECT_EQ(rot_var_matlab, rot_var_symforce); -} - -TEST(AttitudeVariance, matlabVsSymforceZeroTilt) -{ - Quatf q; - - const SquareMatrix24f P = createRandomCovarianceMatrix24f(); - Vector3f rot_var_matlab = calcRotVarMatlab(q, P); - - Vector24f state_vector{}; - state_vector(0) = q(0); - state_vector(1) = q(1); - state_vector(2) = q(2); - state_vector(3) = q(3); - - Vector3f rot_var_symforce; - sym::QuatVarToRotVar(state_vector, P, FLT_EPSILON, &rot_var_symforce); - - EXPECT_EQ(rot_var_matlab, rot_var_symforce); - - const Vector3f rot_var_true = 4.0f * P.slice<3, 3>(1, 1).diag(); // special case - EXPECT_EQ(rot_var_symforce, rot_var_true); -} - -void increaseYawVar(const Vector24f &state_vector, SquareMatrix24f &P, const float yaw_var) -{ - SquareMatrix q_cov; - sym::RotVarNedToLowerTriangularQuatCov(state_vector, Vector3f(0.f, 0.f, yaw_var), &q_cov); - q_cov.copyLowerToUpperTriangle(); - P.slice<4, 4>(0, 0) += q_cov; -} - -void setTiltVar(const Vector24f &state_vector, SquareMatrix24f &P, const float tilt_var) -{ - SquareMatrix q_cov; - sym::RotVarNedToLowerTriangularQuatCov(state_vector, Vector3f(tilt_var, tilt_var, 0.f), &q_cov); - q_cov.copyLowerToUpperTriangle(); - P.slice<4, 4>(0, 0) = q_cov; -} - -float getYawVar(const Vector24f &state_vector, const SquareMatrix24f &P) -{ - Vector24f H_YAW; - float yaw_var = 0.f; - sym::ComputeYaw312InnovVarAndH(state_vector, P, 0.f, FLT_EPSILON, &yaw_var, &H_YAW); - return yaw_var; -} - -TEST(AttitudeVariance, increaseYawVarNoTilt) -{ - Quatf q; - SquareMatrix24f P; - Vector24f state_vector{}; - state_vector(0) = q(0); - state_vector(1) = q(1); - state_vector(2) = q(2); - state_vector(3) = q(3); - - const float yaw_var = radians(25.f); - increaseYawVar(state_vector, P, yaw_var); - - const float var_new = getYawVar(state_vector, P); - - EXPECT_NEAR(var_new, yaw_var, 1e-6f); -} - -TEST(AttitudeVariance, increaseYawVarPitch90) -{ - Quatf q(Eulerf(M_PI_F / 2.f, M_PI_F / 2.f, M_PI_F / 3.f)); - SquareMatrix24f P; - Vector24f state_vector{}; - state_vector(0) = q(0); - state_vector(1) = q(1); - state_vector(2) = q(2); - state_vector(3) = q(3); - - const float yaw_var = radians(25.f); - increaseYawVar(state_vector, P, yaw_var); - - const float var_new = getYawVar(state_vector, P); - - EXPECT_NEAR(var_new, yaw_var, 1e-6f); -} - -TEST(AttitudeVariance, increaseYawWithTilt) -{ - Quatf q(Eulerf(-M_PI_F, M_PI_F / 3.f, -M_PI_F / 5.f)); - SquareMatrix24f P; - Vector24f state_vector{}; - state_vector(0) = q(0); - state_vector(1) = q(1); - state_vector(2) = q(2); - state_vector(3) = q(3); - - // Set the yaw variance (from 0) - const float yaw_var_1 = radians(25.f); - increaseYawVar(state_vector, P, yaw_var_1); - - const float var_1 = getYawVar(state_vector, P); - EXPECT_NEAR(var_1, yaw_var_1, 1e-6f); - - // Increase it even more - const float yaw_var_2 = radians(12.f); - increaseYawVar(state_vector, P, yaw_var_2); - - const float var_2 = getYawVar(state_vector, P); - EXPECT_NEAR(var_2, yaw_var_1 + yaw_var_2, 1e-6f); -} - -TEST(AttitudeVariance, setRotVarNoTilt) -{ - Quatf q; - SquareMatrix24f P; - Vector24f state_vector{}; - state_vector(0) = q(0); - state_vector(1) = q(1); - state_vector(2) = q(2); - state_vector(3) = q(3); - - const float tilt_var = radians(1.2f); - setTiltVar(state_vector, P, tilt_var); - - Vector3f rot_var; - sym::QuatVarToRotVar(state_vector, P, FLT_EPSILON, &rot_var); - - EXPECT_NEAR(rot_var(0), tilt_var, 1e-6f); - EXPECT_NEAR(rot_var(1), tilt_var, 1e-6f); - EXPECT_EQ(rot_var(2), 0.f); - - // Compare against known values (special case) - EXPECT_EQ(P(0, 0), 0.f); - EXPECT_EQ(P(1, 1), 0.25f * tilt_var); - EXPECT_EQ(P(2, 2), 0.25f * tilt_var); - EXPECT_EQ(P(3, 3), 0.25f * 0.f); // no yaw var -} - -TEST(AttitudeVariance, setRotVarPitch90) -{ - Quatf q(Eulerf(0.f, M_PI_F, 0.f)); - SquareMatrix24f P; - Vector24f state_vector{}; - state_vector(0) = q(0); - state_vector(1) = q(1); - state_vector(2) = q(2); - state_vector(3) = q(3); - - const float tilt_var = radians(1.2f); - setTiltVar(state_vector, P, tilt_var); - - Vector3f rot_var; - sym::QuatVarToRotVar(state_vector, P, FLT_EPSILON, &rot_var); - - // TODO: FIXME, due to the nonlinearity of the quaternion parameters, - // setting the variance and getting it back is approximate. - // The correct way would be to keep the uncertainty as a 3D vector in the tangent plane - // instead of converting it to the parameter space - // EXPECT_NEAR(rot_var(0), tilt_var, 1e-6f); - // EXPECT_NEAR(rot_var(1), tilt_var, 1e-6f); - // EXPECT_EQ(rot_var(2), 0.f); -} diff --git a/src/modules/ekf2/test/test_EKF_gnss_yaw_generated.cpp b/src/modules/ekf2/test/test_EKF_gnss_yaw_generated.cpp index 79849741ff37..4d0485f5f58e 100644 --- a/src/modules/ekf2/test/test_EKF_gnss_yaw_generated.cpp +++ b/src/modules/ekf2/test/test_EKF_gnss_yaw_generated.cpp @@ -38,83 +38,23 @@ #include "../EKF/python/ekf_derivation/generated/compute_gnss_yaw_pred_innov_var_and_h.h" using namespace matrix; -using D = matrix::Dual; - -void computeHDual(const Vector24f &state_vector, float yaw_offset, Vector24f &H) -{ - matrix::Quaternion q(D(state_vector(0), 0), - D(state_vector(1), 1), - D(state_vector(2), 2), - D(state_vector(3), 3)); - - Dcm R_to_earth(q); - Vector3 ant_vec_bf(cos(D(yaw_offset)), sin(D(yaw_offset)), D()); - Vector3 ant_vec_ef = R_to_earth * ant_vec_bf; - D meas_pred = atan2(ant_vec_ef(1), ant_vec_ef(0)); - - H.setZero(); - - for (int i = 0; i <= 3; i++) { - H(i) = meas_pred.derivative(i); - } -} - -TEST(GnssYawFusionGenerated, SympyVsSymforce) -{ - const float R_YAW = sq(0.3f); - - const float yaw_offset = M_PI_F / 8.f; - const float yaw = M_PI_F; - - const Quatf q(Eulerf(M_PI_F / 4.f, M_PI_F / 3.f, M_PI_F)); - - Vector24f state_vector{}; - state_vector(0) = q(0); - state_vector(1) = q(1); - state_vector(2) = q(2); - state_vector(3) = q(3); - - SquareMatrix24f P = createRandomCovarianceMatrix24f(); - - Vector24f H_dual; - computeHDual(state_vector, yaw_offset, H_dual); - - float meas_pred_symforce; - float innov_var_symforce; - Vector24f H_symforce; - sym::ComputeGnssYawPredInnovVarAndH(state_vector, P, yaw_offset, R_YAW, FLT_EPSILON, &meas_pred_symforce, - &innov_var_symforce, &H_symforce); - - EXPECT_GT(innov_var_symforce, 50.f); - EXPECT_LT(innov_var_symforce, 60.f); - - EXPECT_EQ(H_symforce, H_dual); - - // The predicted yaw is not exactly yaw + offset because roll and pitch are non-zero, but it's close to that - EXPECT_NEAR(meas_pred_symforce, wrap_pi(yaw + yaw_offset), 0.05f); -} TEST(GnssYawFusionGenerated, SingularityPitch90) { // GIVEN: a vertically oriented antenna (antenna vector aligned with the Forward axis) - const Quatf q(Eulerf(0.f, -M_PI_F / 2.f, 0.f)); + StateSample state{}; + state.quat_nominal = Eulerf(0.f, -M_PI_F / 2.f, 0.f); const float yaw_offset = M_PI_F; - Vector24f state_vector{}; - state_vector(0) = q(0); - state_vector(1) = q(1); - state_vector(2) = q(2); - state_vector(3) = q(3); - - SquareMatrix24f P = createRandomCovarianceMatrix24f(); + SquareMatrixState P = createRandomCovarianceMatrix(); const float R_YAW = sq(0.3f); float meas_pred; float innov_var; - Vector24f H; - sym::ComputeGnssYawPredInnovVarAndH(state_vector, P, yaw_offset, R_YAW, FLT_EPSILON, &meas_pred, + VectorState H; + sym::ComputeGnssYawPredInnovVarAndH(state.vector(), P, yaw_offset, R_YAW, FLT_EPSILON, &meas_pred, &innov_var, &H); - Vector24f K = P * H / innov_var; + VectorState K = P * H / innov_var; // THEN: the arctan is singular, the attitude isn't observable, so the innovation variance // is almost infinite and the Kalman gain goes to 0 @@ -125,24 +65,19 @@ TEST(GnssYawFusionGenerated, SingularityPitch90) TEST(GnssYawFusionGenerated, SingularityRoll90) { // GIVEN: a vertically oriented antenna (antenna vector aligned with the Right axis) - const Quatf q(Eulerf(-M_PI_F / 2.f, 0.f, 0.f)); + StateSample state{}; + state.quat_nominal = Eulerf(-M_PI_F / 2.f, 0.f, 0.f); const float yaw_offset = M_PI_F / 2.f; - Vector24f state_vector{}; - state_vector(0) = q(0); - state_vector(1) = q(1); - state_vector(2) = q(2); - state_vector(3) = q(3); - - SquareMatrix24f P = createRandomCovarianceMatrix24f(); + SquareMatrixState P = createRandomCovarianceMatrix(); const float R_YAW = sq(0.3f); float meas_pred; float innov_var; - Vector24f H; - sym::ComputeGnssYawPredInnovVarAndH(state_vector, P, yaw_offset, R_YAW, FLT_EPSILON, &meas_pred, + VectorState H; + sym::ComputeGnssYawPredInnovVarAndH(state.vector(), P, yaw_offset, R_YAW, FLT_EPSILON, &meas_pred, &innov_var, &H); - Vector24f K = P * H / innov_var; + VectorState K = P * H / innov_var; // THEN: the arctan is singular, the attitude isn't observable, so the innovation variance // is almost infinite and the Kalman gain goes to 0 diff --git a/src/modules/ekf2/test/test_EKF_gps_yaw.cpp b/src/modules/ekf2/test/test_EKF_gps_yaw.cpp index 781133dde28b..42737306eae3 100644 --- a/src/modules/ekf2/test/test_EKF_gps_yaw.cpp +++ b/src/modules/ekf2/test/test_EKF_gps_yaw.cpp @@ -333,10 +333,9 @@ TEST_F(EkfGpsHeadingTest, stopOnGround) _ekf_wrapper.setMagFuseTypeNone(); // WHEN: running without yaw aiding - const matrix::Vector4f quat_variance_before = _ekf->getQuaternionVariance(); + const float yaw_variance_before = _ekf->getYawVar(); _sensor_simulator.runSeconds(20.0); - const matrix::Vector4f quat_variance_after = _ekf->getQuaternionVariance(); // THEN: the yaw variance increases - EXPECT_GT(quat_variance_after(3), quat_variance_before(3)); + EXPECT_GT(_ekf->getYawVar(), yaw_variance_before); } diff --git a/src/modules/ekf2/test/test_EKF_initialization.cpp b/src/modules/ekf2/test/test_EKF_initialization.cpp index 5dad09e2e8b0..d7959489295e 100644 --- a/src/modules/ekf2/test/test_EKF_initialization.cpp +++ b/src/modules/ekf2/test/test_EKF_initialization.cpp @@ -78,10 +78,10 @@ class EkfInitializationTest : public ::testing::Test void quaternionVarianceBigEnoughAfterOrientationInitialization(float quat_variance_limit = 0.00001f) { - const matrix::Vector4f quat_variance = _ekf->getQuaternionVariance(); + const matrix::Vector3f quat_variance = _ekf->getQuaternionVariance(); + EXPECT_TRUE(quat_variance(0) > quat_variance_limit) << "quat_variance(3): " << quat_variance(0); EXPECT_TRUE(quat_variance(1) > quat_variance_limit) << "quat_variance(1): " << quat_variance(1); EXPECT_TRUE(quat_variance(2) > quat_variance_limit) << "quat_variance(2): " << quat_variance(2); - EXPECT_TRUE(quat_variance(3) > quat_variance_limit) << "quat_variance(3): " << quat_variance(3); } void yawVarianceBigEnoughAfterHeadingReset() @@ -209,12 +209,12 @@ TEST_F(EkfInitializationTest, gyroBias) if (fabsf(accel_bias(2)) > 0.3f) { // Print state covariance and correlation matrices for debugging - const matrix::SquareMatrix P = _ekf->covariances(); + const auto P = _ekf->covariances(); printf("State covariance:\n"); - for (int i = 0; i <= 15; i++) { - for (int j = 0; j <= 15; j++) { + for (int i = 0; i <= State::size; i++) { + for (int j = 0; j <= State::size; j++) { printf("%.3fe-9 ", ((double)P(i, j)) * 1e9); } @@ -224,10 +224,10 @@ TEST_F(EkfInitializationTest, gyroBias) printf("State correlation:\n"); printf("\t0\t1\t2\t3\t4\t5\t6\t7\t8\t9\t10\t11\t12\t13\t14\t15\n"); - for (uint8_t i = 0; i <= 15; i++) { + for (uint8_t i = 0; i <= State::size; i++) { printf("%d| ", i); - for (uint8_t j = 0; j <= 15; j++) { + for (uint8_t j = 0; j <= State::size; j++) { float corr = sqrtf(fabsf(P(i, i) * P(j, j))); if (corr > 0.0f) { diff --git a/src/modules/ekf2/test/test_EKF_mag_3d_fusion_generated.cpp b/src/modules/ekf2/test/test_EKF_mag_3d_fusion_generated.cpp deleted file mode 100644 index 642e17d735b2..000000000000 --- a/src/modules/ekf2/test/test_EKF_mag_3d_fusion_generated.cpp +++ /dev/null @@ -1,110 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -#include -#include "EKF/ekf.h" -#include "test_helper/comparison_helper.h" - -#include "../EKF/python/ekf_derivation/generated/compute_mag_innov_innov_var_and_hx.h" -#include "../EKF/python/ekf_derivation/generated/compute_mag_y_innov_var_and_h.h" -#include "../EKF/python/ekf_derivation/generated/compute_mag_z_innov_var_and_h.h" - -using namespace matrix; -using D = matrix::Dual; - -void computeHDual(const Vector24f &state_vector, int axis, Vector24f &H) -{ - matrix::Quaternion q(D(state_vector(0), 0), - D(state_vector(1), 1), - D(state_vector(2), 2), - D(state_vector(3), 3)); - - Vector3 mag_field_earth(D(state_vector(16), 16), D(state_vector(17), 17), D(state_vector(18), 18)); - Vector3 mag_bias_body(D(state_vector(19), 19), D(state_vector(20), 20), D(state_vector(21), 21)); - - Vector3 mag_pred = Dcm(q).transpose() * mag_field_earth + mag_bias_body; - - H.setZero(); - - for (int i = 0; i <= 23; i++) { - H(i) = mag_pred(axis).derivative(i); - } -} - -TEST(Mag3DFusionGenerated, symforceVsDual) -{ - const Quatf q(Eulerf(-M_PI_F / 2.f, M_PI_F / 3.f, M_PI_F * 4.f / 5.f)); - const float q0 = q(0); - const float q1 = q(1); - const float q2 = q(2); - const float q3 = q(3); - - const float magN = 2.0f * ((float)randf() - 0.5f); - const float magE = 2.0f * ((float)randf() - 0.5f); - const float magD = 2.0f * ((float)randf() - 0.5f); - - Vector24f state_vector{}; - state_vector(0) = q0; - state_vector(1) = q1; - state_vector(2) = q2; - state_vector(3) = q3; - state_vector(16) = magN; - state_vector(17) = magE; - state_vector(18) = magD; - - const float R_MAG = sq(0.05f); - - SquareMatrix24f P = createRandomCovarianceMatrix24f(); - - Vector24f H_dual; - Vector24f Hfusion_symforce; - Vector3f mag_innov_var_symforce; - - for (int i = 0; i < 3; i++) { - computeHDual(state_vector, i, H_dual); - - if (i == 0) { - Vector3f innov; - sym::ComputeMagInnovInnovVarAndHx(state_vector, P, Vector3f(), R_MAG, FLT_EPSILON, &innov, &mag_innov_var_symforce, - &Hfusion_symforce); - - } else if (i == 1) { - sym::ComputeMagYInnovVarAndH(state_vector, P, R_MAG, FLT_EPSILON, &(mag_innov_var_symforce(i)), &Hfusion_symforce); - - } else { - sym::ComputeMagZInnovVarAndH(state_vector, P, R_MAG, FLT_EPSILON, &(mag_innov_var_symforce(i)), &Hfusion_symforce); - } - - EXPECT_EQ(Hfusion_symforce, H_dual); - } -} diff --git a/src/modules/ekf2/test/test_EKF_mag_declination_generated.cpp b/src/modules/ekf2/test/test_EKF_mag_declination_generated.cpp index 5751912be061..5bc15e84366f 100644 --- a/src/modules/ekf2/test/test_EKF_mag_declination_generated.cpp +++ b/src/modules/ekf2/test/test_EKF_mag_declination_generated.cpp @@ -36,25 +36,26 @@ #include "test_helper/comparison_helper.h" #include "../EKF/python/ekf_derivation/generated/compute_mag_declination_pred_innov_var_and_h.h" +#include "../EKF/python/ekf_derivation/generated/state.h" using namespace matrix; TEST(MagDeclinationGenerated, declination90deg) { // GIVEN: an estimated mag declination of 90 degrees - Vector24f state_vector{}; - state_vector(16) = 0.f; // North mag field - state_vector(17) = 0.2f; // East mag field + StateSample state{}; + state.mag_I(0) = 0.f; // North mag field + state.mag_I(1) = 0.2f; // East mag field const float R = sq(radians(sq(0.5f))); - SquareMatrix24f P = createRandomCovarianceMatrix24f(); + SquareMatrixState P = createRandomCovarianceMatrix(); - Vector24f H; + VectorState H; float decl_pred; float innov_var; const float decl = radians(90.f); - sym::ComputeMagDeclinationPredInnovVarAndH(state_vector, P, R, FLT_EPSILON, &decl_pred, &innov_var, &H); + sym::ComputeMagDeclinationPredInnovVarAndH(state.vector(), P, R, FLT_EPSILON, &decl_pred, &innov_var, &H); // THEN: Even at the singularity point, atan2 is still defined EXPECT_TRUE(innov_var < 5000.f && innov_var > R) << "innov_var = " << innov_var; @@ -64,123 +65,21 @@ TEST(MagDeclinationGenerated, declination90deg) TEST(MagDeclinationGenerated, declinationUndefined) { // GIVEN: an undefined declination - Vector24f state_vector{}; - state_vector(16) = 0.f; // North mag field - state_vector(17) = 0.f; // East mag field + StateSample state{}; + state.mag_I(0) = 0.f; // North mag field + state.mag_I(1) = 0.f; // East mag field const float R = sq(radians(sq(0.5f))); - SquareMatrix24f P = createRandomCovarianceMatrix24f(); + SquareMatrixState P = createRandomCovarianceMatrix(); - Vector24f H; + VectorState H; float decl_pred; float innov_var; const float decl = radians(0.f); - sym::ComputeMagDeclinationPredInnovVarAndH(state_vector, P, R, FLT_EPSILON, &decl_pred, &innov_var, &H); + sym::ComputeMagDeclinationPredInnovVarAndH(state.vector(), P, R, FLT_EPSILON, &decl_pred, &innov_var, &H); // THEN: the innovation variance is gigantic but finite EXPECT_TRUE(PX4_ISFINITE(innov_var) && innov_var > R && innov_var > 1e9f) << "innov_var = " << innov_var; EXPECT_LT(fabsf(wrap_pi(decl_pred - decl)), 1e-6f); } - -void sympyMagDeclInnovVarHAndK(float magN, float magE, const SquareMatrix24f &P, float R_DECL, - float &innovation_variance, Vector24f &H, Vector24f &Kfusion) -{ - const float h_field_min = 1e-3f; - const float magN_sq = sq(magN); - - if (magN_sq < sq(h_field_min)) { - printf("bad numerical conditioning\n"); - return; - } - - const float HK0 = 1.0F / magN_sq; - const float HK1 = HK0 * sq(magE) + 1.0F; - const float HK2 = 1.0F / HK1; - const float HK3 = 1.0F / magN; - const float HK4 = HK2 * HK3; - const float HK5 = HK3 * magE; - const float HK6 = HK5 * P(16, 17) - P(17, 17); - const float HK7 = 1.0F / sq(HK1); - const float HK8 = HK5 * P(16, 16) - P(16, 17); - innovation_variance = -HK0 * HK6 * HK7 + HK7 * HK8 * magE / (magN * magN_sq) + R_DECL; - float HK9; - - if (innovation_variance > R_DECL) { - HK9 = HK4 / innovation_variance; - - } else { - printf("bad numerical conditioning\n"); - return; - } - - // Calculate the observation Jacobian - // Note only 2 terms are non-zero which can be used in matrix operations for calculation of Kalman gains and covariance update to significantly reduce cost - float Hfusion[24] = {}; - Hfusion[16] = -HK0 * HK2 * magE; - Hfusion[17] = HK4; - - // Calculate the Kalman gains - for (unsigned row = 0; row <= 15; row++) { - Kfusion(row) = -HK9 * (HK5 * P(row, 16) - P(row, 17)); - } - - Kfusion(16) = -HK8 * HK9; - Kfusion(17) = -HK6 * HK9; - - for (unsigned row = 18; row <= 23; row++) { - Kfusion(row) = -HK9 * (HK5 * P(16, row) - P(17, row)); - } - - for (int row = 0; row < 24; row++) { - H(row) = Hfusion[row]; - } -} - -TEST(MagDeclinationGenerated, SympyVsSymforce) -{ - const float R_DECL = sq(0.3f); - const float mag_n = 0.08f; - const float mag_e = -0.06f; - - Vector24f state_vector{}; - state_vector(16) = mag_n; - state_vector(17) = mag_e; - - const float decl = M_PI_F; - - SquareMatrix24f P = createRandomCovarianceMatrix24f(); - - Vector24f H_sympy; - Vector24f H_symforce; - Vector24f K_sympy; - Vector24f K_symforce; - float innov_sympy; - float pred_symforce; - float innov_var_sympy; - float innov_var_symforce; - - sympyMagDeclInnovVarHAndK(mag_n, mag_e, P, R_DECL, innov_var_sympy, H_sympy, K_sympy); - innov_sympy = wrap_pi(std::atan2(mag_e, mag_n) - decl); - sym::ComputeMagDeclinationPredInnovVarAndH(state_vector, P, R_DECL, FLT_EPSILON, &pred_symforce, - &innov_var_symforce, &H_symforce); - const float innov_symforce = wrap_pi(pred_symforce - decl); - K_symforce = P * H_symforce / innov_var_symforce; - - EXPECT_NEAR(innov_sympy, innov_symforce, 1e-5f); - EXPECT_NEAR(innov_var_sympy, innov_var_symforce, 1e-2f); // Slightly different because of epsilon - - DiffRatioReport report = computeDiffRatioVector24f(H_sympy, H_symforce); - EXPECT_LT(report.max_diff_fraction, 2e-4f) - << "Max diff fraction = " << report.max_diff_fraction - << " location index = " << report.max_row - << " sympy = " << report.max_v1 - << " symforce = " << report.max_v2; - - report = computeDiffRatioVector24f(K_sympy, K_symforce); - EXPECT_LT(report.max_diff_fraction, 2e-4f) - << "Max diff fraction = " << report.max_diff_fraction - << " location index = " << report.max_row - << " sympy = " << report.max_v1 - << " symforce = " << report.max_v2; -} diff --git a/src/modules/ekf2/test/test_EKF_opt_flow_fusion_generated.cpp b/src/modules/ekf2/test/test_EKF_opt_flow_fusion_generated.cpp deleted file mode 100644 index db2400d4b398..000000000000 --- a/src/modules/ekf2/test/test_EKF_opt_flow_fusion_generated.cpp +++ /dev/null @@ -1,115 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -#include -#include "EKF/ekf.h" -#include "test_helper/comparison_helper.h" - -#include "../EKF/python/ekf_derivation/generated/compute_flow_xy_innov_var_and_hx.h" -#include "../EKF/python/ekf_derivation/generated/compute_flow_y_innov_var_and_h.h" - -using namespace matrix; -using D = matrix::Dual; - -void computeHDual(const Vector24f &state_vector, float range, int axis, Vector24f &H) -{ - matrix::Quaternion q(D(state_vector(0), 0), - D(state_vector(1), 1), - D(state_vector(2), 2), - D(state_vector(3), 3)); - - // calculate the velocity of the sensor in the earth frame - Vector3 vel_earth(D(state_vector(4), 4), D(state_vector(5), 5), D(state_vector(6), 6)); - - // rotate into body frame - Vector3 vel_body = Dcm(q).transpose() * vel_earth; - matrix::Vector2 predicted_flow; - predicted_flow(0) = vel_body(1) / range; - predicted_flow(1) = -vel_body(0) / range; - - H.setZero(); - - for (int i = 0; i <= 6; i++) { - H(i) = predicted_flow(axis).derivative(i); - } -} - -TEST(OptFlowFusionGenerated, symforceVsDual) -{ - // Compare calculation of observation Jacobians - const Quatf q(Eulerf(M_PI_F / 4.f, -M_PI_F / 6.f, M_PI_F)); - const float q0 = q(0); - const float q1 = q(1); - const float q2 = q(2); - const float q3 = q(3); - - const float vn = 5.f; - const float ve = 0.f; - const float vd = -1.5f; - - const float range = 5.0f; - - Vector24f state_vector{}; - state_vector(0) = q0; - state_vector(1) = q1; - state_vector(2) = q2; - state_vector(3) = q3; - state_vector(4) = vn; - state_vector(5) = ve; - state_vector(6) = vd; - - const float R_LOS = sq(0.15f); - - SquareMatrix24f P; - - Vector24f H; - Vector24f H_dual; - Vector2f innov_var; - - for (int i = 0; i < 2; i++) { - computeHDual(state_vector, range, i, H_dual); - - if (i == 0) { - sym::ComputeFlowXyInnovVarAndHx(state_vector, P, range, R_LOS, FLT_EPSILON, &innov_var, &H); - - } else { - sym::ComputeFlowYInnovVarAndH(state_vector, P, range, R_LOS, FLT_EPSILON, &innov_var(1), &H); - } - - // Both derivations are equivalent - EXPECT_EQ(H, H_dual); - - // Since the state variance is 0, the observation variance is the innovation variance - EXPECT_FLOAT_EQ(innov_var(i), R_LOS); - } -} diff --git a/src/modules/ekf2/test/test_EKF_sideslip_fusion_generated.cpp b/src/modules/ekf2/test/test_EKF_sideslip_fusion_generated.cpp deleted file mode 100644 index 34362b450ef6..000000000000 --- a/src/modules/ekf2/test/test_EKF_sideslip_fusion_generated.cpp +++ /dev/null @@ -1,105 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -#include -#include "EKF/ekf.h" -#include "test_helper/comparison_helper.h" - -#include "../EKF/python/ekf_derivation/generated/compute_sideslip_innov_and_innov_var.h" -#include "../EKF/python/ekf_derivation/generated/compute_sideslip_h_and_k.h" - -using namespace matrix; -using D = matrix::Dual; - -void computeHDual(const Vector24f &state_vector, Vector24f &H) -{ - matrix::Quaternion q(D(state_vector(0), 0), - D(state_vector(1), 1), - D(state_vector(2), 2), - D(state_vector(3), 3)); - - Vector3 vel_earth(D(state_vector(4), 4), D(state_vector(5), 5), D(state_vector(6), 6)); - Vector3 wind_earth(D(state_vector(22), 22), D(state_vector(23), 23), D()); - Vector3 vel_rel_body = Dcm(q).transpose() * (vel_earth - wind_earth); - D sideslip_pred = vel_rel_body(1) / vel_rel_body(0); - - H.setZero(); - - for (int i = 0; i <= 23; i++) { - H(i) = sideslip_pred.derivative(i); - } -} - -TEST(SideslipFusionGenerated, symforceVsDual) -{ - // Compare calculation of observation Jacobians and Kalman gains for sympy and symforce generated equations - const float R_BETA = sq(2.5f); - - const Quatf q(Eulerf(-M_PI_F / 2.f, M_PI_F / 3.f, M_PI_F * 4.f / 5.f)); - const float q0 = q(0); - const float q1 = q(1); - const float q2 = q(2); - const float q3 = q(3); - - const float vn = 9.0f; - const float ve = 12.0f; - const float vd = -1.5f; - - const float vwn = -4.0f; - const float vwe = 3.0f; - - Vector24f state_vector{}; - state_vector(0) = q0; - state_vector(1) = q1; - state_vector(2) = q2; - state_vector(3) = q3; - state_vector(4) = vn; - state_vector(5) = ve; - state_vector(6) = vd; - state_vector(22) = vwn; - state_vector(23) = vwe; - - SquareMatrix24f P = createRandomCovarianceMatrix24f(); - - float innov; - float innov_var; - Vector24f H_symforce; - Vector24f K_symforce; - Vector24f H_dual; - - sym::ComputeSideslipInnovAndInnovVar(state_vector, P, R_BETA, FLT_EPSILON, &innov, &innov_var); - sym::ComputeSideslipHAndK(state_vector, P, innov_var, FLT_EPSILON, &H_symforce, &K_symforce); - computeHDual(state_vector, H_dual); - - EXPECT_TRUE((H_symforce - H_dual).max() < 1e-3f) << H_symforce << H_dual; -} diff --git a/src/modules/ekf2/test/test_EKF_yaw_fusion_generated.cpp b/src/modules/ekf2/test/test_EKF_yaw_fusion_generated.cpp index c447af701c52..ab02fd3cacf8 100644 --- a/src/modules/ekf2/test/test_EKF_yaw_fusion_generated.cpp +++ b/src/modules/ekf2/test/test_EKF_yaw_fusion_generated.cpp @@ -46,26 +46,21 @@ TEST(YawFusionGenerated, singularityYawEquivalence) { // GIVEN: an attitude that should give a singularity when transforming the // rotation matrix to Euler yaw - const Quatf q(Eulerf(M_PI_F, 0.f, M_PI_F)); - - Vector24f state_vector{}; - state_vector(0) = q(0); - state_vector(1) = q(1); - state_vector(2) = q(2); - state_vector(3) = q(3); + StateSample state{}; + state.quat_nominal = Eulerf(M_PI_F, 0.f, M_PI_F); const float R = sq(radians(10.f)); - SquareMatrix24f P = createRandomCovarianceMatrix24f(); + SquareMatrixState P = createRandomCovarianceMatrix(); - Vector24f H_a; - Vector24f H_b; + VectorState H_a; + VectorState H_b; float innov_var_a; float innov_var_b; // WHEN: computing the innovation variance and H using two different // alternate forms (one is singular at pi/2 and the other one at 0) - sym::ComputeYaw321InnovVarAndH(state_vector, P, R, FLT_EPSILON, &innov_var_a, &H_a); - sym::ComputeYaw321InnovVarAndHAlternate(state_vector, P, R, FLT_EPSILON, &innov_var_b, &H_b); + sym::ComputeYaw321InnovVarAndH(state.vector(), P, R, FLT_EPSILON, &innov_var_a, &H_a); + sym::ComputeYaw321InnovVarAndHAlternate(state.vector(), P, R, FLT_EPSILON, &innov_var_b, &H_b); // THEN: Even at the singularity point, the result is still correct, thanks to epsilon EXPECT_TRUE(isEqual(H_a, H_b)); @@ -76,24 +71,19 @@ TEST(YawFusionGenerated, singularityYawEquivalence) TEST(YawFusionGenerated, gimbalLock321vs312) { // GIVEN: an attitude at gimbal lock position - const Quatf q(Eulerf(0.f, -M_PI_F / 2.f, M_PI_F)); - - Vector24f state_vector{}; - state_vector(0) = q(0); - state_vector(1) = q(1); - state_vector(2) = q(2); - state_vector(3) = q(3); + StateSample state{}; + state.quat_nominal = Eulerf(0.f, -M_PI_F / 2.f, M_PI_F); const float R = sq(radians(10.f)); - SquareMatrix24f P = createRandomCovarianceMatrix24f(); + SquareMatrixState P = createRandomCovarianceMatrix(); - Vector24f H_321; - Vector24f H_312; + VectorState H_321; + VectorState H_312; float innov_var_321; float innov_var_312; - sym::ComputeYaw321InnovVarAndH(state_vector, P, R, FLT_EPSILON, &innov_var_321, &H_321); + sym::ComputeYaw321InnovVarAndH(state.vector(), P, R, FLT_EPSILON, &innov_var_321, &H_321); - sym::ComputeYaw312InnovVarAndH(state_vector, P, R, FLT_EPSILON, &innov_var_312, &H_312); + sym::ComputeYaw312InnovVarAndH(state.vector(), P, R, FLT_EPSILON, &innov_var_312, &H_312); // THEN: both computation are not equivalent, 321 is undefined but 312 is valid EXPECT_FALSE(isEqual(H_321, H_312)); @@ -104,27 +94,23 @@ TEST(YawFusionGenerated, gimbalLock321vs312) TEST(YawFusionGenerated, positiveVarianceAllOrientations) { const float R = sq(radians(10.f)); - SquareMatrix24f P = createRandomCovarianceMatrix24f(); + SquareMatrixState P = createRandomCovarianceMatrix(); - Vector24f H; + VectorState H; float innov_var; // GIVEN: all orientations (90 deg steps) for (float yaw = 0.f; yaw < 2.f * M_PI_F; yaw += M_PI_F / 2.f) { for (float pitch = 0.f; pitch < 2.f * M_PI_F; pitch += M_PI_F / 2.f) { for (float roll = 0.f; roll < 2.f * M_PI_F; roll += M_PI_F / 2.f) { - const Quatf q(Eulerf(roll, pitch, yaw)); - Vector24f state_vector{}; - state_vector(0) = q(0); - state_vector(1) = q(1); - state_vector(2) = q(2); - state_vector(3) = q(3); + StateSample state{}; + state.quat_nominal = Eulerf(roll, pitch, yaw); - if (shouldUse321RotationSequence(Dcmf(q))) { - sym::ComputeYaw321InnovVarAndH(state_vector, P, R, FLT_EPSILON, &innov_var, &H); + if (shouldUse321RotationSequence(Dcmf(state.quat_nominal))) { + sym::ComputeYaw321InnovVarAndH(state.vector(), P, R, FLT_EPSILON, &innov_var, &H); } else { - sym::ComputeYaw312InnovVarAndH(state_vector, P, R, FLT_EPSILON, &innov_var, &H); + sym::ComputeYaw312InnovVarAndH(state.vector(), P, R, FLT_EPSILON, &innov_var, &H); } // THEN: the innovation variance must be positive and finite @@ -137,74 +123,3 @@ TEST(YawFusionGenerated, positiveVarianceAllOrientations) } } } - -using D = matrix::Dual; - -void computeHDual321(const Vector24f &state_vector, Vector24f &H) -{ - matrix::Quaternion q(D(state_vector(0), 0), - D(state_vector(1), 1), - D(state_vector(2), 2), - D(state_vector(3), 3)); - - Dcm R_to_earth(q); - D yaw_pred = atan2(R_to_earth(1, 0), R_to_earth(0, 0)); - - H.setZero(); - - for (int i = 0; i <= 3; i++) { - H(i) = yaw_pred.derivative(i); - } -} - -void computeHDual312(const Vector24f &state_vector, Vector24f &H) -{ - matrix::Quaternion q(D(state_vector(0), 0), - D(state_vector(1), 1), - D(state_vector(2), 2), - D(state_vector(3), 3)); - - Dcm R_to_earth(q); - D yaw_pred = atan2(-R_to_earth(0, 1), R_to_earth(1, 1)); - - H.setZero(); - - for (int i = 0; i <= 3; i++) { - H(i) = yaw_pred.derivative(i); - } -} - -TEST(YawFusionGenerated, symforceVsDual) -{ - const float R = sq(radians(10.f)); - SquareMatrix24f P = createRandomCovarianceMatrix24f(); - - Vector24f H_dual; - Vector24f Hfusion_symforce; - float innov_var; - - // GIVEN: all orientations (90 deg steps) - for (float yaw = 0.f; yaw < 2.f * M_PI_F; yaw += M_PI_F / 2.f) { - for (float pitch = 0.f; pitch < 2.f * M_PI_F; pitch += M_PI_F / 2.f) { - for (float roll = 0.f; roll < 2.f * M_PI_F; roll += M_PI_F / 2.f) { - const Quatf q(Eulerf(roll, pitch, yaw)); - Vector24f state_vector{}; - state_vector(0) = q(0); - state_vector(1) = q(1); - state_vector(2) = q(2); - state_vector(3) = q(3); - - if (shouldUse321RotationSequence(Dcmf(q))) { - sym::ComputeYaw321InnovVarAndH(state_vector, P, R, FLT_EPSILON, &innov_var, &Hfusion_symforce); - computeHDual321(state_vector, H_dual); - - } else { - sym::ComputeYaw312InnovVarAndH(state_vector, P, R, FLT_EPSILON, &innov_var, &Hfusion_symforce); - computeHDual312(state_vector, H_dual); - } - - EXPECT_EQ(Hfusion_symforce, H_dual); - } - } - } -} diff --git a/src/modules/ekf2/test/test_helper/comparison_helper.cpp b/src/modules/ekf2/test/test_helper/comparison_helper.cpp index 0d8ddcd74a5a..12e3091b19d5 100644 --- a/src/modules/ekf2/test/test_helper/comparison_helper.cpp +++ b/src/modules/ekf2/test/test_helper/comparison_helper.cpp @@ -38,12 +38,12 @@ float randf() return (float)rand() / (float)RAND_MAX; } -SquareMatrix24f createRandomCovarianceMatrix24f() +SquareMatrixState createRandomCovarianceMatrix() { // Create a symmetric square matrix - SquareMatrix24f P; + SquareMatrixState P; - for (int col = 0; col <= 23; col++) { + for (int col = 0; col < State::size; col++) { for (int row = 0; row <= col; row++) { if (row == col) { P(row, col) = randf(); @@ -59,61 +59,3 @@ SquareMatrix24f createRandomCovarianceMatrix24f() return P; } - -DiffRatioReport computeDiffRatioVector24f(const Vector24f &v1, const Vector24f &v2) -{ - DiffRatioReport report = {}; - - for (int row = 0; row < 24; row++) { - float diff_fraction; - - if (fabsf(v1(row)) > FLT_EPSILON) { - diff_fraction = fabsf(v2(row) - v1(row)) / fabsf(v1(row)); - - } else if (fabsf(v2(row)) > FLT_EPSILON) { - diff_fraction = fabsf(v2(row) - v1(row)) / fabsf(v2(row)); - - } else { - diff_fraction = 0.0f; - } - - if (diff_fraction > report.max_diff_fraction) { - report.max_diff_fraction = diff_fraction; - report.max_row = row; - report.max_v1 = v1(row); - report.max_v2 = v2(row); - } - } - - return report; -} - -DiffRatioReport computeDiffRatioSquareMatrix24f(const SquareMatrix24f &m1, const SquareMatrix24f &m2) -{ - DiffRatioReport report = {}; - - for (int row = 0; row < 24; row++) { - for (int col = 0; col < 24; col++) { - float diff_fraction; - - if (fabsf(m1(row, col)) > FLT_EPSILON) { - diff_fraction = fabsf(m2(row, col) - m1(row, col)) / fabsf(m1(row, col)); - - } else if (fabsf(m2(row, col)) > FLT_EPSILON) { - diff_fraction = fabsf(m2(row, col) - m1(row, col)) / fabsf(m2(row, col)); - - } else { - diff_fraction = 0.0f; - } - - if (diff_fraction > report.max_diff_fraction) { - report.max_diff_fraction = diff_fraction; - report.max_row = row; - report.max_v1 = m1(row, col); - report.max_v2 = m2(row, col); - } - } - } - - return report; -} diff --git a/src/modules/ekf2/test/test_helper/comparison_helper.h b/src/modules/ekf2/test/test_helper/comparison_helper.h index b66b9461c906..1ff2662992ee 100644 --- a/src/modules/ekf2/test/test_helper/comparison_helper.h +++ b/src/modules/ekf2/test/test_helper/comparison_helper.h @@ -36,24 +36,11 @@ #include "EKF/ekf.h" -typedef matrix::Vector Vector24f; -typedef matrix::SquareMatrix SquareMatrix24f; -template -using SparseVector24f = matrix::SparseVectorf<24, Idxs...>; - -struct DiffRatioReport { - float max_diff_fraction; - float max_row; - float max_v1; - float max_v2; -}; +typedef matrix::Vector VectorState; +typedef matrix::SquareMatrix SquareMatrixState; float randf(); // Create a symmetrical positive dfinite matrix with off diagonals between -1 and 1 and diagonals between 0 and 1 -SquareMatrix24f createRandomCovarianceMatrix24f(); - -// Find largest element-wise difference as a fraction of v1 or v2 -DiffRatioReport computeDiffRatioVector24f(const Vector24f &v1, const Vector24f &v2); -DiffRatioReport computeDiffRatioSquareMatrix24f(const SquareMatrix24f &m1, const SquareMatrix24f &m2); +SquareMatrixState createRandomCovarianceMatrix(); #endif diff --git a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp index 9ece7028884d..5538965f0ed1 100644 --- a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp +++ b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp @@ -750,7 +750,6 @@ void BlockLocalPositionEstimator::publishEstimatorStatus() // replacing the hor wind cov with terrain altitude covariance _pub_est_states.get().covariances[22] = m_P(X_tz, X_tz); - _pub_est_states.get().covariances[23] = NAN; _pub_est_states.get().n_states = n_x; _pub_est_states.get().timestamp = hrt_absolute_time();