From 4b34c9a0a4c6fc5337cfc70ded1395924ca44f2b Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Tue, 17 Mar 2026 16:59:13 +0900 Subject: [PATCH 01/60] add: test_autoware Signed-off-by: nokosaaan --- applications/tests/test_autoware/Cargo.toml | 20 + .../test_autoware/ekf_localizer/Cargo.toml | 13 + .../test_autoware/ekf_localizer/README.md | 150 + .../test_autoware/ekf_localizer/src/lib.rs | 599 ++ .../test_autoware/gyro_odometer/Cargo.toml | 12 + .../test_autoware/gyro_odometer/src/lib.rs | 468 ++ .../test_autoware/imu_corrector/Cargo.toml | 11 + .../test_autoware/imu_corrector/src/lib.rs | 605 ++ .../tests/test_autoware/imu_driver/Cargo.toml | 9 + .../tests/test_autoware/imu_driver/src/lib.rs | 341 + applications/tests/test_autoware/imu_raw.csv | 5709 +++++++++++++++++ applications/tests/test_autoware/src/lib.rs | 1121 ++++ .../vehicle_velocity_converter/Cargo.toml | 11 + .../vehicle_velocity_converter/src/lib.rs | 300 + .../tests/test_autoware/velocity_status.csv | 5700 ++++++++++++++++ userland/Cargo.toml | 7 +- 16 files changed, 15075 insertions(+), 1 deletion(-) create mode 100644 applications/tests/test_autoware/Cargo.toml create mode 100644 applications/tests/test_autoware/ekf_localizer/Cargo.toml create mode 100644 applications/tests/test_autoware/ekf_localizer/README.md create mode 100644 applications/tests/test_autoware/ekf_localizer/src/lib.rs create mode 100644 applications/tests/test_autoware/gyro_odometer/Cargo.toml create mode 100644 applications/tests/test_autoware/gyro_odometer/src/lib.rs create mode 100644 applications/tests/test_autoware/imu_corrector/Cargo.toml create mode 100644 applications/tests/test_autoware/imu_corrector/src/lib.rs create mode 100644 applications/tests/test_autoware/imu_driver/Cargo.toml create mode 100644 applications/tests/test_autoware/imu_driver/src/lib.rs create mode 100644 applications/tests/test_autoware/imu_raw.csv create mode 100644 applications/tests/test_autoware/src/lib.rs create mode 100644 applications/tests/test_autoware/vehicle_velocity_converter/Cargo.toml create mode 100644 applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs create mode 100644 applications/tests/test_autoware/velocity_status.csv diff --git a/applications/tests/test_autoware/Cargo.toml b/applications/tests/test_autoware/Cargo.toml new file mode 100644 index 000000000..9ded42fb7 --- /dev/null +++ b/applications/tests/test_autoware/Cargo.toml @@ -0,0 +1,20 @@ +[package] +name = "test_autoware" +version = "0.1.0" +edition = "2021" + +[lib] +path = "src/lib.rs" +crate-type = ["rlib"] + +[dependencies] +log = "0.4" +libm = "0.2" +csv-core = "0.1" +awkernel_async_lib = { path = "../../../awkernel_async_lib", default-features = false } +awkernel_lib = { path = "../../../awkernel_lib", default-features = false } +imu_driver = { path = "./imu_driver", default-features = false } +imu_corrector = { path = "./imu_corrector", default-features = false } +vehicle_velocity_converter = { path = "./vehicle_velocity_converter", default-features = false } +gyro_odometer = { path = "./gyro_odometer", default-features = false} +ekf_localizer = { path = "./ekf_localizer", default-features = false} \ No newline at end of file diff --git a/applications/tests/test_autoware/ekf_localizer/Cargo.toml b/applications/tests/test_autoware/ekf_localizer/Cargo.toml new file mode 100644 index 000000000..b81a101b1 --- /dev/null +++ b/applications/tests/test_autoware/ekf_localizer/Cargo.toml @@ -0,0 +1,13 @@ +[package] +name = "ekf_localizer" +version = "0.1.0" +edition = "2021" + +[dependencies] +# no_std compatible dependencies +libm = "0.2" +nalgebra = { version = "0.32", default-features = false} +approx = "0.5" + +# Optional: for better math functions +micromath = "2.1" \ No newline at end of file diff --git a/applications/tests/test_autoware/ekf_localizer/README.md b/applications/tests/test_autoware/ekf_localizer/README.md new file mode 100644 index 000000000..f84837adc --- /dev/null +++ b/applications/tests/test_autoware/ekf_localizer/README.md @@ -0,0 +1,150 @@ +# EKF Localizer for awkernel + +This is a no_std Rust implementation of the EKF (Extended Kalman Filter) Localizer for awkernel, extracted from Autoware's EKF Localizer. + +## Features + +- **no_std compatible**: Can run in embedded environments without standard library +- **TF publishing support**: Provides transform data for ROS2 tf broadcasting +- **EKF state estimation**: Estimates vehicle pose (x, y, yaw) and velocity (vx, wz) +- **Yaw bias estimation**: Optional yaw bias estimation for improved accuracy +- **Simple 1D filters**: For z, roll, and pitch estimation + +## State Vector + +The EKF state vector contains 6 elements: +- `x`: X position [m] +- `y`: Y position [m] +- `yaw`: Yaw angle [rad] +- `yaw_bias`: Yaw bias [rad] +- `vx`: X velocity [m/s] +- `wz`: Z angular velocity [rad/s] + +## Usage + +### Basic Usage + +```rust +use ekf_localizer::{EKFModule, EKFParameters, Pose, Transform, Point3D, Quaternion}; + +// Create EKF parameters +let params = EKFParameters::default(); + +// Create EKF module +let mut ekf = EKFModule::new(params); + +// Initialize with initial pose +let initial_pose = Pose { + position: Point3D { x: 0.0, y: 0.0, z: 0.0 }, + orientation: Quaternion { x: 0.0, y: 0.0, z: 0.0, w: 1.0 }, +}; + +let transform = Transform { + translation: Point3D { x: 0.0, y: 0.0, z: 0.0 }, + rotation: Quaternion { x: 0.0, y: 0.0, z: 0.0, w: 1.0 }, +}; + +ekf.initialize(initial_pose, transform); + +// Prediction step +ekf.predict(0.01); // dt = 10ms + +// Get current pose for tf publishing +let pose = ekf.get_current_pose(false); +let transform = ekf.get_transform("base_link"); + +// Get covariance for uncertainty representation +let pose_covariance = ekf.get_current_pose_covariance(); +let twist_covariance = ekf.get_current_twist_covariance(); +``` + +### TF Publishing + +To publish transforms for ROS2 tf, use the `get_transform` method: + +```rust +// Get transform from map to base_link +let transform = ekf.get_transform("base_link"); + +// The transform contains: +// - translation: (x, y, z) position +// - rotation: quaternion orientation + +// Use this data to publish tf2_msgs/TransformStamped +``` + +### Integration with awkernel Reactor API + +The EKF module is designed to be used with awkernel's reactor API. You can create a separate file for pub/sub implementation: + +```rust +// In your reactor implementation file +use ekf_localizer::EKFModule; + +pub struct EKFLocalizerReactor { + ekf: EKFModule, + // Add other fields for pub/sub +} + +impl EKFLocalizerReactor { + pub fn new() -> Self { + let params = EKFParameters::default(); + let ekf = EKFModule::new(params); + + Self { + ekf, + // Initialize other fields + } + } + + pub fn timer_callback(&mut self) { + // Predict step + self.ekf.predict(0.01); + + // Get transform for publishing + let transform = self.ekf.get_transform("base_link"); + + // Publish transform using awkernel reactor API + // self.publish_tf(transform); + } +} +``` + +## Parameters + +Key parameters that can be tuned: + +- `enable_yaw_bias_estimation`: Enable/disable yaw bias estimation +- `extend_state_step`: Number of extended state steps for delay compensation +- `proc_stddev_vx_c`: Process noise standard deviation for velocity +- `proc_stddev_wz_c`: Process noise standard deviation for angular velocity +- `proc_stddev_yaw_c`: Process noise standard deviation for yaw +- `z_filter_proc_dev`: Process noise for z filter +- `roll_filter_proc_dev`: Process noise for roll filter +- `pitch_filter_proc_dev`: Process noise for pitch filter + +## Dependencies + +- `libm`: Mathematical functions for no_std +- `nalgebra`: Linear algebra operations +- `approx`: Approximate equality comparisons for tests + +## Building + +```bash +cd ~/azumi-lab/awkernel_1/ekf_localizer +cargo build --target thumbv7em-none-eabihf # For ARM Cortex-M4 +``` + +## Testing + +```bash +cargo test +``` + +## Notes + +- This implementation focuses on the core EKF calculation and tf generation +- Pub/sub functionality should be implemented separately using awkernel's reactor API +- The original Autoware implementation includes additional features like measurement updates, diagnostics, etc. +- This version is simplified for embedded use but maintains the essential EKF functionality \ No newline at end of file diff --git a/applications/tests/test_autoware/ekf_localizer/src/lib.rs b/applications/tests/test_autoware/ekf_localizer/src/lib.rs new file mode 100644 index 000000000..585ccb28b --- /dev/null +++ b/applications/tests/test_autoware/ekf_localizer/src/lib.rs @@ -0,0 +1,599 @@ +#![no_std] +#![allow(non_snake_case)] + +extern crate alloc; + +use core::f64::consts::PI; +use alloc::{vec, vec::Vec}; +use nalgebra::{Matrix6, Vector6, Vector3}; +use libm::{sin, cos, atan2, asin}; + +/// State indices for EKF +#[derive(Debug, Clone, Copy, PartialEq)] +pub enum StateIndex { + X = 0, + Y = 1, + Yaw = 2, + YawBias = 3, + Vx = 4, + Wz = 5, +} + +/// EKF State vector (6x1) +/// [x, y, yaw, yaw_bias, vx, wz] +pub type StateVector = Vector6; + +/// EKF Covariance matrix (6x6) +pub type StateCovariance = Matrix6; + +/// 3D Point structure +#[derive(Debug, Clone, Copy)] +pub struct Point3D { + pub x: f64, + pub y: f64, + pub z: f64, +} + +/// Quaternion structure +#[derive(Debug, Clone, Copy)] +pub struct Quaternion { + pub x: f64, + pub y: f64, + pub z: f64, + pub w: f64, +} + +/// Pose structure +#[derive(Debug, Clone, Copy)] +pub struct Pose { + pub position: Point3D, + pub orientation: Quaternion, +} + +/// Twist structure +#[derive(Debug, Clone, Copy)] +pub struct Twist { + pub linear: Vector3, + pub angular: Vector3, +} + +/// PoseWithCovariance structure +#[derive(Debug, Clone, Copy)] +pub struct PoseWithCovariance { + pub pose: Pose, + pub covariance: [f64; 36], +} + +/// EKF Parameters +#[derive(Debug, Clone)] +pub struct EKFParameters { + pub enable_yaw_bias_estimation: bool, + pub extend_state_step: usize, + pub proc_stddev_vx_c: f64, + pub proc_stddev_wz_c: f64, + pub proc_stddev_yaw_c: f64, + pub z_filter_proc_dev: f64, + pub roll_filter_proc_dev: f64, + pub pitch_filter_proc_dev: f64, +} + +impl Default for EKFParameters { + fn default() -> Self { + Self { + enable_yaw_bias_estimation: true, + extend_state_step: 50, + proc_stddev_vx_c: 2.0, + proc_stddev_wz_c: 1.0, + proc_stddev_yaw_c: 0.005, + z_filter_proc_dev: 1.0, + roll_filter_proc_dev: 0.1, + pitch_filter_proc_dev: 0.1, + } + } +} + +/// Simple 1D Filter for z, roll, pitch +#[derive(Debug, Clone)] +pub struct Simple1DFilter { + initialized: bool, + x: f64, + var: f64, + proc_var_x_c: f64, +} + +impl Simple1DFilter { + pub fn new() -> Self { + Self { + initialized: false, + x: 0.0, + var: 1e9, + proc_var_x_c: 0.0, + } + } + + pub fn init(&mut self, init_obs: f64, obs_var: f64) { + self.x = init_obs; + self.var = obs_var; + self.initialized = true; + } + + pub fn update(&mut self, obs: f64, obs_var: f64, dt: f64) { + if !self.initialized { + self.init(obs, obs_var); + return; + } + + // Prediction step + let proc_var_x_d = self.proc_var_x_c * dt * dt; + self.var = self.var + proc_var_x_d; + + // Update step + let kalman_gain = self.var / (self.var + obs_var); + self.x = self.x + kalman_gain * (obs - self.x); + self.var = (1.0 - kalman_gain) * self.var; + } + + pub fn set_proc_var(&mut self, proc_var: f64) { + self.proc_var_x_c = proc_var; + } + + pub fn get_x(&self) -> f64 { + self.x + } + + pub fn get_var(&self) -> f64 { + self.var + } +} + +/// Main EKF Module +#[derive(Debug, Clone)] +pub struct EKFModule { + params: EKFParameters, + dim_x: usize, + state: StateVector, + covariance: StateCovariance, + z_filter: Simple1DFilter, + roll_filter: Simple1DFilter, + pitch_filter: Simple1DFilter, + accumulated_delay_times: Vec, + last_angular_velocity: Vector3, + /// MRM (Minimal Risk Maneuver) mode flag + /// When true, only prediction is performed (no measurement updates) + is_mrm_mode: bool, +} + +impl EKFModule { + pub fn new(params: EKFParameters) -> Self { + let dim_x = 6; + let mut state = StateVector::zeros(); + let mut covariance = StateCovariance::identity() * 1e15; + + // Initialize covariance with reasonable values + covariance[(StateIndex::Yaw as usize, StateIndex::Yaw as usize)] = 50.0; + if params.enable_yaw_bias_estimation { + covariance[(StateIndex::YawBias as usize, StateIndex::YawBias as usize)] = 50.0; + } + covariance[(StateIndex::Vx as usize, StateIndex::Vx as usize)] = 1000.0; + covariance[(StateIndex::Wz as usize, StateIndex::Wz as usize)] = 50.0; + + let mut z_filter = Simple1DFilter::new(); + let mut roll_filter = Simple1DFilter::new(); + let mut pitch_filter = Simple1DFilter::new(); + + z_filter.set_proc_var(params.z_filter_proc_dev * params.z_filter_proc_dev); + roll_filter.set_proc_var(params.roll_filter_proc_dev * params.roll_filter_proc_dev); + pitch_filter.set_proc_var(params.pitch_filter_proc_dev * params.pitch_filter_proc_dev); + + let accumulated_delay_times = vec![1e15; params.extend_state_step]; + + Self { + params, + dim_x, + state, + covariance, + z_filter, + roll_filter, + pitch_filter, + accumulated_delay_times, + last_angular_velocity: Vector3::zeros(), + is_mrm_mode: false, + } + } + + /// Initialize EKF with initial pose + pub fn initialize(&mut self, initial_pose: Pose) { + // Set initial state directly from pose + self.state[StateIndex::X as usize] = initial_pose.position.x; + self.state[StateIndex::Y as usize] = initial_pose.position.y; + self.state[StateIndex::Yaw as usize] = self.quaternion_to_yaw(initial_pose.orientation); + self.state[StateIndex::YawBias as usize] = 0.0; + self.state[StateIndex::Vx as usize] = 0.0; + self.state[StateIndex::Wz as usize] = 0.0; + + // Initialize covariance (simplified) + self.covariance = StateCovariance::identity() * 0.01; + if self.params.enable_yaw_bias_estimation { + self.covariance[(StateIndex::YawBias as usize, StateIndex::YawBias as usize)] = 0.0001; + } + + // Initialize filters + self.z_filter.init(initial_pose.position.z, 0.01); + self.roll_filter.init(0.0, 0.01); + self.pitch_filter.init(0.0, 0.01); + } + + /// Predict next state using nonlinear state transition (core prediction logic) + /// x_{k+1} = x_k + vx * cos(yaw + bias) * dt, y_{k+1} = y_k + vx * sin(yaw + bias) * dt, etc. + fn predict_next_state(&self, dt: f64) -> StateVector { + let mut x_next = self.state.clone(); + let x = self.state[StateIndex::X as usize]; + let y = self.state[StateIndex::Y as usize]; + let yaw = self.state[StateIndex::Yaw as usize]; + let yaw_bias = self.state[StateIndex::YawBias as usize]; + let vx = self.state[StateIndex::Vx as usize]; + let wz = self.state[StateIndex::Wz as usize]; + + // Nonlinear state transition + x_next[StateIndex::X as usize] = x + vx * cos(yaw + yaw_bias) * dt; + x_next[StateIndex::Y as usize] = y + vx * sin(yaw + yaw_bias) * dt; + // Normalize yaw to [-π, π] range (Autoware compatible) + let yaw_next = yaw + wz * dt; + x_next[StateIndex::Yaw as usize] = atan2(sin(yaw_next), cos(yaw_next)); + x_next[StateIndex::YawBias as usize] = yaw_bias; // yaw bias doesn't change + x_next[StateIndex::Vx as usize] = vx; // velocity doesn't change in predict + x_next[StateIndex::Wz as usize] = wz; // angular velocity doesn't change in predict + + x_next + } + + /// Create state transition (Jacobian) matrix F + /// F = d(f)/d(x) where f is the nonlinear state transition function + fn create_state_transition_matrix(&self, dt: f64) -> Matrix6 { + let mut F = Matrix6::identity(); + let yaw = self.state[StateIndex::Yaw as usize]; + let yaw_bias = self.state[StateIndex::YawBias as usize]; + let vx = self.state[StateIndex::Vx as usize]; + + // Jacobian of position with respect to yaw and velocity + F[(StateIndex::X as usize, StateIndex::Yaw as usize)] = -vx * sin(yaw + yaw_bias) * dt; + F[(StateIndex::X as usize, StateIndex::YawBias as usize)] = -vx * sin(yaw + yaw_bias) * dt; + F[(StateIndex::X as usize, StateIndex::Vx as usize)] = cos(yaw + yaw_bias) * dt; + + F[(StateIndex::Y as usize, StateIndex::Yaw as usize)] = vx * cos(yaw + yaw_bias) * dt; + F[(StateIndex::Y as usize, StateIndex::YawBias as usize)] = vx * cos(yaw + yaw_bias) * dt; + F[(StateIndex::Y as usize, StateIndex::Vx as usize)] = sin(yaw + yaw_bias) * dt; + + F[(StateIndex::Yaw as usize, StateIndex::Wz as usize)] = dt; + + F + } + + /// Calculate process noise covariance Q + /// Q represents the uncertainty in the motion model + fn process_noise_covariance(&self, dt: f64) -> Matrix6 { + let mut Q = Matrix6::zeros(); + + // Process noise for each state variable + Q[(StateIndex::Vx as usize, StateIndex::Vx as usize)] = + self.params.proc_stddev_vx_c * self.params.proc_stddev_vx_c * dt * dt; + Q[(StateIndex::Wz as usize, StateIndex::Wz as usize)] = + self.params.proc_stddev_wz_c * self.params.proc_stddev_wz_c * dt * dt; + Q[(StateIndex::Yaw as usize, StateIndex::Yaw as usize)] = + self.params.proc_stddev_yaw_c * self.params.proc_stddev_yaw_c * dt * dt; + + // No process noise for position and yaw bias + Q[(StateIndex::X as usize, StateIndex::X as usize)] = 0.0; + Q[(StateIndex::Y as usize, StateIndex::Y as usize)] = 0.0; + Q[(StateIndex::YawBias as usize, StateIndex::YawBias as usize)] = 0.0; + + Q + } + + /// Predict step of EKF (uses predict_next_state, create_state_transition_matrix, and process_noise_covariance) + pub fn predict(&mut self, dt: f64) { + // 1. Predict next state using nonlinear motion model + self.state = self.predict_next_state(dt); + + // 2. Create state transition (Jacobian) matrix + let F = self.create_state_transition_matrix(dt); + + // 3. Calculate process noise covariance + let Q = self.process_noise_covariance(dt); + + // 4. Predict covariance: P = F * P * F^T + Q + self.covariance = F * self.covariance * F.transpose() + Q; + + // 5. Update accumulated delay times + self.accumulate_delay_time(dt); + } + + /// Predict with delay support (Autoware compatible) + /// This version maintains the delay history for measurement updates + pub fn predict_with_delay(&mut self, dt: f64) { + self.predict(dt); + } + + /// Predict-only step (for MRM mode when measurement updates are not available) + /// Only performs prediction without any measurement updates + pub fn predict_only(&mut self, dt: f64) { + self.predict(dt); + } + + /// Get current pose for tf publishing + pub fn get_current_pose(&self, get_biased_yaw: bool) -> Pose { + let z = self.z_filter.get_x(); + let roll = self.roll_filter.get_x(); + let pitch = self.pitch_filter.get_x(); + + let x = self.state[StateIndex::X as usize]; + let y = self.state[StateIndex::Y as usize]; + let biased_yaw = self.state[StateIndex::Yaw as usize]; + let yaw_bias = self.state[StateIndex::YawBias as usize]; + + let yaw = if get_biased_yaw { + biased_yaw + } else { + biased_yaw + yaw_bias + }; + + Pose { + position: Point3D { x, y, z }, + orientation: self.rpy_to_quaternion(roll, pitch, yaw), + } + } + + /// Get current twist + pub fn get_current_twist(&self) -> Twist { + let vx = self.state[StateIndex::Vx as usize]; + let wz = self.state[StateIndex::Wz as usize]; + + Twist { + linear: Vector3::new(vx, 0.0, 0.0), + angular: Vector3::new(0.0, 0.0, wz), + } + } + + /// Get yaw bias + pub fn get_yaw_bias(&self) -> f64 { + self.state[StateIndex::YawBias as usize] + } + + /// Get current pose with covariance for publishing + pub fn get_current_pose_with_covariance(&self) -> PoseWithCovariance { + // Get current pose + let pose = self.get_current_pose(false); + + // Get covariance matrix + let pose_covariance = self.get_current_pose_covariance(); + + // Create and return PoseWithCovariance + PoseWithCovariance { + pose, + covariance: pose_covariance, + } + } + + /// Get pose covariance (simplified 6x6 to 36-element array) + pub fn get_current_pose_covariance(&self) -> [f64; 36] { + let mut cov = [0.0; 36]; + + // Copy 6x6 covariance matrix to 36-element array + for i in 0..6 { + for j in 0..6 { + cov[i * 6 + j] = self.covariance[(i, j)]; + } + } + + // Add z, roll, pitch variances + cov[14] = self.z_filter.get_var(); // Z_Z + cov[21] = self.roll_filter.get_var(); // ROLL_ROLL + cov[28] = self.pitch_filter.get_var(); // PITCH_PITCH + + cov + } + + /// Get twist covariance + pub fn get_current_twist_covariance(&self) -> [f64; 36] { + let mut cov = [0.0; 36]; + + // Simplified: only vx and wz have significant covariance + cov[0] = self.covariance[(StateIndex::Vx as usize, StateIndex::Vx as usize)]; // VX_VX + cov[35] = self.covariance[(StateIndex::Wz as usize, StateIndex::Wz as usize)]; // WZ_WZ + + cov + } + + /// Update velocity measurement (measurement update for Vx and Wz) + /// This is NOT executed during MRM mode (dead reckoning only) + pub fn update_velocity(&mut self, vx_measurement: f64, wz_measurement: f64) { + // Skip measurement update during MRM mode + if self.is_mrm_mode { + return; + } + + // Simple measurement update using Kalman gain + // This assumes direct observation of velocity states + + // Measurement variance (assumed) + let vx_obs_var = 1.0; + let wz_obs_var = 0.1; + + // Update Vx + let vx_var = self.covariance[(StateIndex::Vx as usize, StateIndex::Vx as usize)]; + let vx_gain = vx_var / (vx_var + vx_obs_var); + self.state[StateIndex::Vx as usize] = + self.state[StateIndex::Vx as usize] + + vx_gain * (vx_measurement - self.state[StateIndex::Vx as usize]); + self.covariance[(StateIndex::Vx as usize, StateIndex::Vx as usize)] = + (1.0 - vx_gain) * vx_var; + + // Update Wz + let wz_var = self.covariance[(StateIndex::Wz as usize, StateIndex::Wz as usize)]; + let wz_gain = wz_var / (wz_var + wz_obs_var); + self.state[StateIndex::Wz as usize] = + self.state[StateIndex::Wz as usize] + + wz_gain * (wz_measurement - self.state[StateIndex::Wz as usize]); + self.covariance[(StateIndex::Wz as usize, StateIndex::Wz as usize)] = + (1.0 - wz_gain) * wz_var; + } + + /// Set MRM (Minimal Risk Maneuver) mode + /// When MRM mode is active, only prediction is performed (no measurement updates) + pub fn set_mrm_mode(&mut self, is_mrm: bool) { + self.is_mrm_mode = is_mrm; + } + + /// Get current MRM mode status + pub fn is_mrm(&self) -> bool { + self.is_mrm_mode + } + + /// Accumulate delay time + pub fn accumulate_delay_time(&mut self, dt: f64) { + let len = self.accumulated_delay_times.len(); + if len == 0 { + return; + } + + let last_time = self.accumulated_delay_times[len - 1]; + let new_time = last_time + dt; + + // Shift and add new time + for i in 0..len - 1 { + self.accumulated_delay_times[i] = self.accumulated_delay_times[i + 1]; + } + self.accumulated_delay_times[len - 1] = new_time; + } + + /// Find closest delay time index + pub fn find_closest_delay_time_index(&self, target_value: f64) -> usize { + let len = self.accumulated_delay_times.len(); + if len == 0 { + return 0; + } + + if target_value > self.accumulated_delay_times[len - 1] { + return len; + } + + // Simple linear search for closest value + let mut closest_index = 0; + let mut min_diff = f64::MAX; + + for i in 0..len { + let time = self.accumulated_delay_times[i]; + let diff = (target_value - time).abs(); + if diff < min_diff { + min_diff = diff; + closest_index = i; + } + } + + closest_index + } + + // Utility functions for quaternion and euler angle conversions + fn quaternion_to_yaw(&self, q: Quaternion) -> f64 { + atan2(2.0 * (q.w * q.z + q.x * q.y), 1.0 - 2.0 * (q.y * q.y + q.z * q.z)) + } + + fn rpy_to_quaternion(&self, roll: f64, pitch: f64, yaw: f64) -> Quaternion { + let cy = cos(yaw * 0.5); + let sy = sin(yaw * 0.5); + let cp = cos(pitch * 0.5); + let sp = sin(pitch * 0.5); + let cr = cos(roll * 0.5); + let sr = sin(roll * 0.5); + + Quaternion { + w: cr * cp * cy + sr * sp * sy, + x: sr * cp * cy - cr * sp * sy, + y: cr * sp * cy + sr * cp * sy, + z: cr * cp * sy - sr * sp * cy, + } + } + + fn quaternion_to_rpy(&self, q: Quaternion) -> (f64, f64, f64) { + // Roll (x-axis rotation) + let sinr_cosp = 2.0 * (q.w * q.x + q.y * q.z); + let cosr_cosp = 1.0 - 2.0 * (q.x * q.x + q.y * q.y); + let roll = atan2(sinr_cosp, cosr_cosp); + + // Pitch (y-axis rotation) + let sinp = 2.0 * (q.w * q.y - q.z * q.x); + let pitch = if sinp.abs() >= 1.0 { + PI / 2.0 * sinp.signum() + } else { + asin(sinp) + }; + + // Yaw (z-axis rotation) + let siny_cosp = 2.0 * (q.w * q.z + q.x * q.y); + let cosy_cosp = 1.0 - 2.0 * (q.y * q.y + q.z * q.z); + let yaw = atan2(siny_cosp, cosy_cosp); + + (roll, pitch, yaw) + } +} + +#[cfg(test)] +mod tests { + use super::*; + + #[test] + fn test_ekf_initialization() { + let params = EKFParameters::default(); + let mut ekf = EKFModule::new(params); + + let initial_pose = Pose { + position: Point3D { x: 1.0, y: 2.0, z: 0.0 }, + orientation: Quaternion { x: 0.0, y: 0.0, z: 0.0, w: 1.0 }, + }; + + ekf.initialize(initial_pose); + + let pose = ekf.get_current_pose(false); + assert!((pose.position.x - 1.0).abs() < 1e-6); + assert!((pose.position.y - 2.0).abs() < 1e-6); + } + + #[test] + fn test_quaternion_conversions() { + let params = EKFParameters::default(); + let ekf = EKFModule::new(params); + + let roll = 0.1; + let pitch = 0.2; + let yaw = 0.3; + + let q = ekf.rpy_to_quaternion(roll, pitch, yaw); + let (r, p, y) = ekf.quaternion_to_rpy(q); + + assert!((roll - r).abs() < 1e-6); + assert!((pitch - p).abs() < 1e-6); + assert!((yaw - y).abs() < 1e-6); + } + + #[test] + fn test_pose_with_covariance_generation() { + let params = EKFParameters::default(); + let mut ekf = EKFModule::new(params); + + let initial_pose = Pose { + position: Point3D { x: 1.0, y: 2.0, z: 0.0 }, + orientation: Quaternion { x: 0.0, y: 0.0, z: 0.0, w: 1.0 }, + }; + + ekf.initialize(initial_pose); + + let pose_with_cov = ekf.get_current_pose_with_covariance(); + + // Check pose + assert!((pose_with_cov.pose.position.x - 1.0).abs() < 1e-6); + assert!((pose_with_cov.pose.position.y - 2.0).abs() < 1e-6); + + // Check covariance array + assert_eq!(pose_with_cov.covariance.len(), 36); + } +} \ No newline at end of file diff --git a/applications/tests/test_autoware/gyro_odometer/Cargo.toml b/applications/tests/test_autoware/gyro_odometer/Cargo.toml new file mode 100644 index 000000000..b7890f557 --- /dev/null +++ b/applications/tests/test_autoware/gyro_odometer/Cargo.toml @@ -0,0 +1,12 @@ +[package] +name = "gyro_odometer" +version = "0.1.0" +edition = "2021" + +[dependencies] +log = "0.4" +awkernel_async_lib = { path = "../../../../awkernel_async_lib", default-features = false } +awkernel_lib = { path = "../../../../awkernel_lib", default-features = false } +imu_driver = { path = "../imu_driver", default-features = false } +imu_corrector = { path = "../imu_corrector", default-features = false } +vehicle_velocity_converter = { path = "../vehicle_velocity_converter", default-features = false} \ No newline at end of file diff --git a/applications/tests/test_autoware/gyro_odometer/src/lib.rs b/applications/tests/test_autoware/gyro_odometer/src/lib.rs new file mode 100644 index 000000000..8851bda3c --- /dev/null +++ b/applications/tests/test_autoware/gyro_odometer/src/lib.rs @@ -0,0 +1,468 @@ +#![no_std] +extern crate alloc; + +use alloc::{borrow::Cow, collections::VecDeque, string::String, vec::Vec}; +use core::time::Duration; +// Global instance and lazy initialization support +use core::sync::atomic::{AtomicPtr, Ordering as AtomicOrdering}; +use core::ptr::null_mut; + +// Re-export common types for consistency with other libraries +pub use imu_driver::{Header, Vector3, Quaternion, ImuMsg}; +pub use vehicle_velocity_converter::{Odometry, TwistWithCovarianceStamped, TwistWithCovariance, Twist}; +pub use imu_corrector::{ImuWithCovariance, Transform, transform_covariance}; + + +static GYRO_ODOMETER_INSTANCE: AtomicPtr = AtomicPtr::new(null_mut()); + +// Constants for covariance indices (matching C++ implementation) +const COV_IDX_X_X: usize = 0; +const COV_IDX_Y_Y: usize = 4; +const COV_IDX_Z_Z: usize = 8; + +// XYZRPY covariance indices (matching C++ implementation) +const COV_IDX_XYZRPY_X_X: usize = 0; +const COV_IDX_XYZRPY_Y_Y: usize = 7; +const COV_IDX_XYZRPY_Z_Z: usize = 14; +const COV_IDX_XYZRPY_ROLL_ROLL: usize = 21; +const COV_IDX_XYZRPY_PITCH_PITCH: usize = 28; +const COV_IDX_XYZRPY_YAW_YAW: usize = 35; + +// GyroOdometerCore implementation +pub struct GyroOdometerCore { + // Parameters + pub output_frame: String, + pub message_timeout_sec: f64, + + // State + pub vehicle_twist_arrived: bool, + pub imu_arrived: bool, + pub vehicle_twist_queue: VecDeque, + pub gyro_queue: VecDeque, + + // Configuration + pub config: GyroOdometerConfig, +} + +impl GyroOdometerCore { + pub fn new(config: GyroOdometerConfig) -> Result { + let queue_size = config.queue_size; + let output_frame = config.output_frame.clone(); + let message_timeout_sec = config.message_timeout_sec; + + Ok(Self { + output_frame, + message_timeout_sec, + vehicle_twist_arrived: false, + imu_arrived: false, + vehicle_twist_queue: VecDeque::with_capacity(queue_size), + gyro_queue: VecDeque::with_capacity(queue_size), + config, + }) + } + + + + /// Main processing function (matching C++ concat_gyro_and_odometer) + /// + /// # Arguments + /// * `current_time` - Current system time in nanoseconds (matching C++ this->now()) + pub fn concat_gyro_and_odometer(&mut self, current_time: u64) -> Result> { + // Check if first messages have arrived (matching C++ implementation) + if !self.vehicle_twist_arrived { + self.vehicle_twist_queue.clear(); + self.gyro_queue.clear(); + return Ok(None); + } + if !self.imu_arrived { + self.vehicle_twist_queue.clear(); + self.gyro_queue.clear(); + return Ok(None); + } + + // Check timeout (matching C++ implementation) + // C++: vehicle_twist_dt = std::abs((this->now() - latest_vehicle_twist_ros_time_).seconds()) + if !self.vehicle_twist_queue.is_empty() && !self.gyro_queue.is_empty() { + let latest_vehicle_twist_stamp = self.vehicle_twist_queue.back().unwrap().header.timestamp; + let latest_imu_stamp = self.gyro_queue.back().unwrap().header.timestamp; + + // Check vehicle twist timeout (matching C++ vehicle_twist_dt > message_timeout_sec_) + if Self::check_timeout(current_time, latest_vehicle_twist_stamp, self.message_timeout_sec) { + self.vehicle_twist_queue.clear(); + self.gyro_queue.clear(); + return Err(GyroOdometerError::TimeoutError( + String::from("Vehicle twist message timeout") + )); + } + + // Check IMU timeout (matching C++ imu_dt > message_timeout_sec_) + if Self::check_timeout(current_time, latest_imu_stamp, self.message_timeout_sec) { + self.vehicle_twist_queue.clear(); + self.gyro_queue.clear(); + return Err(GyroOdometerError::TimeoutError( + String::from("IMU message timeout") + )); + } + } + + // Check queue size (matching C++ implementation) + if self.vehicle_twist_queue.is_empty() || self.gyro_queue.is_empty() { + return Ok(None); + } + + // Get transformation (matching C++ implementation) + let tf = self.get_transform( + &self.gyro_queue.front().unwrap().header.frame_id, + &self.output_frame, + )?; + + // Transform gyro frame (matching C++ implementation) + for gyro in &mut self.gyro_queue { + let transformed_angular_velocity = tf.apply_to_vector(gyro.angular_velocity.clone()); + // Note: In C++ implementation, frame_id is updated to output_frame + // but for now we keep the original frame_id to avoid lifetime issues + gyro.angular_velocity = transformed_angular_velocity; + // Covariance is already calculated and transformed by imu_corrector + } + + // Calculate mean and covariance (matching C++ implementation exactly) + let mut vx_mean = 0.0; + let mut gyro_mean = Vector3::new(0.0, 0.0, 0.0); + let mut vx_covariance_original = 0.0; + let mut gyro_covariance_original = Vector3::new(0.0, 0.0, 0.0); + + // Calculate vehicle twist mean and covariance + for vehicle_twist in &self.vehicle_twist_queue { + vx_mean += vehicle_twist.twist.twist.linear.x; + vx_covariance_original += vehicle_twist.twist.covariance[0 * 6 + 0]; + } + vx_mean /= self.vehicle_twist_queue.len() as f64; + vx_covariance_original /= self.vehicle_twist_queue.len() as f64; + + // Calculate gyro mean and covariance (using pre-calculated covariance from imu_corrector) + for gyro in &self.gyro_queue { + gyro_mean.x += gyro.angular_velocity.x; + gyro_mean.y += gyro.angular_velocity.y; + gyro_mean.z += gyro.angular_velocity.z; + // Use pre-calculated covariance from imu_corrector (already transformed) + gyro_covariance_original.x += gyro.angular_velocity_covariance[COV_IDX_X_X]; + gyro_covariance_original.y += gyro.angular_velocity_covariance[COV_IDX_Y_Y]; + gyro_covariance_original.z += gyro.angular_velocity_covariance[COV_IDX_Z_Z]; + } + gyro_mean.x /= self.gyro_queue.len() as f64; + gyro_mean.y /= self.gyro_queue.len() as f64; + gyro_mean.z /= self.gyro_queue.len() as f64; + gyro_covariance_original.x /= self.gyro_queue.len() as f64; + gyro_covariance_original.y /= self.gyro_queue.len() as f64; + gyro_covariance_original.z /= self.gyro_queue.len() as f64; + + // Create result (matching C++ implementation) + let latest_vehicle_twist_stamp = self.vehicle_twist_queue.back().unwrap().header.timestamp; + let latest_imu_stamp = self.gyro_queue.back().unwrap().header.timestamp; + + let result_timestamp = if latest_vehicle_twist_stamp < latest_imu_stamp { + latest_imu_stamp + } else { + latest_vehicle_twist_stamp + }; + + let mut result = TwistWithCovarianceStamped { + header: Header { + frame_id: self.gyro_queue.front().unwrap().header.frame_id, + timestamp: result_timestamp, + }, + twist: TwistWithCovariance { + twist: Twist { + linear: Vector3::new(vx_mean, 0.0, 0.0), + angular: gyro_mean, + }, + covariance: [0.0; 36], + }, + }; + + // Set covariance (matching C++ implementation exactly) + result.twist.covariance[COV_IDX_XYZRPY_X_X] = + vx_covariance_original / self.vehicle_twist_queue.len() as f64; + result.twist.covariance[COV_IDX_XYZRPY_Y_Y] = 100000.0; + result.twist.covariance[COV_IDX_XYZRPY_Z_Z] = 100000.0; + result.twist.covariance[COV_IDX_XYZRPY_ROLL_ROLL] = + gyro_covariance_original.x / self.gyro_queue.len() as f64; + result.twist.covariance[COV_IDX_XYZRPY_PITCH_PITCH] = + gyro_covariance_original.y / self.gyro_queue.len() as f64; + result.twist.covariance[COV_IDX_XYZRPY_YAW_YAW] = + gyro_covariance_original.z / self.gyro_queue.len() as f64; + + // Clear queues (matching C++ implementation) + self.vehicle_twist_queue.clear(); + self.gyro_queue.clear(); + + Ok(Some(result)) + } + + /// Check timeout (matching C++ implementation) + // Timeout checking function (matching C++ implementation) + pub fn check_timeout(current_timestamp: u64, last_timestamp: u64, timeout_sec: f64) -> bool { + let dt = (current_timestamp as f64 - last_timestamp as f64) / 1_000_000_000.0; // Convert to seconds + dt.abs() > timeout_sec + } + + /// Get transform (to be implemented by the caller) + /// Returns identity transform by default. Override this behavior by providing transform externally. + pub fn get_transform(&self, from_frame: &str, to_frame: &str) -> Result { + // This should be implemented by the caller (e.g., transform listener) + // For now, return identity transform + if from_frame == to_frame || from_frame == "" || to_frame == "" { + Ok(Transform::identity()) + } else { + // In a real implementation, this would query the transform tree + // For awkernel, we assume all frames are aligned (identity transform) + Ok(Transform::identity()) + } + } + + /// Process result and apply vehicle stop logic + pub fn process_result(&self, twist_with_cov_raw: TwistWithCovarianceStamped) -> TwistWithCovarianceStamped { + // 車両が停止している場合の処理 (matching C++ implementation exactly) + if twist_with_cov_raw.twist.twist.angular.z.abs() < 0.01 + && twist_with_cov_raw.twist.twist.linear.x.abs() < 0.01 + { + let mut twist = twist_with_cov_raw; + twist.twist.twist.angular.x = 0.0; + twist.twist.twist.angular.y = 0.0; + twist.twist.twist.angular.z = 0.0; + twist + } else { + twist_with_cov_raw + } + } + + /// Convert vehicle velocity data to twist format + pub fn convert_vehicle_velocity_to_twist(&self, odometry: &Odometry, timestamp: u64) -> TwistWithCovarianceStamped { + TwistWithCovarianceStamped { + header: Header { + frame_id: "base_link", + timestamp, + }, + twist: TwistWithCovariance { + twist: Twist { + linear: Vector3::new(odometry.velocity, 0.0, 0.0), + angular: Vector3::new(0.0, 0.0, 0.0), + }, + covariance: [0.0; 36], + }, + } + } + + /// Add vehicle twist to queue (matching test_autoware usage pattern) + pub fn add_vehicle_twist(&mut self, twist: TwistWithCovarianceStamped) { + self.vehicle_twist_arrived = true; + self.vehicle_twist_queue.push_back(twist); + } + + /// Add IMU data to queue (matching test_autoware usage pattern) + pub fn add_imu(&mut self, imu: ImuWithCovariance) { + self.imu_arrived = true; + self.gyro_queue.push_back(imu); + } + + /// Process queues and get result (matching test_autoware process_queues_and_get_result) + pub fn process_and_get_result(&mut self, current_time: u64) -> Option { + match self.concat_gyro_and_odometer(current_time) { + Ok(result) => result, + Err(_) => None, + } + } + + /// Get queue sizes + pub fn get_queue_sizes(&self) -> (usize, usize) { + (self.vehicle_twist_queue.len(), self.gyro_queue.len()) + } + + /// Clear both queues + pub fn clear_queues(&mut self) { + self.vehicle_twist_queue.clear(); + self.gyro_queue.clear(); + } + + /// Reset arrival flags + pub fn reset_arrival_flags(&mut self) { + self.vehicle_twist_arrived = false; + self.imu_arrived = false; + } +} + +#[derive(Debug)] +pub enum GyroOdometerError { + TransformError(String), + TimeoutError(String), + QueueError(String), + ParameterError(String), +} + +impl core::fmt::Display for GyroOdometerError { + fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result { + match self { + GyroOdometerError::TransformError(msg) => write!(f, "Transform error: {}", msg), + GyroOdometerError::TimeoutError(msg) => write!(f, "Timeout error: {}", msg), + GyroOdometerError::QueueError(msg) => write!(f, "Queue error: {}", msg), + GyroOdometerError::ParameterError(msg) => write!(f, "Invalid parameter: {}", msg), + } + } +} + +impl core::error::Error for GyroOdometerError {} + +type Result = core::result::Result; + +#[derive(Debug, Clone)] +pub struct GyroOdometerConfig { + pub output_frame: String, + pub message_timeout_sec: f64, + pub queue_size: usize, + pub transform_timeout: Duration, + pub min_velocity_threshold: f64, + pub covariance_scale: f64, +} + +impl Default for GyroOdometerConfig { + fn default() -> Self { + Self { + output_frame: String::from("base_link"), + message_timeout_sec: 1.0, + queue_size: 100, + transform_timeout: Duration::from_secs(1), + min_velocity_threshold: 0.01, + covariance_scale: 100000.0, + } + } +} + +#[cfg(test)] +mod tests { + use super::*; + + #[test] + fn test_gyro_odometer_core_creation() { + let config = GyroOdometerConfig::default(); + let core = GyroOdometerCore::new(config); + assert!(core.is_ok()); + } + + #[test] + fn test_imu_with_covariance_conversion() { + let imu_msg = ImuMsg { + header: Header { + frame_id: "imu_link", + timestamp: 123456789, + }, + orientation: Quaternion { + x: 0.0, + y: 0.0, + z: 0.0, + w: 1.0, + }, + angular_velocity: Vector3::new(0.1, 0.2, 0.3), + linear_acceleration: Vector3::new(9.8, 0.0, 0.0), + }; + + let imu_with_cov = ImuWithCovariance::from_imu_msg(&imu_msg); + let converted_back = imu_with_cov.to_imu_msg(); + + assert_eq!(imu_msg.header.frame_id, converted_back.header.frame_id); + assert_eq!(imu_msg.header.timestamp, converted_back.header.timestamp); + assert_eq!(imu_msg.angular_velocity.x, converted_back.angular_velocity.x); + assert_eq!(imu_msg.angular_velocity.y, converted_back.angular_velocity.y); + assert_eq!(imu_msg.angular_velocity.z, converted_back.angular_velocity.z); + } + + #[test] + fn test_vehicle_velocity_conversion() { + let config = GyroOdometerConfig::default(); + let core = GyroOdometerCore::new(config).unwrap(); + + let odometry = Odometry { velocity: 15.5 }; + let twist = core.convert_vehicle_velocity_to_twist(&odometry, 123456789); + + assert_eq!(twist.header.frame_id, "base_link"); + assert_eq!(twist.header.timestamp, 123456789); + assert_eq!(twist.twist.twist.linear.x, 15.5); + assert_eq!(twist.twist.twist.linear.y, 0.0); + assert_eq!(twist.twist.twist.linear.z, 0.0); + } + + #[test] + fn test_imu_corrector_integration() { + let config = GyroOdometerConfig::default(); + let mut core = GyroOdometerCore::new(config).unwrap(); + + // Create IMU with covariance from imu_corrector + let imu_with_cov = ImuWithCovariance { + header: Header { + frame_id: "imu_link", + timestamp: 123456789, + }, + orientation: Quaternion { + x: 0.0, + y: 0.0, + z: 0.0, + w: 1.0, + }, + angular_velocity: Vector3::new(0.1, 0.2, 0.3), + angular_velocity_covariance: [0.0009, 0.0, 0.0, 0.0, 0.0009, 0.0, 0.0, 0.0, 0.0009], // 0.03^2 + linear_acceleration: Vector3::new(9.8, 0.0, 0.0), + linear_acceleration_covariance: [100000000.0, 0.0, 0.0, 0.0, 100000000.0, 0.0, 0.0, 0.0, 100000000.0], // 10000^2 + }; + + // Process IMU with covariance + let result = core.process_imu_with_covariance(imu_with_cov); + assert!(result.is_ok()); + } + + #[test] + fn test_transform_covariance_from_imu_corrector() { + // Test that we can use the transform_covariance function from imu_corrector + let input = [1.0, 0.0, 0.0, 0.0, 2.0, 0.0, 0.0, 0.0, 3.0]; + let output = transform_covariance(&input); + assert_eq!(output[COV_IDX_X_X], 3.0); + assert_eq!(output[COV_IDX_Y_Y], 3.0); + assert_eq!(output[COV_IDX_Z_Z], 3.0); + } +} + +/// Get or initialize the global GyroOdometerCore instance +/// This provides lazy initialization with thread-safe access +pub fn get_or_initialize() -> Result<&'static mut GyroOdometerCore> { + let ptr = GYRO_ODOMETER_INSTANCE.load(AtomicOrdering::Acquire); + + if !ptr.is_null() { + return Ok(unsafe { &mut *ptr }); + } + + // Not initialized, try to initialize + let config = GyroOdometerConfig::default(); + let core = GyroOdometerCore::new(config)?; + + // Allocate on heap and store pointer + let boxed_core = alloc::boxed::Box::new(core); + let new_ptr = alloc::boxed::Box::into_raw(boxed_core); + + // Try to store the pointer atomically + match GYRO_ODOMETER_INSTANCE.compare_exchange( + null_mut(), + new_ptr, + AtomicOrdering::Acquire, + AtomicOrdering::Relaxed, + ) { + Ok(_) => { + // We successfully initialized + Ok(unsafe { &mut *new_ptr }) + } + Err(existing_ptr) => { + // Another thread already initialized it, clean up our allocation + unsafe { + let _ = alloc::boxed::Box::from_raw(new_ptr); + } + Ok(unsafe { &mut *existing_ptr }) + } + } +} \ No newline at end of file diff --git a/applications/tests/test_autoware/imu_corrector/Cargo.toml b/applications/tests/test_autoware/imu_corrector/Cargo.toml new file mode 100644 index 000000000..30b5ce849 --- /dev/null +++ b/applications/tests/test_autoware/imu_corrector/Cargo.toml @@ -0,0 +1,11 @@ +[package] +name = "imu_corrector" +version = "0.1.0" +edition = "2021" + +[dependencies] +log = "0.4" +nalgebra = { version = "0.32", default-features = false, features = ["libm"] } +awkernel_async_lib = { path = "../../../../awkernel_async_lib", default-features = false } +awkernel_lib = { path = "../../../../awkernel_lib", default-features = false } +imu_driver = { path = "../imu_driver", default-features = false } \ No newline at end of file diff --git a/applications/tests/test_autoware/imu_corrector/src/lib.rs b/applications/tests/test_autoware/imu_corrector/src/lib.rs new file mode 100644 index 000000000..3abe671ee --- /dev/null +++ b/applications/tests/test_autoware/imu_corrector/src/lib.rs @@ -0,0 +1,605 @@ +#![no_std] +extern crate alloc; + +use nalgebra::{Matrix3, UnitQuaternion, Vector3 as NVector3, Quaternion as NQuaternion}; +use imu_driver::{ImuMsg, Vector3, Quaternion, Header}; +use alloc::{format, string::String}; + +// Transform structure (simplified TF representation) +#[derive(Clone, Debug)] +pub struct Transform { + pub translation: Vector3, + pub rotation: Quaternion, +} + +impl Transform { + pub fn identity() -> Self { + Self { + translation: imu_driver::Vector3::new(5.22444, 0.07615, 2.72762), // use aip_x2_gen2_description. + rotation: imu_driver::Quaternion { + x: 1.0, + y: 0.0, + z: 0.0, + w: 0.0, + }, + } + } + + /// Convert imu_driver Vector3 to nalgebra Vector3 + fn to_nalgebra_vector3(&self, vec: &Vector3) -> NVector3 { + NVector3::new(vec.x, vec.y, vec.z) + } + + /// Convert nalgebra Vector3 to imu_driver Vector3 + fn to_imu_vector3(&self, vec: &NVector3) -> Vector3 { + Vector3::new(vec.x, vec.y, vec.z) + } + + /// Convert imu_driver Quaternion to nalgebra UnitQuaternion + fn to_nalgebra_quaternion(&self, quat: &Quaternion) -> UnitQuaternion { + // Create nalgebra Quaternion first, then normalize to UnitQuaternion + let n_quat = NQuaternion::new(quat.w, quat.x, quat.y, quat.z); + UnitQuaternion::from_quaternion(n_quat) + } + + pub fn apply_to_vector(&self, vec: Vector3) -> Vector3 { + let nalgebra_vec = self.to_nalgebra_vector3(&vec); + let nalgebra_quat = self.to_nalgebra_quaternion(&self.rotation); + let nalgebra_trans = self.to_nalgebra_vector3(&self.translation); + let rotated = nalgebra_quat * nalgebra_vec; + let result = rotated + nalgebra_trans; + self.to_imu_vector3(&result) + } +} + +// Dynamic TF listener interface (simplified version) +pub trait TransformListener { + fn get_latest_transform(&self, from_frame: &str, to_frame: &str) -> Option; + fn get_transform_at_time(&self, from_frame: &str, to_frame: &str, timestamp: u64) -> Option; +} + +// Mock TF listener for testing (can be replaced with actual ROS2 TF implementation) +pub struct MockTransformListener { + transforms: alloc::collections::BTreeMap, +} + +impl MockTransformListener { + pub fn new() -> Self { + Self { + transforms: alloc::collections::BTreeMap::new(), + } + } + + pub fn add_transform(&mut self, from_frame: &str, to_frame: &str, transform: Transform) { + let key = format!("{}_to_{}", from_frame, to_frame); + self.transforms.insert(key, transform); + } +} + +impl TransformListener for MockTransformListener { + fn get_latest_transform(&self, from_frame: &str, to_frame: &str) -> Option { + let key = format!("{}_to_{}", from_frame, to_frame); + self.transforms.get(&key).cloned() + } + + fn get_transform_at_time(&self, from_frame: &str, to_frame: &str, _timestamp: u64) -> Option { + // For mock implementation, ignore timestamp and return latest + self.get_latest_transform(from_frame, to_frame) + } +} + +// Enhanced IMU structure with covariance information +#[derive(Clone, Debug)] +pub struct ImuWithCovariance { + pub header: Header, + pub orientation: Quaternion, + pub angular_velocity: Vector3, + pub angular_velocity_covariance: [f64; 9], + pub linear_acceleration: Vector3, + pub linear_acceleration_covariance: [f64; 9], +} + +impl ImuWithCovariance { + pub fn from_imu_msg(imu_msg: &ImuMsg) -> Self { + Self { + header: imu_msg.header.clone(), + orientation: imu_msg.orientation.clone(), + angular_velocity: imu_msg.angular_velocity.clone(), + angular_velocity_covariance: [0.0; 9], + linear_acceleration: imu_msg.linear_acceleration.clone(), + linear_acceleration_covariance: [0.0; 9], + } + } + + pub fn to_imu_msg(&self) -> ImuMsg { + ImuMsg { + header: self.header.clone(), + orientation: self.orientation.clone(), + angular_velocity: self.angular_velocity.clone(), + linear_acceleration: self.linear_acceleration.clone(), + } + } +} + +// Configuration structure +pub struct ImuCorrectorConfig { + pub angular_velocity_offset_x: f64, + pub angular_velocity_offset_y: f64, + pub angular_velocity_offset_z: f64, + pub angular_velocity_stddev_xx: f64, + pub angular_velocity_stddev_yy: f64, + pub angular_velocity_stddev_zz: f64, + pub acceleration_stddev: f64, + pub output_frame: &'static str, +} + +impl Default for ImuCorrectorConfig { + //sensing/autoware_imu_corrector/config/imu_corrector.param.yaml + fn default() -> Self { + Self { + angular_velocity_offset_x: 0.0, + angular_velocity_offset_y: 0.0, + angular_velocity_offset_z: 0.0, + angular_velocity_stddev_xx: 0.03, + angular_velocity_stddev_yy: 0.03, + angular_velocity_stddev_zz: 0.03, + acceleration_stddev: 10000.0, + output_frame: "base_link", + } + } +} + +// IMU corrector implementation +pub struct ImuCorrector { + config: ImuCorrectorConfig, + transform_listener: T, +} + +impl ImuCorrector { + pub fn new() -> Self { + Self { + config: ImuCorrectorConfig::default(), + transform_listener: MockTransformListener::new(), + } + } + + pub fn with_transform_listener(transform_listener: MockTransformListener) -> Self { + Self { + config: ImuCorrectorConfig::default(), + transform_listener, + } + } +} + +impl ImuCorrector { + pub fn set_config(&mut self, config: ImuCorrectorConfig) { + self.config = config; + } + + /// Convert imu_driver Vector3 to nalgebra Vector3 + fn to_nalgebra_vector3(&self, vec: &Vector3) -> NVector3 { + NVector3::new(vec.x, vec.y, vec.z) + } + + /// Convert nalgebra Vector3 to imu_driver Vector3 + fn to_imu_vector3(&self, vec: &NVector3) -> Vector3 { + Vector3::new(vec.x, vec.y, vec.z) + } + + /// Convert imu_driver Quaternion to nalgebra UnitQuaternion + fn to_nalgebra_quaternion(&self, quat: &Quaternion) -> UnitQuaternion { + // Create nalgebra Quaternion first, then normalize to UnitQuaternion + let n_quat = NQuaternion::new(quat.w, quat.x, quat.y, quat.z); + UnitQuaternion::from_quaternion(n_quat) + } + + /// Transform vector3 using transform (simplified version) + fn transform_vector3(&self, vec: &Vector3, transform: &Transform) -> Vector3 { + // Convert to nalgebra types for transformation + let nalgebra_vec = self.to_nalgebra_vector3(vec); + let nalgebra_quat = self.to_nalgebra_quaternion(&transform.rotation); + let nalgebra_trans = self.to_nalgebra_vector3(&transform.translation); + + // Apply rotation and translation + let rotated = nalgebra_quat * nalgebra_vec; + let result = rotated + nalgebra_trans; + + // Convert back to imu_driver Vector3 + self.to_imu_vector3(&result) + } + + /// Transform covariance matrix (matches C++ transform_covariance function) + /// Takes the maximum covariance value and applies it to diagonal elements + fn transform_covariance(&self, cov: &[f64; 9]) -> [f64; 9] { + // Find maximum covariance value from diagonal elements (xx, yy, zz) + let max_cov = cov[0].max(cov[4]).max(cov[8]); // X_X, Y_Y, Z_Z indices + + // Create new covariance matrix with max_cov on diagonal, zeros elsewhere + let mut cov_transformed = [0.0; 9]; + cov_transformed[0] = max_cov; // X_X + cov_transformed[4] = max_cov; // Y_Y + cov_transformed[8] = max_cov; // Z_Z + // Other elements remain 0.0 + + cov_transformed + } + + /// Create default covariance matrix as array + fn create_default_covariance_array(&self) -> [f64; 9] { + [0.0; 9] + } + + /// Convert Matrix3 to array format for compatibility + fn matrix3_to_array(&self, matrix: &Matrix3) -> [f64; 9] { + [ + matrix[(0, 0)], matrix[(0, 1)], matrix[(0, 2)], + matrix[(1, 0)], matrix[(1, 1)], matrix[(1, 2)], + matrix[(2, 0)], matrix[(2, 1)], matrix[(2, 2)], + ] + } + + /// Correct IMU data with covariance (enhanced version for gyro_odometer) + /// This function matches the C++ callback_imu function more faithfully + pub fn correct_imu_with_covariance(&self, imu_msg: &ImuMsg, transform: Option<&Transform>) -> ImuWithCovariance { + // Start with a copy of the input IMU message (matches C++ line 82) + let mut corrected_imu = ImuWithCovariance::from_imu_msg(imu_msg); + + // Apply angular velocity offset correction (matches C++ lines 85-87) + corrected_imu.angular_velocity.x -= self.config.angular_velocity_offset_x; + corrected_imu.angular_velocity.y -= self.config.angular_velocity_offset_y; + corrected_imu.angular_velocity.z -= self.config.angular_velocity_offset_z; + + // Calculate angular velocity covariance (matches C++ lines 89-93) + // Convert to array format: [xx, xy, xz, yx, yy, yz, zx, zy, zz] + corrected_imu.angular_velocity_covariance[0] = + self.config.angular_velocity_stddev_xx * self.config.angular_velocity_stddev_xx; // xx + corrected_imu.angular_velocity_covariance[4] = + self.config.angular_velocity_stddev_yy * self.config.angular_velocity_stddev_yy; // yy + corrected_imu.angular_velocity_covariance[8] = + self.config.angular_velocity_stddev_zz * self.config.angular_velocity_stddev_zz; // zz + + // Calculate acceleration covariance (matches C++ lines 98-103) + let accel_var = self.config.acceleration_stddev * self.config.acceleration_stddev; + corrected_imu.linear_acceleration_covariance[0] = accel_var; // xx + corrected_imu.linear_acceleration_covariance[4] = accel_var; // yy + corrected_imu.linear_acceleration_covariance[8] = accel_var; // zz + + // Apply TF transformation if provided (matches C++ lines 105-125) + if let Some(tf) = transform { + // Transform linear acceleration (matches C++ line 115) + corrected_imu.linear_acceleration = self.transform_vector3(&corrected_imu.linear_acceleration, tf); + // Transform linear acceleration covariance (matches C++ line 116) + corrected_imu.linear_acceleration_covariance = + self.transform_covariance(&corrected_imu.linear_acceleration_covariance); + + // Transform angular velocity (matches C++ line 118) + corrected_imu.angular_velocity = self.transform_vector3(&corrected_imu.angular_velocity, tf); + // Transform angular velocity covariance (matches C++ line 119) + corrected_imu.angular_velocity_covariance = + self.transform_covariance(&corrected_imu.angular_velocity_covariance); + + // Update frame_id (matches C++ line 113) + corrected_imu.header.frame_id = self.config.output_frame; + } + + corrected_imu + } + + /// Correct IMU data (matches C++ implementation more closely) + pub fn correct_imu(&self, imu_msg: &ImuMsg, transform: Option<&Transform>) -> ImuMsg { + let corrected_with_cov = self.correct_imu_with_covariance(imu_msg, transform); + corrected_with_cov.to_imu_msg() + } + + /// Correct IMU data with dynamic TF lookup (matches C++ callback_imu function) + pub fn correct_imu_with_dynamic_tf(&self, imu_msg: &ImuMsg) -> Option { + // Get latest transform dynamically (matches C++ lines 106-107) + let transform = self.transform_listener.get_latest_transform( + &imu_msg.header.frame_id, + self.config.output_frame + )?; + + // Apply correction with the dynamic transform + let corrected_with_cov = self.correct_imu_with_covariance(imu_msg, Some(&transform)); + Some(corrected_with_cov.to_imu_msg()) + } + + /// Correct IMU data with dynamic TF lookup and covariance + pub fn correct_imu_with_dynamic_tf_covariance(&self, imu_msg: &ImuMsg) -> Option { + // Get latest transform dynamically (matches C++ lines 106-107) + let transform = self.transform_listener.get_latest_transform( + &imu_msg.header.frame_id, + self.config.output_frame + )?; + + // Apply correction with the dynamic transform + Some(self.correct_imu_with_covariance(imu_msg, Some(&transform))) + } + + /// Correct IMU data without TF transformation (simplified version) + pub fn correct_imu_simple(&self, imu_msg: &ImuMsg) -> ImuMsg { + let mut corrected_msg = imu_msg.clone(); + + // Apply angular velocity offset correction + corrected_msg.angular_velocity.x -= self.config.angular_velocity_offset_x; + corrected_msg.angular_velocity.y -= self.config.angular_velocity_offset_y; + corrected_msg.angular_velocity.z -= self.config.angular_velocity_offset_z; + + // Update frame_id + corrected_msg.header.frame_id = self.config.output_frame; + + corrected_msg + } + + /// Get covariance configuration for external use + pub fn get_covariance_config(&self) -> (f64, f64, f64, f64) { + ( + self.config.angular_velocity_stddev_xx, + self.config.angular_velocity_stddev_yy, + self.config.angular_velocity_stddev_zz, + self.config.acceleration_stddev, + ) + } +} + +/// Public transform_covariance function that can be called from other libraries +/// Transform covariance matrix (matches C++ transform_covariance function) +/// Takes the maximum covariance value and applies it to diagonal elements +pub fn transform_covariance(cov: &[f64; 9]) -> [f64; 9] { + // Find maximum covariance value from diagonal elements (xx, yy, zz) + let max_cov = cov[0].max(cov[4]).max(cov[8]); // X_X, Y_Y, Z_Z indices + + // Create new covariance matrix with max_cov on diagonal, zeros elsewhere + let mut cov_transformed = [0.0; 9]; + cov_transformed[0] = max_cov; // X_X + cov_transformed[4] = max_cov; // Y_Y + cov_transformed[8] = max_cov; // Z_Z + // Other elements remain 0.0 + + cov_transformed +} + +#[cfg(test)] +mod tests { + use super::*; + + #[test] + fn test_imu_corrector() { + let corrector = ImuCorrector::new(); + let imu_msg = ImuMsg { + header: Header { + frame_id: "imu_link", + timestamp: 0, + }, + orientation: Quaternion { + x: 0.0, + y: 0.0, + z: 0.0, + w: 1.0, + }, + angular_velocity: Vector3::new(0.1, 0.2, 0.3), + linear_acceleration: Vector3::new(9.8, 0.0, 0.0), + }; + + let corrected_msg = corrector.correct_imu_simple(&imu_msg); + assert_eq!(corrected_msg.header.frame_id, "base_link"); + + // Check that offset correction was applied (no offset in default config) + assert_eq!(corrected_msg.angular_velocity.x, 0.1); + assert_eq!(corrected_msg.angular_velocity.y, 0.2); + assert_eq!(corrected_msg.angular_velocity.z, 0.3); + } + + #[test] + fn test_imu_corrector_with_offset() { + let mut config = ImuCorrectorConfig::default(); + config.angular_velocity_offset_x = 0.05; + config.angular_velocity_offset_y = 0.1; + config.angular_velocity_offset_z = 0.15; + + let mut corrector = ImuCorrector::new(); + corrector.set_config(config); + + let imu_msg = ImuMsg { + header: Header { + frame_id: "imu_link", + timestamp: 0, + }, + orientation: Quaternion { + x: 0.0, + y: 0.0, + z: 0.0, + w: 1.0, + }, + angular_velocity: Vector3::new(0.1, 0.2, 0.3), + linear_acceleration: Vector3::new(9.8, 0.0, 0.0), + }; + + let corrected_msg = corrector.correct_imu_simple(&imu_msg); + + // Check that offset correction was applied + assert_eq!(corrected_msg.angular_velocity.x, 0.1 - 0.05); + assert_eq!(corrected_msg.angular_velocity.y, 0.2 - 0.1); + assert_eq!(corrected_msg.angular_velocity.z, 0.3 - 0.15); + } + + #[test] + fn test_imu_corrector_with_covariance() { + let corrector = ImuCorrector::new(); + let imu_msg = ImuMsg { + header: Header { + frame_id: "imu_link", + timestamp: 0, + }, + orientation: Quaternion { + x: 0.0, + y: 0.0, + z: 0.0, + w: 1.0, + }, + angular_velocity: Vector3::new(0.1, 0.2, 0.3), + linear_acceleration: Vector3::new(9.8, 0.0, 0.0), + }; + + let corrected_with_cov = corrector.correct_imu_with_covariance(&imu_msg, None); + + // Check that covariance was calculated correctly + let expected_angular_var = 0.03 * 0.03; // stddev^2 + assert_eq!(corrected_with_cov.angular_velocity_covariance[0], expected_angular_var); // xx + assert_eq!(corrected_with_cov.angular_velocity_covariance[4], expected_angular_var); // yy + assert_eq!(corrected_with_cov.angular_velocity_covariance[8], expected_angular_var); // zz + + let expected_accel_var = 10000.0 * 10000.0; // stddev^2 + assert_eq!(corrected_with_cov.linear_acceleration_covariance[0], expected_accel_var); // xx + assert_eq!(corrected_with_cov.linear_acceleration_covariance[4], expected_accel_var); // yy + assert_eq!(corrected_with_cov.linear_acceleration_covariance[8], expected_accel_var); // zz + } + + #[test] + fn test_transform_covariance() { + let corrector = ImuCorrector::new(); + + // Test covariance transformation (matches C++ transform_covariance function) + let input_cov = [1.0, 0.5, 0.3, 0.5, 2.0, 0.4, 0.3, 0.4, 3.0]; // xx=1, yy=2, zz=3 + let transformed_cov = corrector.transform_covariance(&input_cov); + + // Should take maximum value (3.0) and apply to diagonal + assert_eq!(transformed_cov[0], 3.0); // xx + assert_eq!(transformed_cov[4], 3.0); // yy + assert_eq!(transformed_cov[8], 3.0); // zz + + // Off-diagonal elements should be 0 + assert_eq!(transformed_cov[1], 0.0); // xy + assert_eq!(transformed_cov[2], 0.0); // xz + assert_eq!(transformed_cov[3], 0.0); // yx + assert_eq!(transformed_cov[5], 0.0); // yz + assert_eq!(transformed_cov[6], 0.0); // zx + assert_eq!(transformed_cov[7], 0.0); // zy + } + + #[test] + fn test_public_transform_covariance() { + // Test the public transform_covariance function + let input_cov = [1.0, 0.5, 0.3, 0.5, 2.0, 0.4, 0.3, 0.4, 3.0]; // xx=1, yy=2, zz=3 + let transformed_cov = transform_covariance(&input_cov); + + // Should take maximum value (3.0) and apply to diagonal + assert_eq!(transformed_cov[0], 3.0); // xx + assert_eq!(transformed_cov[4], 3.0); // yy + assert_eq!(transformed_cov[8], 3.0); // zz + + // Off-diagonal elements should be 0 + assert_eq!(transformed_cov[1], 0.0); // xy + assert_eq!(transformed_cov[2], 0.0); // xz + assert_eq!(transformed_cov[3], 0.0); // yx + assert_eq!(transformed_cov[5], 0.0); // yz + assert_eq!(transformed_cov[6], 0.0); // zx + assert_eq!(transformed_cov[7], 0.0); // zy + } + + #[test] + fn test_imu_corrector_with_transform() { + let corrector = ImuCorrector::new(); + let imu_msg = ImuMsg { + header: Header { + frame_id: "imu_link", + timestamp: 0, + }, + orientation: Quaternion { + x: 0.0, + y: 0.0, + z: 0.0, + w: 1.0, + }, + angular_velocity: Vector3::new(0.1, 0.2, 0.3), + linear_acceleration: Vector3::new(9.8, 0.0, 0.0), + }; + + let transform = Transform { + translation: Vector3::new(0.0, 0.0, 0.0), + rotation: Quaternion { + x: 0.0, + y: 0.0, + z: 0.0, + w: 1.0, + }, + }; + + let corrected_with_cov = corrector.correct_imu_with_covariance(&imu_msg, Some(&transform)); + + // Check that frame_id was updated + assert_eq!(corrected_with_cov.header.frame_id, "base_link"); + + // Check that covariance was transformed (should use max value) + let expected_angular_var = 0.03 * 0.03; // stddev^2 + assert_eq!(corrected_with_cov.angular_velocity_covariance[0], expected_angular_var); // xx + assert_eq!(corrected_with_cov.angular_velocity_covariance[4], expected_angular_var); // yy + assert_eq!(corrected_with_cov.angular_velocity_covariance[8], expected_angular_var); // zz + } + + #[test] + fn test_imu_corrector_with_dynamic_tf() { + let mut transform_listener = MockTransformListener::new(); + let transform = Transform { + translation: Vector3::new(1.0, 0.0, 0.0), + rotation: Quaternion { + x: 0.0, + y: 0.0, + z: 0.0, + w: 1.0, + }, + }; + transform_listener.add_transform("imu_link", "base_link", transform); + + let corrector = ImuCorrector::with_transform_listener(transform_listener); + let imu_msg = ImuMsg { + header: Header { + frame_id: "imu_link", + timestamp: 0, + }, + orientation: Quaternion { + x: 0.0, + y: 0.0, + z: 0.0, + w: 1.0, + }, + angular_velocity: Vector3::new(0.1, 0.2, 0.3), + linear_acceleration: Vector3::new(9.8, 0.0, 0.0), + }; + + let corrected_msg = corrector.correct_imu_with_dynamic_tf(&imu_msg); + assert!(corrected_msg.is_some()); + + let corrected_msg = corrected_msg.unwrap(); + // Check that frame_id was updated + assert_eq!(corrected_msg.header.frame_id, "base_link"); + + // Check that translation was applied (linear acceleration should be transformed) + // With translation of (1.0, 0.0, 0.0), the acceleration should be affected + assert_eq!(corrected_msg.linear_acceleration.x, 9.8); // No change for identity rotation + } + + #[test] + fn test_imu_corrector_with_dynamic_tf_no_transform() { + let transform_listener = MockTransformListener::new(); // Empty listener + let corrector = ImuCorrector::with_transform_listener(transform_listener); + let imu_msg = ImuMsg { + header: Header { + frame_id: "imu_link", + timestamp: 0, + }, + orientation: Quaternion { + x: 0.0, + y: 0.0, + z: 0.0, + w: 1.0, + }, + angular_velocity: Vector3::new(0.1, 0.2, 0.3), + linear_acceleration: Vector3::new(9.8, 0.0, 0.0), + }; + + let corrected_msg = corrector.correct_imu_with_dynamic_tf(&imu_msg); + // Should return None when no transform is available + assert!(corrected_msg.is_none()); + } +} diff --git a/applications/tests/test_autoware/imu_driver/Cargo.toml b/applications/tests/test_autoware/imu_driver/Cargo.toml new file mode 100644 index 000000000..f08727aa3 --- /dev/null +++ b/applications/tests/test_autoware/imu_driver/Cargo.toml @@ -0,0 +1,9 @@ +[package] +name = "imu_driver" +version = "0.1.0" +edition = "2021" + +[dependencies] +log = "0.4" +awkernel_async_lib = { path = "../../../../awkernel_async_lib", default-features = false } +awkernel_lib = { path = "../../../../awkernel_lib", default-features = false } \ No newline at end of file diff --git a/applications/tests/test_autoware/imu_driver/src/lib.rs b/applications/tests/test_autoware/imu_driver/src/lib.rs new file mode 100644 index 000000000..9d7f29837 --- /dev/null +++ b/applications/tests/test_autoware/imu_driver/src/lib.rs @@ -0,0 +1,341 @@ +#![no_std] +extern crate alloc; + +use alloc::{vec, vec::Vec, format,string::String}; +//use awkernel_lib::time::Time; +use core::{f64::consts::PI}; + +// IMU message structure +#[derive(Clone, Debug)] +pub struct ImuMsg { + pub header: Header, + pub orientation: Quaternion, + pub angular_velocity: Vector3, + pub linear_acceleration: Vector3, +} + +#[derive(Clone, Debug)] +pub struct Header { + pub frame_id: &'static str, + pub timestamp: u64, +} + +#[derive(Debug, Clone)] +pub struct Quaternion { + pub x: f64, + pub y: f64, + pub z: f64, + pub w: f64, +} + +#[derive(Clone, Debug)] +pub struct Vector3 { + pub x: f64, + pub y: f64, + pub z: f64, +} + +impl Vector3 { + pub fn new(x: f64, y: f64, z: f64) -> Self { + Self { x, y, z } + } +} + +impl Default for ImuMsg { + fn default() -> Self { + Self { + header: Header { + frame_id: "imu", + timestamp: 0, + }, + orientation: Quaternion { + x: 1.0, + y: 0.0, + z: 0.0, + w: 0.0, + }, + angular_velocity: Vector3::new(0.0, 0.0, 0.0), + linear_acceleration: Vector3::new(0.0, 0.0, 0.0), + } + } +} + +/// IMU data parser for Tamagawa IMU +pub struct TamagawaImuParser { + frame_id: &'static str, + dummy_counter: u16, +} + +impl TamagawaImuParser { + pub fn new(frame_id: &'static str) -> Self { + Self { + frame_id, + dummy_counter: 0, + } + } + + /// Parse binary IMU data from Tamagawa sensor + /// + /// # Arguments + /// * `data` - Raw binary data from sensor (expected length 58 bytes) + /// * `timestamp` - Current timestamp in nanoseconds + /// + /// # Returns + /// * `Option` - Parsed IMU message if data is valid, None otherwise + pub fn parse_binary_data(&self, data: &[u8], timestamp: u64) -> Option { + // Check if data is valid BIN format and correct length + if data.len() != 58 || data[5] != b'B' || data[6] != b'I' || data[7] != b'N' || data[8] != b',' { + return None; + } + + let mut imu_msg = ImuMsg::default(); + imu_msg.header.frame_id = self.frame_id; + imu_msg.header.timestamp = timestamp; + + // Parse counter (bytes 11-12) + let _counter = ((data[11] as u16) << 8) | (data[12] as u16); + + // Parse angular velocity (gyroscope) data + // Bytes 15-16: X-axis angular velocity + let raw_data = self.parse_signed_16bit(&data[15..17]); + imu_msg.angular_velocity.x = self.convert_angular_velocity(raw_data); + + // Bytes 17-18: Y-axis angular velocity + let raw_data = self.parse_signed_16bit(&data[17..19]); + imu_msg.angular_velocity.y = self.convert_angular_velocity(raw_data); + + // Bytes 19-20: Z-axis angular velocity + let raw_data = self.parse_signed_16bit(&data[19..21]); + imu_msg.angular_velocity.z = self.convert_angular_velocity(raw_data); + + // Parse linear acceleration data + // Bytes 21-22: X-axis acceleration + let raw_data = self.parse_signed_16bit(&data[21..23]); + imu_msg.linear_acceleration.x = self.convert_acceleration(raw_data); + + // Bytes 23-24: Y-axis acceleration + let raw_data = self.parse_signed_16bit(&data[23..25]); + imu_msg.linear_acceleration.y = self.convert_acceleration(raw_data); + + // Bytes 25-26: Z-axis acceleration + let raw_data = self.parse_signed_16bit(&data[25..27]); + imu_msg.linear_acceleration.z = self.convert_acceleration(raw_data); + + Some(imu_msg) + } + + /// Generate dummy binary data for testing + /// + /// # Arguments + /// * `timestamp` - Current timestamp in nanoseconds + /// * `angular_velocity` - Angular velocity values in rad/s + /// * `linear_acceleration` - Linear acceleration values in m/s² + /// + /// # Returns + /// * `Vec` - 58-byte binary data in Tamagawa format + pub fn generate_dummy_binary_data( + &mut self, + _timestamp: u64, + angular_velocity: Vector3, + linear_acceleration: Vector3, + ) -> Vec { + let mut data = vec![0u8; 58]; + + // Header: $TSC,BIN, + data[0..5].copy_from_slice(b"$TSC,"); + data[5] = b'B'; + data[6] = b'I'; + data[7] = b'N'; + data[8] = b','; + + // Counter (bytes 11-12) + data[11] = (self.dummy_counter >> 8) as u8; + data[12] = (self.dummy_counter & 0xFF) as u8; + self.dummy_counter = self.dummy_counter.wrapping_add(1); + + // Convert angular velocity from rad/s to LSB + let angular_vel_x_lsb = self.convert_angular_velocity_to_lsb(angular_velocity.x); + let angular_vel_y_lsb = self.convert_angular_velocity_to_lsb(angular_velocity.y); + let angular_vel_z_lsb = self.convert_angular_velocity_to_lsb(angular_velocity.z); + + // Convert acceleration from m/s² to LSB + let accel_x_lsb = self.convert_acceleration_to_lsb(linear_acceleration.x); + let accel_y_lsb = self.convert_acceleration_to_lsb(linear_acceleration.y); + let accel_z_lsb = self.convert_acceleration_to_lsb(linear_acceleration.z); + + // Angular velocity data (bytes 15-20) + data[15] = (angular_vel_x_lsb >> 8) as u8; + data[16] = (angular_vel_x_lsb & 0xFF) as u8; + data[17] = (angular_vel_y_lsb >> 8) as u8; + data[18] = (angular_vel_y_lsb & 0xFF) as u8; + data[19] = (angular_vel_z_lsb >> 8) as u8; + data[20] = (angular_vel_z_lsb & 0xFF) as u8; + + // Linear acceleration data (bytes 21-26) + data[21] = (accel_x_lsb >> 8) as u8; + data[22] = (accel_x_lsb & 0xFF) as u8; + data[23] = (accel_y_lsb >> 8) as u8; + data[24] = (accel_y_lsb & 0xFF) as u8; + data[25] = (accel_z_lsb >> 8) as u8; + data[26] = (accel_z_lsb & 0xFF) as u8; + + data + } + + /// Generate sinusoidal dummy data for realistic simulation + /// + /// # Arguments + /// * `timestamp` - Current timestamp in nanoseconds + /// * `time_offset` - Time offset for phase calculation + /// + /// # Returns + /// * `Vec` - 58-byte binary data with sinusoidal motion + /* + pub fn generate_sinusoidal_dummy_data(&mut self, timestamp: u64, time_offset: f64) -> Vec { + // Convert timestamp to seconds for sinusoidal calculation + let time_sec = (timestamp as f64) / 1_000_000_000.0 + time_offset; + + // Generate sinusoidal angular velocity (rotation around Z-axis) + let angular_vel_z = 0.5 * (2.0 * PI * 0.1 * time_sec).sin(); // 0.1 Hz, ±0.5 rad/s + + // Generate sinusoidal acceleration (oscillation in X-axis) + let accel_x = 9.8 + 2.0 * (2.0 * PI * 0.05 * time_sec).sin(); // 0.05 Hz, 9.8±2.0 m/s² + + let angular_velocity = Vector3::new(0.1, 0.2, angular_vel_z); + let linear_acceleration = Vector3::new(accel_x, 0.0, 9.8); + + self.generate_dummy_binary_data(timestamp, angular_velocity, linear_acceleration) + } + */ + + /// Generate static dummy data with fixed values + /// + /// # Arguments + /// * `timestamp` - Current timestamp in nanoseconds + /// + /// # Returns + /// * `Vec` - 58-byte binary data with static values + // Autoware側と統一:加速度は重力加速度のみ + pub fn generate_static_dummy_data(&mut self, timestamp: u64) -> Vec { + let angular_velocity = Vector3::new(0.1, 0.2, 0.01); + let linear_acceleration = Vector3::new(0.0, 0.0, 9.80665); // z方向のみ重力加速度 + + self.generate_dummy_binary_data(timestamp, angular_velocity, linear_acceleration) + } + + /// Convert angular velocity from rad/s to LSB + fn convert_angular_velocity_to_lsb(&self, rad_per_sec: f64) -> i16 { + let deg_per_sec = rad_per_sec * 180.0 / PI; + let lsb = deg_per_sec / (200.0 / (1 << 15) as f64); + lsb as i16 + } + + /// Convert acceleration from m/s² to LSB + fn convert_acceleration_to_lsb(&self, m_per_sec_squared: f64) -> i16 { + let lsb = m_per_sec_squared / (100.0 / (1 << 15) as f64); + lsb as i16 + } + + /// Parse signed 16-bit value from 2 bytes + /// + /// This matches the C++ implementation: + /// raw_data = ((((rbuf[15] << 8) & 0xFFFFFF00) | (rbuf[16] & 0x000000FF))); + fn parse_signed_16bit(&self, data: &[u8]) -> i16 { + if data.len() != 2 { + return 0; + } + // Match C++ implementation: 32-bit integer with masking + let high_byte = (data[0] as i32) << 8; + let low_byte = data[1] as i32; + let result = (high_byte & 0xFFFFFF00u32 as i32) | (low_byte & 0x000000FF); + result as i16 + } + + /// Convert raw angular velocity data to rad/s + /// + /// Raw data is in LSB units with range ±200 deg/s + /// Conversion: raw * (200 / 2^15) * π / 180 + fn convert_angular_velocity(&self, raw_data: i16) -> f64 { + let lsb_to_deg_per_sec = 200.0 / (1 << 15) as f64; + let deg_to_rad = PI / 180.0; + (raw_data as f64) * lsb_to_deg_per_sec * deg_to_rad + } + + /// Convert raw acceleration data to m/s² + /// + /// Raw data is in LSB units with range ±100 m/s² + /// Conversion: raw * (100 / 2^15) + fn convert_acceleration(&self, raw_data: i16) -> f64 { + let lsb_to_m_per_sec_squared = 100.0 / (1 << 15) as f64; + (raw_data as f64) * lsb_to_m_per_sec_squared + } + + /// Generate version request command + pub fn generate_version_request() -> &'static [u8] { + b"$TSC,VER*29\r\n" + } + + /// Generate offset cancel request command + pub fn generate_offset_cancel_request(offset_value: i32) -> String { + format!("$TSC,OFC,{}\r\n", offset_value) + } + + /// Generate heading reset request command + pub fn generate_heading_reset_request() -> &'static [u8] { + b"$TSC,HRST*29\r\n" + } + + /// Generate binary data request command + pub fn generate_binary_request(rate_hz: u32) -> String { + format!("$TSC,BIN,{}\r\n", rate_hz) + } +} + + + +#[cfg(test)] +mod tests { + use super::*; + + #[test] + fn example_usage() { + // Create parser instance + let mut parser = TamagawaImuParser::new("imu_link"); + + // Generate commands + let version_cmd = TamagawaImuParser::generate_version_request(); + let binary_cmd = TamagawaImuParser::generate_binary_request(30); + let offset_cmd = TamagawaImuParser::generate_offset_cancel_request(123); + let heading_cmd = TamagawaImuParser::generate_heading_reset_request(); + + // Example 1: Generate static dummy data + let static_dummy_data = parser.generate_static_dummy_data(123456789); + if let Some(imu_msg) = parser.parse_binary_data(&static_dummy_data, 123456789) { + // Use the parsed IMU message + let _angular_vel = imu_msg.angular_velocity; + let _acceleration = imu_msg.linear_acceleration; + } + + // Example 2: Generate sinusoidal dummy data for realistic simulation + let sinusoidal_dummy_data = parser.generate_sinusoidal_dummy_data(123456789, 0.0); + if let Some(imu_msg) = parser.parse_binary_data(&sinusoidal_dummy_data, 123456789) { + // Use the parsed IMU message with realistic motion + let _angular_vel = imu_msg.angular_velocity; + let _acceleration = imu_msg.linear_acceleration; + } + + // Example 3: Generate custom dummy data + let custom_angular_velocity = Vector3::new(0.5, -0.3, 1.2); + let custom_acceleration = Vector3::new(8.5, 2.1, 10.2); + let custom_dummy_data = parser.generate_dummy_binary_data( + 123456789, + custom_angular_velocity, + custom_acceleration + ); + if let Some(imu_msg) = parser.parse_binary_data(&custom_dummy_data, 123456789) { + // Use the parsed IMU message with custom values + let _angular_vel = imu_msg.angular_velocity; + let _acceleration = imu_msg.linear_acceleration; + } + } +} \ No newline at end of file diff --git a/applications/tests/test_autoware/imu_raw.csv b/applications/tests/test_autoware/imu_raw.csv new file mode 100644 index 000000000..4886b7850 --- /dev/null +++ b/applications/tests/test_autoware/imu_raw.csv @@ -0,0 +1,5709 @@ +timestamp_sec,timestamp_nanosec,orientation_x,orientation_y,orientation_z,orientation_w,angular_velocity_x,angular_velocity_y,angular_velocity_z,linear_acceleration_x,linear_acceleration_y,linear_acceleration_z +1769682011,410121472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682011,462363136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682011,469166592,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682011,509448960,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682011,543781120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682011,570960384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682011,609601792,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682011,659680256,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682011,666435840,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682011,701181184,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682011,759175424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682011,770347264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682011,809539328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682011,865306112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682011,880912896,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682011,910638592,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682011,950943488,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682011,978671360,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,10963968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,52329472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,76876544,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,114380288,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,158851328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,170333952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,209740288,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,264206336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,273925632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,309050368,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,356011264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,376484608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,400628736,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,452687104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,476804608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,511975936,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,555344128,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,573499648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,609228288,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,647077120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,669924608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,709627904,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,747266304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,776354560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,809455616,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,853366016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,877307136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,909498624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,947997696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682012,979754496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,9405696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,43408640,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,67382272,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,109652480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,144094208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,175933440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,213615104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,258479872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,268090368,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,308947200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,363198720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,380390400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,409442304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,446046208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,477171456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,511062016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,548630784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,576634880,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,614119424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,659646208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,669505792,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,709091072,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,754778880,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,777250816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,809955840,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,842801920,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,878489088,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,910355968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,961571328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682013,968428032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,500224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,61579520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,72642816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,110277888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,163835648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,175374336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,209796608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,244276224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,276851200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,310392320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,353491456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,376546560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,409061120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,459643392,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,469405184,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,509146624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,544073216,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,578467072,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,610523392,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,645220864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,676251648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,709531392,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,743406848,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,776807168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,812845824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,846098432,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,878514688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,911022848,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,958437376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682014,969724672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,10676480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,43781632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,78323712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,110242816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,145303040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,179990784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,209876224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,246270208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,278840064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,314503168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,349533440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,375959040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,409660928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,454444800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,476497920,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,509792512,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,543955456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,580643584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,612306944,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,645478656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,676257536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,709653760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,755419648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,776323072,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,809076736,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,862409472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,869460224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,911052544,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,945050624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682015,980811008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,9593344,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,45559552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,76001536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,110477568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,144845568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,177478400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,209633024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,266411008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,274794496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,309711872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,343024128,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,377344512,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,411144192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,456842496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,476329216,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,510285312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,552322048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,576834560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,609375232,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,644767232,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,665960192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,713820416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,747127040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,828725760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,830855168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,864070656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,871448064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,911274752,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,944341504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682016,976420864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,9947136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,49340160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,77211904,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,109819136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,158978816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,170197760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,209368064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,244061696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,276502016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,310521856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,357883136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,384333824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,410472960,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,446477312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,477434112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,511023872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,549916416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,577069824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,609644800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,662749696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,669412352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,709689088,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,744481024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,776696320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,809918464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,846062848,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,877307904,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,915363328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,947344640,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682017,976938496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682018,9361152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682018,57942016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682018,67345152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682018,110760704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682018,143277824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682018,181226752,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682018,209636864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682018,245412096,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682018,277799680,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682018,314036224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682018,354016512,0.0,0.0,0.0,1.0,0.014358777552843094,-0.03264179825782776,0.00043512278352864087,1.6609306335449219,0.8149923086166382,-4.72646951675415 +1769682018,378463232,0.0,0.0,0.0,1.0,0.01761149987578392,-0.05850871279835701,0.0009570895927026868,0.9481403827667236,0.2100292444229126,-2.714618444442749 +1769682018,410350848,0.0,0.0,0.0,1.0,0.01570582017302513,-0.06417010724544525,0.0012279312359169126,-0.5181403756141663,-0.32497110962867737,-0.9743397831916809 +1769682018,464692480,0.0,0.0,0.0,1.0,0.011602478101849556,-0.053104933351278305,0.0012069185031577945,-1.0990111827850342,0.04187984764575958,0.6243825554847717 +1769682018,473776896,0.0,0.0,0.0,1.0,0.009407504461705685,-0.038554079830646515,0.001043057651259005,-1.2761266231536865,-0.24411405622959137,1.3442267179489136 +1769682018,510287872,0.0,0.0,0.0,1.0,0.0070592123083770275,-0.02376710996031761,0.0007886536186560988,-0.8540163040161133,-0.3414801359176636,1.6605005264282227 +1769682018,549068800,0.0,0.0,0.0,1.0,0.005631800275295973,-0.00807406846433878,0.0004554156621452421,-0.8337791562080383,0.208700031042099,1.6470088958740234 +1769682018,577014528,0.0,0.0,0.0,1.0,0.0043827383778989315,-0.0005656213033944368,0.00021280259534250945,-0.4945983588695526,0.2380276322364807,1.4357680082321167 +1769682018,610034432,0.0,0.0,0.0,1.0,0.0033162739127874374,0.0037964421790093184,1.6558158677071333e-05,-0.49590009450912476,0.2362305372953415,1.1162302494049072 +1769682018,646877440,0.0,0.0,0.0,1.0,0.0025875617284327745,0.005088666453957558,-0.00019407004583626986,-0.25737112760543823,-0.1560479700565338,0.668285071849823 +1769682018,676283648,0.0,0.0,0.0,1.0,0.002293581608682871,0.004002165514975786,-0.00027116795536130667,-0.17841367423534393,-0.2878539264202118,0.35529476404190063 +1769682018,715464960,0.0,0.0,0.0,1.0,0.0014286770019680262,0.002398464363068342,-0.000362870137905702,-0.24001342058181763,0.39022552967071533,0.09845121204853058 +1769682018,751439616,0.0,0.0,0.0,1.0,0.0009561797487549484,0.0005182125605642796,-0.00037578027695417404,-0.4204089641571045,0.09861285239458084,-0.13754582405090332 +1769682018,776400384,0.0,0.0,0.0,1.0,-0.00019652271294035017,-0.00030091029475443065,-0.00038026596303097904,-0.2604846954345703,-0.16172528266906738,-0.2317706197500229 +1769682018,809322240,0.0,0.0,0.0,1.0,-0.0002173051907448098,-0.0007950104773044586,-0.00035245815524831414,-0.5203346014022827,-0.32220444083213806,-0.2680325210094452 +1769682018,859503872,0.0,0.0,0.0,1.0,-0.0010283852461725473,-0.0011585456086322665,-0.0003098126908298582,-0.680616021156311,-0.06254737079143524,-0.2786766290664673 +1769682018,865981696,0.0,0.0,0.0,1.0,-0.0011799205094575882,-0.0011962095741182566,-0.00028650229796767235,0.2589378356933594,0.1587587296962738,-0.23434194922447205 +1769682018,912800512,0.0,0.0,0.0,1.0,-0.0011685179779306054,-0.0005853036418557167,-0.00021313849720172584,-0.420572429895401,0.0983397364616394,-0.17920704185962677 +1769682018,955111424,0.0,0.0,0.0,1.0,-0.0016090166755020618,0.00030316782067529857,-0.0001169246097560972,-0.5999751091003418,-0.19140098989009857,-0.12074214965105057 +1769682018,983323136,0.0,0.0,0.0,1.0,-0.001579517382197082,0.0021224617958068848,-3.8352965930243954e-05,-0.1606135368347168,0.25903943181037903,-0.10955487191677094 +1769682019,9780480,0.0,0.0,0.0,1.0,-0.0011749914847314358,0.0036997233983129263,4.364276901469566e-05,-0.6797910332679749,-0.06098197400569916,-0.031976960599422455 +1769682019,63262208,0.0,0.0,0.0,1.0,-0.0016347073251381516,0.004802745301276445,0.00011798564810305834,-0.5191839933395386,-0.3199845254421234,0.08460760116577148 +1769682019,73359360,0.0,0.0,0.0,1.0,-0.0013325101463124156,0.001962781185284257,0.00015812087804079056,-0.4998626708984375,0.22979100048542023,0.07519267499446869 +1769682019,100884224,0.0,0.0,0.0,1.0,-0.0020272464025765657,0.0007424092618748546,0.00018082863243762404,-0.07987979054450989,0.13035506010055542,0.08170486241579056 +1769682019,149033728,0.0,0.0,0.0,1.0,-0.0013139211805537343,-0.0012264352990314364,0.0002864305570255965,-0.2595556974411011,-0.15990819036960602,0.05656507983803749 +1769682019,178920704,0.0,0.0,0.0,1.0,-0.0014810527209192514,-0.0016676244558766484,0.0003281341341789812,-0.08002602308988571,0.13004358112812042,0.030467208474874496 +1769682019,209931008,0.0,0.0,0.0,1.0,-0.0016177979996427894,-0.0014092583442106843,0.0003889485960826278,-0.5994576215744019,-0.19039477407932281,0.03753240033984184 +1769682019,248896000,0.0,0.0,0.0,1.0,-0.0013614653144031763,-0.0010151714086532593,0.0004848823300562799,-0.5995762348175049,-0.1906040906906128,0.0005959551781415939 +1769682019,279114752,0.0,0.0,0.0,1.0,-0.0014579102862626314,-0.0007408582023344934,0.0005284020444378257,0.25972381234169006,0.16021472215652466,-0.002934660529717803 +1769682019,309730048,0.0,0.0,0.0,1.0,-0.0010531352600082755,-0.00029737415025010705,0.0005952980718575418,-0.5996666550636292,-0.19074003398418427,-0.026813479140400887 +1769682019,342887936,0.0,0.0,0.0,1.0,-0.0012509834486991167,0.00027850648621097207,0.000684003927744925,-0.16030353307724,0.25957852602005005,-0.02838844247162342 +1769682019,377901568,0.0,0.0,0.0,1.0,-0.0008489490137435496,0.0005182474851608276,0.0007465402013622224,-0.8593383431434631,-0.350779265165329,-0.00127364881336689 +1769682019,411501568,0.0,0.0,0.0,1.0,-0.001166374422609806,0.0008277237066067755,0.0008067653980106115,-0.41995808482170105,0.09952292591333389,-0.002821642439812422 +1769682019,447005952,0.0,0.0,0.0,1.0,-0.001723594730719924,0.001105783274397254,0.0008707031956873834,-0.33987852931022644,-0.030375953763723373,-0.009511372074484825 +1769682019,481549568,0.0,0.0,0.0,1.0,-0.0009703924297355115,0.0012781331315636635,0.000955854426138103,-0.25972533226013184,-0.16013191640377045,0.011211629956960678 +1769682019,509959424,0.0,0.0,0.0,1.0,-0.001493085059337318,0.0014055684441700578,0.001013646018691361,-0.1602206528186798,0.25968489050865173,-0.014050970785319805 +1769682019,555195392,0.0,0.0,0.0,1.0,-0.0017278699669986963,0.0013918228214606643,0.0010778849245980382,-0.16021603345870972,0.2596796751022339,-0.01642657443881035 +1769682019,576477184,0.0,0.0,0.0,1.0,-0.0019736974500119686,0.00144700868986547,0.001145191490650177,-0.599660336971283,-0.19050364196300507,-0.011538006365299225 +1769682019,613140224,0.0,0.0,0.0,1.0,-0.0017546213930472732,0.0013152147876098752,0.0012115506688132882,-0.500006377696991,0.22950899600982666,-0.0009735384956002235 +1769682019,649756160,0.0,0.0,0.0,1.0,-0.0016882875934243202,0.0013868293026462197,0.0012890693033114076,-0.5996822714805603,-0.19046321511268616,-0.014001766219735146 +1769682019,676992000,0.0,0.0,0.0,1.0,-0.0016811522655189037,0.001570007181726396,0.001355680637061596,-0.5996759533882141,-0.1904139518737793,-0.009269829839468002 +1769682019,709649920,0.0,0.0,0.0,1.0,-0.0018769016023725271,0.001583663048222661,0.0014017962384968996,-0.08007518947124481,0.1298673450946808,-0.006407645530998707 +1769682019,761499136,0.0,0.0,0.0,1.0,-0.0017820842331275344,0.0014813162852078676,0.0014707462396472692,-0.5996589064598083,-0.19028717279434204,0.0037515098229050636 +1769682019,770610688,0.0,0.0,0.0,1.0,-0.002011739183217287,0.0012669740244746208,0.0015132620465010405,-0.6797248125076294,-0.06038839370012283,-0.00148025993257761 +1769682019,810937856,0.0,0.0,0.0,1.0,-0.0021897268015891314,0.0013511055149137974,0.001579607604071498,0.17976222932338715,0.28994879126548767,-0.009048134088516235 +1769682019,844546560,0.0,0.0,0.0,1.0,-0.0018184375949203968,0.0014753910945728421,0.001645161071792245,-0.6600278615951538,0.4894373416900635,-0.017398148775100708 +1769682019,879716864,0.0,0.0,0.0,1.0,-0.0018518993165344,0.0015361205441877246,0.0016844415804371238,-0.5799512267112732,0.3596039414405823,-0.006245370954275131 +1769682019,912297216,0.0,0.0,0.0,1.0,-0.0018627013778313994,0.0015311045572161674,0.0017548114992678165,-0.4998740255832672,0.22979000210762024,0.010857288725674152 +1769682019,949766912,0.0,0.0,0.0,1.0,-0.002138451673090458,0.001794222742319107,0.0018183771753683686,-0.5197455883026123,-0.3200805187225342,-0.009205376729369164 +1769682019,977427456,0.0,0.0,0.0,1.0,-0.0022545193787664175,0.0017781752394512296,0.001856209826655686,-0.16003812849521637,0.2597963213920593,-0.016316290944814682 +1769682020,12406272,0.0,0.0,0.0,1.0,-0.002169262384995818,0.001936362124979496,0.0018991457764059305,-0.4998660385608673,0.22981469333171844,-0.003484392538666725 +1769682020,59058432,0.0,0.0,0.0,1.0,-0.0022767132613807917,0.0019258329411968589,0.001974612008780241,-0.08003057539463043,0.1298495978116989,-0.02185678295791149 +1769682020,72169216,0.0,0.0,0.0,1.0,-0.002365145832300186,0.002034558914601803,0.001989185344427824,-6.13878364674747e-05,-0.00012508318468462676,-0.028609907254576683 +1769682020,112495360,0.0,0.0,0.0,1.0,-0.0022194574121385813,0.0020858701318502426,0.002045518485829234,-0.9396838545799255,-0.21993516385555267,-0.007850328460335732 +1769682020,161177856,0.0,0.0,0.0,1.0,-0.002333069685846567,0.0024040595162659883,0.002103828825056553,-0.33989793062210083,-0.029990151524543762,-0.00874185748398304 +1769682020,177283584,0.0,0.0,0.0,1.0,-0.0024103729519993067,0.0022562718950212,0.002129646949470043,-0.6797599196434021,-0.05985264107584953,0.0027295295149087906 +1769682020,201306112,0.0,0.0,0.0,1.0,-0.0025123769883066416,0.0023225913755595684,0.0021410793997347355,-0.25990375876426697,-0.15980631113052368,0.020203109830617905 +1769682020,267985408,0.0,0.0,0.0,1.0,-0.0027702271472662687,0.002176680602133274,0.0021972130052745342,-0.8598073720932007,-0.3496067523956299,-0.0019029416143894196 +1769682020,275361024,0.0,0.0,0.0,1.0,-0.002624168759211898,0.0022626840509474277,0.00223132804967463,0.33990374207496643,0.029891368001699448,0.008854015730321407 +1769682020,300538624,0.0,0.0,0.0,1.0,-0.0025042265187948942,0.0023084685672074556,0.0022458622697740793,-0.2397301197052002,0.38999268412590027,0.007257262244820595 +1769682020,364577024,0.0,0.0,0.0,1.0,-0.0027509843930602074,0.0023654564283788204,0.00230006268247962,-0.7799532413482666,-0.4793204367160797,0.023193076252937317 +1769682020,374328320,0.0,0.0,0.0,1.0,-0.003068530233576894,0.002365312073379755,0.0023150083143264055,-0.41980087757110596,0.10018596798181534,-0.010483062826097012 +1769682020,409896448,0.0,0.0,0.0,1.0,-0.002722540171816945,0.002335426863282919,0.002332766307517886,-0.7800359725952148,-0.47925835847854614,0.009889258071780205 +1769682020,459754496,0.0,0.0,0.0,1.0,-0.00271616387180984,0.002456498332321644,0.002361229620873928,-0.41980838775634766,0.10018832236528397,-0.030800800770521164 +1769682020,468659200,0.0,0.0,0.0,1.0,-0.002707344712689519,0.0023533832281827927,0.0023761133197695017,-0.23956622183322906,0.39012598991394043,0.019261743873357773 +1769682020,510630144,0.0,0.0,0.0,1.0,-0.0024871539790183306,0.0023674294352531433,0.0024078914429992437,-0.6798281669616699,-0.05940405651926994,-0.01692809909582138 +1769682020,545726976,0.0,0.0,0.0,1.0,-0.0028936341404914856,0.0025722591672092676,0.0024070492945611477,-0.3399069309234619,-0.02964075095951557,0.00043869856745004654 +1769682020,573634048,0.0,0.0,0.0,1.0,-0.0029759646859019995,0.002599380211904645,0.002416030503809452,-9.247669368050992e-06,-2.8858350560767576e-05,-0.009536702185869217 +1769682020,610342144,0.0,0.0,0.0,1.0,-0.003187020542100072,0.002594871912151575,0.0024333344772458076,-0.26009008288383484,-0.15963011980056763,0.003072799649089575 +1769682020,644784896,0.0,0.0,0.0,1.0,-0.0029339324682950974,0.0027098197024315596,0.0024739617947489023,-0.6798273324966431,-0.0591033473610878,0.004255509003996849 +1769682020,678584832,0.0,0.0,0.0,1.0,-0.0029738196171820164,0.0026103442069143057,0.0024855879601091146,-0.520237147808075,-0.3191750645637512,0.004787363111972809 +1769682020,710590464,0.0,0.0,0.0,1.0,-0.003265115199610591,0.002732487628236413,0.002488016849383712,4.266970790922642e-06,1.8579510651761666e-05,0.007152630016207695 +1769682020,757523968,0.0,0.0,0.0,1.0,-0.001192536554299295,0.0028862154576927423,0.0032887887209653854,-0.6798295974731445,-0.058864399790763855,0.03027988225221634 +1769682020,779055616,0.0,0.0,0.0,1.0,3.1192321330308914e-06,0.003574145259335637,0.004201407078653574,-0.4994281828403473,0.23081235587596893,0.029420938342809677 +1769682020,811077888,0.0,0.0,0.0,1.0,0.00021784832642879337,0.004155638627707958,0.004856544081121683,-0.3399200737476349,-0.029293043538928032,0.035926949232816696 +1769682020,859848448,0.0,0.0,0.0,1.0,0.0002815593034029007,0.004719587508589029,0.00546981068328023,0.18051429092884064,0.2895667254924774,0.012374421581625938 +1769682020,873881600,0.0,0.0,0.0,1.0,0.00015066724154166877,0.004924987908452749,0.005703721661120653,-9.922950994223356e-08,3.878487041220069e-05,0.015497169457376003 +1769682020,912237056,0.0,0.0,0.0,1.0,0.0003449393843766302,0.005179139319807291,0.0060071395710110664,-0.07966878265142441,0.13017573952674866,0.013960381038486958 +1769682020,943518464,0.0,0.0,0.0,1.0,-0.00011628677020780742,0.005234840791672468,0.006192019209265709,-0.6799085736274719,-0.05823757126927376,-0.007286674343049526 +1769682020,976794880,0.0,0.0,0.0,1.0,0.0006705350824631751,0.005157118197530508,0.006279081106185913,0.5207087993621826,0.31839150190353394,-0.01839715801179409 +1769682021,12615680,0.0,0.0,0.0,1.0,0.0002828471770044416,0.005256240256130695,0.006345172878354788,-0.15916307270526886,0.2603571116924286,-0.009127151221036911 +1769682021,46971136,0.0,0.0,0.0,1.0,9.191378194373101e-05,0.005171367898583412,0.006324755493551493,-0.6003636121749878,-0.18807362020015717,-0.029877468943595886 +1769682021,76916224,0.0,0.0,0.0,1.0,0.0001792931871023029,0.00495016248896718,0.0063250744715332985,-0.4194920063018799,0.1013675406575203,-0.011443562805652618 +1769682021,110328064,0.0,0.0,0.0,1.0,0.00032038730569183826,0.004554418381303549,0.006290524732321501,-0.33997204899787903,-0.028786655515432358,-0.00868501141667366 +1769682021,162013696,0.0,0.0,0.0,1.0,0.0003008018829859793,0.004518935456871986,0.006215964909642935,-0.41945216059684753,0.10156692564487457,-0.005619330797344446 +1769682021,172635392,0.0,0.0,0.0,1.0,-8.896219515008852e-05,0.004325512330979109,0.00617254339158535,-0.15891531109809875,0.2605539858341217,0.0050462521612644196 +1769682021,211464192,0.0,0.0,0.0,1.0,-0.00022953332518227398,0.004473834298551083,0.006108389236032963,-0.3399839699268341,-0.02857929840683937,-0.010027348063886166 +1769682021,247774208,0.0,0.0,0.0,1.0,0.0001401766057824716,0.004503927193582058,0.006037286948412657,0.2605994939804077,0.1588049978017807,0.009602688252925873 +1769682021,278373376,0.0,0.0,0.0,1.0,-0.0003942037292290479,0.00473205279558897,0.005948987323790789,-0.781957745552063,-0.4761722683906555,0.010421765968203545 +1769682021,310172160,0.0,0.0,0.0,1.0,0.0001690940116532147,0.0045538595877587795,0.005885944236069918,0.18135590851306915,0.28900161385536194,-0.00990759115666151 +1769682021,344241664,0.0,0.0,0.0,1.0,0.00011993679072475061,0.00443072896450758,0.005790318828076124,-0.0793125107884407,0.13035471737384796,-0.0005227377405390143 +1769682021,377205504,0.0,0.0,0.0,1.0,0.0003104891220573336,0.004586861934512854,0.005741224158555269,0.10222768783569336,0.4192434549331665,-0.029457520693540573 +1769682021,411677952,0.0,0.0,0.0,1.0,-1.143282133853063e-05,0.004665837623178959,0.00569411925971508,-0.15846459567546844,0.2606922686100006,-0.028507284820079803 +1769682021,446598400,0.0,0.0,0.0,1.0,0.0002836619096342474,0.0043972693383693695,0.005206753965467215,-0.34011417627334595,-0.02800750359892845,0.026555053889751434 +1769682021,477125888,0.0,0.0,0.0,1.0,-0.0012630674755200744,0.0031205317936837673,0.004104235675185919,-0.10248814523220062,-0.41916516423225403,0.03894533962011337 +1769682021,513151488,0.0,0.0,0.0,1.0,-0.0021177385933697224,0.0021629114635288715,0.0032855295576155186,-0.41933274269104004,0.10249053686857224,0.02592773176729679 +1769682021,559305984,0.0,0.0,0.0,1.0,-0.0031242237892001867,0.0015965915517881513,0.002541346475481987,-0.9410632848739624,-0.21421638131141663,0.03465370088815689 +1769682021,568832256,0.0,0.0,0.0,1.0,-0.0037480639293789864,0.001469478360377252,0.0022572509478777647,-0.9410922527313232,-0.214161217212677,0.040568411350250244 +1769682021,609844224,0.0,0.0,0.0,1.0,-0.004667934030294418,0.0013674118090420961,0.0018252590671181679,-0.6009419560432434,-0.1862608790397644,0.0033193137496709824 +1769682021,648161536,0.0,0.0,0.0,1.0,-0.0053909714333713055,0.001497872406616807,0.0015374585054814816,-3.7521122067118995e-06,2.3674986096011708e-06,0.0011920854449272156 +1769682021,679477248,0.0,0.0,0.0,1.0,-0.005256290081888437,0.0018826216692104936,0.0013931109569966793,-0.34002792835235596,-0.027894943952560425,-0.009381272830069065 +1769682021,710776064,0.0,0.0,0.0,1.0,-0.005273687187582254,0.002097558928653598,0.0012741953833028674,-0.8618564009666443,-0.34449219703674316,-0.002233244478702545 +1769682021,761895424,0.0,0.0,0.0,1.0,-0.005240064114332199,0.002320703584700823,0.0011840853840112686,-0.15820905566215515,0.26086682081222534,-0.028329260647296906 +1769682021,776955904,0.0,0.0,0.0,1.0,-0.005117230117321014,0.002550919074565172,0.0011458109365776181,0.2609485983848572,0.15827973186969757,-0.010042271576821804 +1769682021,809715456,0.0,0.0,0.0,1.0,-0.005280615296214819,0.0027243804652243853,0.001122458023019135,-0.340000182390213,-0.027844756841659546,-0.017847727984189987 +1769682021,852265472,0.0,0.0,0.0,1.0,-0.004908241797238588,0.002757570706307888,0.0011116156820207834,-0.5218009948730469,-0.31655818223953247,-0.014700695872306824 +1769682021,882038784,0.0,0.0,0.0,1.0,-0.005110922735184431,0.002876236569136381,0.0011093424400314689,-0.18180707097053528,-0.2887275516986847,0.0019403165206313133 +1769682021,910562304,0.0,0.0,0.0,1.0,-0.004910163581371307,0.0027780334930866957,0.001105863368138671,0.34010645747184753,0.027779676020145416,-0.010652264580130577 +1769682021,944945152,0.0,0.0,0.0,1.0,-0.004704038612544537,0.002948861103504896,0.0011004672851413488,0.18176472187042236,0.28872162103652954,0.014883749186992645 +1769682021,976455936,0.0,0.0,0.0,1.0,-0.004663723986595869,0.002879429142922163,0.001098032807931304,-0.3399682343006134,-0.0277679692953825,-0.025187961757183075 +1769682022,11354880,0.0,0.0,0.0,1.0,-0.00453756470233202,0.002935101045295596,0.0010829137172549963,-0.5218209028244019,-0.31645578145980835,-0.022336140275001526 +1769682022,58962176,0.0,0.0,0.0,1.0,-0.00455908989533782,0.0028786510229110718,0.0010401703184470534,-0.33999523520469666,-0.027734432369470596,-0.018112167716026306 +1769682022,71576576,0.0,0.0,0.0,1.0,-0.0045872521586716175,0.0027450299821794033,0.0010254201479256153,-0.15828394889831543,0.26096197962760925,0.017238546162843704 +1769682022,109678080,0.0,0.0,0.0,1.0,-0.004464726895093918,0.002932851668447256,0.0009765615686774254,-0.07905728369951248,0.13048788905143738,-0.009843803942203522 +1769682022,165895936,0.0,0.0,0.0,1.0,-0.004448650870472193,0.002836560131981969,0.0009396105306223035,-0.6802093386650085,-0.05540888011455536,0.013623273931443691 +1769682022,174504448,0.0,0.0,0.0,1.0,-0.00444706529378891,0.0027948087081313133,0.0008987404289655387,-0.4192452132701874,0.1027878001332283,0.017225250601768494 +1769682022,211208704,0.0,0.0,0.0,1.0,-0.004554073326289654,0.0028900958131998777,0.0008583407034166157,-0.41915544867515564,0.10281050205230713,-0.0018703923560678959 +1769682022,252853760,0.0,0.0,0.0,1.0,-0.0044236755929887295,0.002864146139472723,0.0008228504448197782,-0.18184205889701843,-0.2886486053466797,-0.014243505895137787 +1769682022,278900992,0.0,0.0,0.0,1.0,-0.004577312618494034,0.002774567576125264,0.0008148382767103612,-0.07915423065423965,0.1304808259010315,0.015251725912094116 +1769682022,310474752,0.0,0.0,0.0,1.0,-0.004532750695943832,0.0027848253957927227,0.0007798345177434385,-0.7592989802360535,0.0751723200082779,0.013041593134403229 +1769682022,350478848,0.0,0.0,0.0,1.0,-0.004525846801698208,0.0028451806865632534,0.0007888402324169874,-0.2608250081539154,-0.15809674561023712,-0.03610081225633621 +1769682022,378842880,0.0,0.0,0.0,1.0,-0.00469947000965476,0.002897967817261815,0.0007730756769888103,-0.26089268922805786,-0.15810543298721313,-0.023032452911138535 +1769682022,411169280,0.0,0.0,0.0,1.0,-0.004781089257448912,0.0028516617603600025,0.0007498615887016058,-0.3401752710342407,-0.02766188234090805,0.01606580801308155 +1769682022,463796992,0.0,0.0,0.0,1.0,-0.004808102734386921,0.002877181861549616,0.0007383294869214296,-0.26092180609703064,-0.15809299051761627,-0.018366726115345955 +1769682022,476756224,0.0,0.0,0.0,1.0,-0.004561657551676035,0.0029231582302600145,0.0007071188883855939,7.086689583957195e-05,2.5817509595071897e-05,-0.013112906366586685 +1769682022,511643648,0.0,0.0,0.0,1.0,-0.004737295210361481,0.0030139992013573647,0.0006608128314837813,-0.18194729089736938,-0.2886180877685547,-0.003993373364210129 +1769682022,546880000,0.0,0.0,0.0,1.0,-0.0045842076651751995,0.002930551068857312,0.0005915969959460199,-0.6801910400390625,-0.05519567057490349,0.0032095834612846375 +1769682022,568301056,0.0,0.0,0.0,1.0,-0.004450775217264891,0.002991301007568836,0.0005805643741041422,-0.4191393554210663,0.10292025655508041,0.00025444338098168373 +1769682022,610092032,0.0,0.0,0.0,1.0,-0.004591223318129778,0.0029916793573647738,0.0005023471894674003,0.18199719488620758,0.28862109780311584,-0.001774609787389636 +1769682022,648278528,0.0,0.0,0.0,1.0,-0.004629518371075392,0.0028420838061720133,0.00044076365884393454,0.1820378601551056,0.288634717464447,-0.007658651098608971 +1769682022,676817664,0.0,0.0,0.0,1.0,-0.005571292247623205,0.0034960992634296417,0.0004625300061888993,-0.2613450288772583,-0.15824155509471893,0.050418321043252945 +1769682022,710621184,0.0,0.0,0.0,1.0,-0.0056869350373744965,0.003664272138848901,0.000488597434014082,5.826639971928671e-05,2.9622206056956202e-05,-0.009536526165902615 +1769682022,754890752,0.0,0.0,0.0,1.0,-0.0060885013081133366,0.0038827569223940372,0.0005164111498743296,0.18208430707454681,0.2886461615562439,-0.012198958545923233 +1769682022,776943104,0.0,0.0,0.0,1.0,-0.006425629369914532,0.003987230826169252,0.0005059108370915055,-0.2611284852027893,-0.15812350809574127,0.01207861676812172 +1769682022,810786560,0.0,0.0,0.0,1.0,-0.006350731942802668,0.004076996352523565,0.0005414236220531166,-0.5219933986663818,-0.31608766317367554,-0.017690690234303474 +1769682022,848917248,0.0,0.0,0.0,1.0,-0.006592810619622469,0.004181189462542534,0.0005465829744935036,-0.26092302799224854,-0.1579904854297638,-0.020255709066987038 +1769682022,878193664,0.0,0.0,0.0,1.0,-0.006966360379010439,0.004137731622904539,0.000565669615752995,-0.26102855801582336,-0.15804705023765564,-0.004824052564799786 +1769682022,910323200,0.0,0.0,0.0,1.0,-0.006810111925005913,0.004193337634205818,0.0005892704357393086,-0.6011151075363159,-0.1855708360671997,-0.006173995323479176 +1769682022,944896512,0.0,0.0,0.0,1.0,-0.00682809017598629,0.004057300742715597,0.0006316254148259759,-0.10303331166505814,-0.4191268980503082,0.0020768558606505394 +1769682022,968076032,0.0,0.0,0.0,1.0,-0.006791441701352596,0.004028115421533585,0.0006470362422987819,0.34011077880859375,0.027533255517482758,-0.002196104731410742 +1769682023,12306944,0.0,0.0,0.0,1.0,-0.0039479294791817665,0.0030263070948421955,0.0005534047377295792,-0.07939611375331879,0.13027431070804596,0.051337696611881256 +1769682023,52602368,0.0,0.0,0.0,1.0,-0.0026193992234766483,0.0011950981570407748,0.0004502914089243859,0.07868341356515884,-0.1307680308818817,0.04520835727453232 +1769682023,78546176,0.0,0.0,0.0,1.0,-0.0019906621892005205,0.00042993962415494025,0.00040724524296820164,0.18174384534358978,0.28834858536720276,0.04338814690709114 +1769682023,110942464,0.0,0.0,0.0,1.0,-0.0019326518522575498,-0.00034188898280262947,0.00038247142219915986,0.4428982436656952,0.44642916321754456,0.03425344079732895 +1769682023,150531328,0.0,0.0,0.0,1.0,-0.0016803945181891322,-0.0004860684275627136,0.0003338879032526165,0.6010286211967468,0.18541637063026428,0.020932931452989578 +1769682023,177417472,0.0,0.0,0.0,1.0,-0.001732200151309371,-0.0005121568683534861,0.00030171641265042126,-8.788714694674127e-06,-6.4556061261100695e-06,0.0011920437682420015 +1769682023,210151424,0.0,0.0,0.0,1.0,-0.0016255168011412024,-9.580120968166739e-05,0.00026305264327675104,0.26122573018074036,0.15813077986240387,-0.0186705831438303 +1769682023,260018944,0.0,0.0,0.0,1.0,-0.0014398047933354974,0.0009735508938319981,0.0002519825065974146,0.26120132207870483,0.1581096202135086,-0.015077798627316952 +1769682023,267456000,0.0,0.0,0.0,1.0,-0.0011932122288271785,0.001441214350052178,0.0002427065628580749,0.3643425405025482,0.5772640705108643,-0.02389470301568508 +1769682023,311934464,0.0,0.0,0.0,1.0,-0.0013901668135076761,0.0020995596423745155,0.00021443651348818094,0.18217027187347412,0.2886277139186859,-0.011320717632770538 +1769682023,348523264,0.0,0.0,0.0,1.0,-0.0015179289039224386,0.0025903922505676746,0.00019237269589211792,-0.26085472106933594,-0.15784254670143127,-0.03148750960826874 +1769682023,372276736,0.0,0.0,0.0,1.0,-0.0014749473193660378,0.0025216180365532637,0.00017765199299901724,0.07911587506532669,-0.13045985996723175,-0.014444162137806416 +1769682023,410816768,0.0,0.0,0.0,1.0,-0.001587596139870584,0.0024008513428270817,0.00015964968770276755,-3.693064354592934e-05,-2.746362952166237e-05,0.004768152721226215 +1769682023,448561664,0.0,0.0,0.0,1.0,-0.0014601255534216762,0.0023810577113181353,0.00011923519195988774,-0.0790611207485199,0.13050061464309692,0.0072927637957036495 +1769682023,476992000,0.0,0.0,0.0,1.0,-0.0015421544667333364,0.0022477363236248493,0.00010196937364526093,0.15769827365875244,-0.26131579279899597,0.03905453905463219 +1769682023,501478144,0.0,0.0,0.0,1.0,-0.0014715950237587094,0.0021145902574062347,8.396844350500032e-05,0.26100775599479675,0.15794965624809265,0.011352398432791233 +1769682023,548555264,0.0,0.0,0.0,1.0,-0.0015163597417995334,0.002028438728302717,4.909520430373959e-05,-0.2610741853713989,-0.1579979658126831,-0.003048896323889494 +1769682023,576540160,0.0,0.0,0.0,1.0,-0.0013323320308700204,0.0019623106345534325,2.8547807232826017e-05,-0.07908141613006592,0.1304853856563568,0.009682082571089268 +1769682023,610271744,0.0,0.0,0.0,1.0,-0.0015953108668327332,0.0019504769006744027,-3.792163624893874e-06,0.1578909456729889,-0.2611728608608246,0.014007728546857834 +1769682023,650550784,0.0,0.0,0.0,1.0,-0.0020990613847970963,0.0018307045102119446,-1.1971147614531219e-05,0.0789056196808815,-0.13061626255512238,0.011768573895096779 +1769682023,677761280,0.0,0.0,0.0,1.0,-0.0019098640186712146,0.0017931892070919275,-1.1313595678075217e-05,-0.18206946551799774,-0.28853991627693176,-0.003303603269159794 +1769682023,710422528,0.0,0.0,0.0,1.0,-0.001851406297646463,0.0017039261292666197,-2.8573282179422677e-05,0.3400774300098419,0.02745434269309044,0.00301567860879004 +1769682023,767465472,0.0,0.0,0.0,1.0,-0.0015982529148459435,0.001843755366280675,-1.8797565644490533e-05,0.07903444021940231,-0.13052009046077728,-0.00373563589528203 +1769682023,775609856,0.0,0.0,0.0,1.0,-0.001861603930592537,0.0018535519484430552,-1.66758218256291e-05,0.07918643206357956,-0.13040582835674286,-0.021618565544486046 +1769682023,810900224,0.0,0.0,0.0,1.0,-0.0016450220718979836,0.0018527066567912698,4.668476321967319e-06,-0.07881089299917221,0.13068819046020508,-0.02248453162610531 +1769682023,846051328,0.0,0.0,0.0,1.0,-0.0015907384222373366,0.001819394645281136,3.35047698172275e-05,-0.1820475310087204,-0.28852370381355286,-0.005826436914503574 +1769682023,876978688,0.0,0.0,0.0,1.0,-0.0015728160506114364,0.0018730566371232271,4.270305726095103e-05,-0.26106202602386475,-0.15798823535442352,-0.004489169456064701 +1769682023,911592192,0.0,0.0,0.0,1.0,-0.0016957507468760014,0.0018171851988881826,5.3468815167434514e-05,0.10308535397052765,0.4190969169139862,0.0012778027448803186 +1769682023,950628608,0.0,0.0,0.0,1.0,-0.0011504126014187932,0.0019479203037917614,0.00030516739934682846,-0.44308018684387207,-0.44648313522338867,-0.014021364971995354 +1769682023,979652352,0.0,0.0,0.0,1.0,-0.0004275682440493256,0.002172796055674553,0.0006006965413689613,1.0563991054368671e-05,7.94676088844426e-06,-0.0011920204851776361 +1769682024,9963776,0.0,0.0,0.0,1.0,-0.000243854578002356,0.0025780457071959972,0.0007821746985428035,0.18212275207042694,0.28856202960014343,-0.001214747317135334 +1769682024,49433088,0.0,0.0,0.0,1.0,0.0002083012368530035,0.002713217167183757,0.0009467425406910479,-0.36447128653526306,-0.5772621035575867,0.025039970874786377 +1769682024,79658240,0.0,0.0,0.0,1.0,0.0003045535122510046,0.0028374199755489826,0.0010254407534375787,-0.34005627036094666,-0.027399461716413498,-0.005672721192240715 +1769682024,111691520,0.0,0.0,0.0,1.0,0.00013964406389277428,0.002873390680179,0.0010535138426348567,0.1582132875919342,-0.26093313097953796,-0.026507340371608734 +1769682024,143777280,0.0,0.0,0.0,1.0,6.492636748589575e-05,0.0030179847963154316,0.0010478991316631436,8.90618612174876e-05,6.343828863464296e-05,-0.00953612383455038 +1769682024,177519360,0.0,0.0,0.0,1.0,0.000529253389686346,0.0024657677859067917,0.001066801487468183,0.07908836007118225,-0.13048052787780762,-0.012044357135891914 +1769682024,210771200,0.0,0.0,0.0,1.0,0.00011414129403419793,0.002137495204806328,0.0010426645167171955,-0.6798332333564758,-0.054507769644260406,-0.041384655982255936 +1769682024,248420096,0.0,0.0,0.0,1.0,7.543213723693043e-05,0.0016907607205212116,0.0010180240496993065,0.261365681886673,0.15809419751167297,-0.022680044174194336 +1769682024,277323776,0.0,0.0,0.0,1.0,-0.00014657255087513477,0.0015881586587056518,0.0009879089193418622,0.6803247332572937,0.054799482226371765,-0.009790281765162945 +1769682024,311400960,0.0,0.0,0.0,1.0,-0.0001358057197649032,0.001471725874580443,0.0009409741614945233,-0.18207307159900665,-0.2884118854999542,-0.013206349685788155 +1769682024,347001600,0.0,0.0,0.0,1.0,0.00021336005011107773,0.001440417836420238,0.0009023654274642467,0.33985212445259094,0.027164272964000702,0.027323033660650253 +1769682024,376586240,0.0,0.0,0.0,1.0,0.0002896078513003886,0.0013741147704422474,0.0008770122658461332,-0.4434793293476105,-0.4464624226093292,0.009413884952664375 +1769682024,410203136,0.0,0.0,0.0,1.0,0.00031055189901962876,0.0013945618411526084,0.0008299326291307807,0.26126575469970703,0.15796856582164764,-0.009511101990938187 +1769682024,446993408,0.0,0.0,0.0,1.0,3.856822513625957e-05,0.0013655397342517972,0.0007883140351623297,0.2607666850090027,0.15762126445770264,0.0417594276368618 +1769682024,478015744,0.0,0.0,0.0,1.0,3.638041380327195e-05,0.0013528323033824563,0.0007506097899749875,-0.26112210750579834,-0.15785180032253265,-0.006010167300701141 +1769682024,510290176,0.0,0.0,0.0,1.0,0.00018781237304210663,0.0013761045411229134,0.0007227301248349249,0.2613857388496399,0.15801943838596344,-0.020203370600938797 +1769682024,562672384,0.0,0.0,0.0,1.0,-0.00018199441547039896,0.0013579961378127337,0.0006602095090784132,0.2611173689365387,0.15783114731311798,0.007227485999464989 +1769682024,569429760,0.0,0.0,0.0,1.0,-0.00010999922960763797,0.0015274969628080726,0.0006260153604671359,0.41880425810813904,-0.10346320271492004,0.02497177943587303 +1769682024,611751424,0.0,0.0,0.0,1.0,-0.000824393646325916,0.0006716857315041125,0.00010208832827629521,-0.07945813238620758,0.1302400827407837,0.052519023418426514 +1769682024,646274816,0.0,0.0,0.0,1.0,-0.0013289459748193622,0.0003454602265264839,-0.00030289340065792203,-0.2611795961856842,-0.15786579251289368,-0.00129981548525393 +1769682024,677509120,0.0,0.0,0.0,1.0,-0.00160176248755306,-1.388329837936908e-05,-0.0005377765628509223,0.18208786845207214,0.2883511781692505,0.016882993280887604 +1769682024,710402816,0.0,0.0,0.0,1.0,-0.0018516907002776861,-0.0001383966882713139,-0.00075321871554479,0.4190100431442261,-0.10331770777702332,0.004717601463198662 +1769682024,757998080,0.0,0.0,0.0,1.0,-0.0021057804115116596,-5.845008126925677e-05,-0.0009711916791275144,-0.3402172327041626,-0.02737589366734028,0.009498586878180504 +1769682024,766961152,0.0,0.0,0.0,1.0,-0.002270494820550084,-3.713593469001353e-05,-0.0010651370976120234,-0.18220989406108856,-0.2884606420993805,-0.0026280893944203854 +1769682024,810832896,0.0,0.0,0.0,1.0,-0.0021510201040655375,-3.0867275199852884e-05,-0.0012055148836225271,-0.07884129881858826,0.13065071403980255,-0.010613602586090565 +1769682024,860964352,0.0,0.0,0.0,1.0,-0.0021379380486905575,0.00014650207594968379,-0.0013235254446044564,-0.18234986066818237,-0.2885957360267639,0.01400850247591734 +1769682024,876510976,0.0,0.0,0.0,1.0,-0.0021842338610440493,0.00033904684823937714,-0.001377952634356916,-0.10313619673252106,-0.41900303959846497,-0.009984605014324188 +1769682024,910624512,0.0,0.0,0.0,1.0,-0.001772206393070519,0.00015586239169351757,-0.0014460883103311062,-0.18216949701309204,-0.288501501083374,-0.001525825704447925 +1769682024,946598656,0.0,0.0,0.0,1.0,-0.0018590284744277596,0.0002967343316413462,-0.0014830069849267602,0.26109105348587036,0.15792560577392578,0.004977104719728231 +1769682024,967790592,0.0,0.0,0.0,1.0,-0.002040123101323843,0.00038803659845143557,-0.001518701552413404,0.18219193816184998,0.2885523736476898,-0.0032042283564805984 +1769682025,14878976,0.0,0.0,0.0,1.0,-0.0020106250885874033,0.00027095459518022835,-0.0015566330403089523,-0.18212583661079407,-0.2885287404060364,-0.0015875946264714003 +1769682025,47076096,0.0,0.0,0.0,1.0,-0.0014233876718208194,0.00032799170003272593,-0.001601917203515768,0.33988022804260254,0.027283940464258194,0.02272261306643486 +1769682025,77172736,0.0,0.0,0.0,1.0,-0.0021844676230102777,0.0003547013329807669,-0.0016586793353781104,-0.26107057929039,-0.1579868495464325,-0.0038339910097420216 +1769682025,110536960,0.0,0.0,0.0,1.0,-0.002113817259669304,0.0003940212482120842,-0.0017309397226199508,-7.262994768097997e-05,-5.407795470091514e-05,0.007151988800615072 +1769682025,153158144,0.0,0.0,0.0,1.0,-0.0017873315373435616,0.00040214144974015653,-0.0018121656030416489,-0.00012122451880713925,-9.09105219761841e-05,0.011919974349439144 +1769682025,178824704,0.0,0.0,0.0,1.0,-0.0014060157118365169,0.0003561849589459598,-0.001894650747999549,0.5220340490341187,0.3160257637500763,0.013703161850571632 +1769682025,210188032,0.0,0.0,0.0,1.0,-0.0018152393167838454,0.0004224117728881538,-0.001962834969162941,0.07891089469194412,-0.13061779737472534,0.011716163717210293 +1769682025,250141952,0.0,0.0,0.0,1.0,-0.0015270158182829618,0.0003139556501992047,-0.002063256921246648,-3.648027632152662e-05,-2.7895548555534333e-05,0.0035759862512350082 +1769682025,279085056,0.0,0.0,0.0,1.0,-0.0017247035866603255,0.0001328900398220867,-0.0021460189018398523,-0.34006136655807495,-0.02757083997130394,-0.003687983611598611 +1769682025,311014912,0.0,0.0,0.0,1.0,-0.001962837530300021,0.00023503982811234891,-0.00222213682718575,-0.340376079082489,-0.027838073670864105,0.027300497516989708 +1769682025,344905216,0.0,0.0,0.0,1.0,-0.001546944142319262,0.0002541377325542271,-0.0022920339833945036,0.7039570808410645,0.6049350500106812,0.00486038951203227 +1769682025,367199488,0.0,0.0,0.0,1.0,-0.0012688532005995512,0.00023388181580230594,-0.002354515716433525,-0.18181462585926056,-0.2885688245296478,-0.012512650340795517 +1769682025,411104000,0.0,0.0,0.0,1.0,-0.001594405504874885,0.00034548970870673656,-0.002471220912411809,0.5220345854759216,0.31641191244125366,-0.002832903992384672 +1769682025,459264000,0.0,0.0,0.0,1.0,-0.0020803557708859444,0.00028704863507300615,-0.0026500513777136803,-0.157963365316391,0.2611583471298218,-0.02333899214863777 +1769682025,468748032,0.0,0.0,0.0,1.0,-0.0002451996551826596,-0.0006064838380552828,-0.0027955700643360615,0.783129870891571,0.4748624563217163,-0.019112585112452507 +1769682025,502334464,0.0,0.0,0.0,1.0,0.0012498389696702361,-0.0018436142709106207,-0.003050104482099414,0.601231575012207,0.18621297180652618,-0.018594717606902122 +1769682025,548987136,0.0,0.0,0.0,1.0,0.002436462789773941,-0.0028003216721117496,-0.0032208331394940615,0.5220992565155029,0.3167746067047119,-0.0219978466629982 +1769682025,579428352,0.0,0.0,0.0,1.0,0.0032764466013759375,-0.0032581426203250885,-0.0033160201273858547,0.15856173634529114,-0.2607029974460602,-0.025518739596009254 +1769682025,614193152,0.0,0.0,0.0,1.0,0.003763077314943075,-0.0036298225168138742,-0.003384624607861042,0.18169951438903809,0.28876346349716187,0.004054335877299309 +1769682025,650633472,0.0,0.0,0.0,1.0,0.004252694547176361,-0.0037581808865070343,-0.0034867103677242994,0.41924431920051575,-0.10248805582523346,0.0009149415418505669 +1769682025,677529088,0.0,0.0,0.0,1.0,0.004414575640112162,-0.0036374470219016075,-0.0035492933820933104,0.6006901264190674,0.18621298670768738,0.025069374591112137 +1769682025,710178560,0.0,0.0,0.0,1.0,0.004530878737568855,-0.0034961188212037086,-0.0036152522079646587,0.26092755794525146,0.15850232541561127,-0.008264802396297455 +1769682025,762567680,0.0,0.0,0.0,1.0,0.004167797509580851,-0.003338838228955865,-0.003688489319756627,-0.1584007441997528,0.260858416557312,-0.006754905916750431 +1769682025,769988352,0.0,0.0,0.0,1.0,0.004475228022783995,-0.0033268413972109556,-0.0037303967401385307,0.4422382414340973,0.44728341698646545,0.015656860545277596 +1769682025,811881472,0.0,0.0,0.0,1.0,0.004304883535951376,-0.0031583255622535944,-0.0037905126810073853,0.41931572556495667,-0.10223355889320374,-0.00043644243851304054 +1769682025,845780224,0.0,0.0,0.0,1.0,0.0042936489917337894,-0.003148099174723029,-0.003855051239952445,0.3399401605129242,0.028123129159212112,0.01161525771021843 +1769682025,896609024,0.0,0.0,0.0,1.0,0.003913823049515486,-0.003003304358571768,-0.0038817645981907845,0.6007592082023621,0.18682751059532166,0.0030550933443009853 +1769682025,916404224,0.0,0.0,0.0,1.0,0.0036527893971651793,-0.0030826893635094166,-0.003897880669683218,-0.10222767293453217,-0.4194420278072357,0.014226112514734268 +1769682025,950042112,0.0,0.0,0.0,1.0,0.003778030164539814,-0.002933284966275096,-0.0039000592660158873,0.5215418338775635,0.3174569010734558,-0.01605476811528206 +1769682025,966524160,0.0,0.0,0.0,1.0,0.004928953479975462,-0.0034393328242003918,-0.003910656552761793,0.44173723459243774,0.4475165903568268,0.034080855548381805 +1769682026,10418176,0.0,0.0,0.0,1.0,0.005291566252708435,-0.004043112508952618,-0.00392820592969656,0.8613107204437256,0.3458597958087921,0.004695627838373184 +1769682026,60415232,0.0,0.0,0.0,1.0,0.004800995346158743,-0.004275918006896973,-0.003913785330951214,0.10177116096019745,0.41933342814445496,0.011682724580168724 +1769682026,68340224,0.0,0.0,0.0,1.0,0.004547751974314451,-0.004372790921479464,-0.003921557683497667,0.6798791289329529,0.056873567402362823,0.019070561975240707 +1769682026,112941056,0.0,0.0,0.0,1.0,0.0048365285620093346,-0.004243018571287394,-0.0039020779076963663,-0.15889866650104523,0.26053887605667114,0.008528498001396656 +1769682026,152789504,0.0,0.0,0.0,1.0,0.004517365247011185,-0.004235259257256985,-0.0039180270396173,0.07958721369504929,-0.13017648458480835,-0.019153432920575142 +1769682026,179586560,0.0,0.0,0.0,1.0,0.004926342982798815,-0.004091713111847639,-0.003941504284739494,0.3400851786136627,0.028692997992038727,-0.010306349024176598 +1769682026,211516416,0.0,0.0,0.0,1.0,0.0041700974106788635,-0.003941432107239962,-0.004002852365374565,0.057440150529146194,-0.6799221038818359,-0.013814771547913551 +1769682026,248396288,0.0,0.0,0.0,1.0,0.004078778438270092,-0.0033001548144966364,-0.004061430227011442,-0.07920920103788376,0.13043397665023804,-0.03690038621425629 +1769682026,277673984,0.0,0.0,0.0,1.0,0.004546398762613535,-0.002788727870211005,-0.0040591093711555,-0.1808403730392456,-0.2891584038734436,-0.0194469653069973 +1769682026,312977664,0.0,0.0,0.0,1.0,0.0046007512137293816,-0.0023847869597375393,-0.004077659919857979,0.2385677993297577,-0.39068278670310974,-0.0012839487753808498 +1769682026,361124608,0.0,0.0,0.0,1.0,0.004725880455225706,-0.0022392922546714544,-0.0040890551172196865,-0.18094338476657867,-0.28933030366897583,0.005707928910851479 +1769682026,372091648,0.0,0.0,0.0,1.0,0.004352065734565258,-0.0022790462244302034,-0.004084046930074692,0.15909452736377716,-0.260425329208374,0.0011801805812865496 +1769682026,411293952,0.0,0.0,0.0,1.0,0.0045715924352407455,-0.002361821476370096,-0.004095620010048151,0.18076924979686737,0.28931179642677307,0.008494540117681026 +1769682026,456879360,0.0,0.0,0.0,1.0,0.004474163521081209,-0.0023764180950820446,-0.0040992251597344875,0.6002437472343445,0.1881137192249298,0.01576092280447483 +1769682026,474326272,0.0,0.0,0.0,1.0,0.0045755296014249325,-0.0025278788525611162,-0.004107434768229723,-4.160061871516518e-05,-2.373063216509763e-05,0.005960275884717703 +1769682026,511446016,0.0,0.0,0.0,1.0,0.004587067291140556,-0.0026058463845402002,-0.004124761559069157,0.41958102583885193,-0.10107540339231491,0.0013156314380466938 +1769682026,547110912,0.0,0.0,0.0,1.0,0.004261404275894165,-0.002524235285818577,-0.004139703232795,0.15925534069538116,-0.26032403111457825,0.00608702190220356 +1769682026,568729344,0.0,0.0,0.0,1.0,0.004099278710782528,-0.0026053215842694044,-0.004155838396400213,0.6001076102256775,0.18842321634292603,0.021416708827018738 +1769682026,611441920,0.0,0.0,0.0,1.0,0.004563738591969013,-0.0025993145536631346,-0.004171489737927914,0.34005364775657654,0.029287714511156082,-0.015523443929851055 +1769682026,661702912,0.0,0.0,0.0,1.0,0.004222643095999956,-0.002647108631208539,-0.004209639970213175,-0.26018884778022766,-0.1593824326992035,-0.008179815486073494 +1769682026,668305408,0.0,0.0,0.0,1.0,0.00429471954703331,-0.0028175089973956347,-0.00422512786462903,0.07958216965198517,-0.13017535209655762,0.020367801189422607 +1769682026,710523392,0.0,0.0,0.0,1.0,0.004032873548567295,-0.002708113519474864,-0.004271684214472771,0.15947872400283813,-0.2601911127567291,-0.0009592385031282902 +1769682026,752803584,0.0,0.0,0.0,1.0,0.004001556430011988,-0.002670817542821169,-0.004292170982807875,0.5202762484550476,0.31900686025619507,0.011313572525978088 +1769682026,778111488,0.0,0.0,0.0,1.0,0.003988491836935282,-0.0025673620402812958,-0.0043272231705486774,-0.2601473927497864,-0.1595507264137268,-0.0008487708400934935 +1769682026,812201984,0.0,0.0,0.0,1.0,0.003906992729753256,-0.002594483783468604,-0.004343975801020861,-0.18035681545734406,-0.2896569073200226,0.0029157684184610844 +1769682026,856098048,0.0,0.0,0.0,1.0,0.0038348319940268993,-0.002652144758030772,-0.00439015356823802,0.6000049114227295,0.1892087608575821,0.0028650141321122646 +1769682026,877694976,0.0,0.0,0.0,1.0,0.004351044539362192,-0.002560434164479375,-0.004400715231895447,0.6798117160797119,0.059249863028526306,0.002965171355754137 +1769682026,910620928,0.0,0.0,0.0,1.0,0.0030726243276149035,-0.0024682150688022375,-0.004783426411449909,-0.1802416741847992,-0.2897408902645111,0.005462369415909052 +1769682026,961139200,0.0,0.0,0.0,1.0,0.0006256558699533343,-0.0034284167923033237,-0.005971415434032679,0.3399057388305664,0.029750879853963852,-0.00037750881165266037 +1769682026,968531968,0.0,0.0,0.0,1.0,0.0003218948550056666,-0.0038807366508990526,-0.006413183640688658,0.33998262882232666,0.02982444129884243,-0.01470866333693266 +1769682027,12419328,0.0,0.0,0.0,1.0,0.00045956537360325456,-0.004702828824520111,-0.007032681722193956,0.5199126601219177,0.31972432136535645,0.002334066666662693 +1769682027,45026048,0.0,0.0,0.0,1.0,-0.0001292507949983701,-0.004933634772896767,-0.007453761529177427,0.339834600687027,0.02996557205915451,0.009008334949612617 +1769682027,80266496,0.0,0.0,0.0,1.0,-0.0005584704922512174,-0.00496777193620801,-0.007692338433116674,0.5997273325920105,0.1900508552789688,0.004676359705626965 +1769682027,111076864,0.0,0.0,0.0,1.0,-0.0004215130757074803,-0.005014221183955669,-0.00784516055136919,0.2401265949010849,-0.3897341191768646,-0.008002640679478645 +1769682027,152194816,0.0,0.0,0.0,1.0,-0.0007850199472159147,-0.005139875691384077,-0.007984570227563381,0.17955707013607025,0.28995898365974426,0.033682771027088165 +1769682027,178457600,0.0,0.0,0.0,1.0,-0.0005446779541671276,-0.005050865467637777,-0.008046045899391174,0.25968676805496216,0.16017384827136993,0.013475869782269001 +1769682027,214256640,0.0,0.0,0.0,1.0,-0.0001347070501651615,-0.005003886763006449,-0.008061482571065426,0.4198295772075653,-0.09951283037662506,0.032645948231220245 +1769682027,262811648,0.0,0.0,0.0,1.0,-0.00014108663890510798,-0.0028657938819378614,-0.008027960546314716,0.2591448724269867,0.1600804328918457,0.11949342489242554 +1769682027,275598336,0.0,0.0,0.0,1.0,-0.000158715556608513,-0.000665105355437845,-0.008123776875436306,-0.08054016530513763,0.12963108718395233,0.07862843573093414 +1769682027,311012096,0.0,0.0,0.0,1.0,7.252313662320375e-05,0.000887672184035182,-0.008199324831366539,0.4197884798049927,-0.09924241900444031,0.06236690282821655 +1769682027,365179648,0.0,0.0,0.0,1.0,8.74282413860783e-05,0.0025726635940372944,-0.008232568390667439,-0.00014550978085026145,-7.546236156485975e-05,0.0333782434463501 +1769682027,374592512,0.0,0.0,0.0,1.0,0.00015543668996542692,0.003520405385643244,-0.008225616998970509,0.6796130537986755,0.06177244707942009,-0.0027927402406930923 +1769682027,412386560,0.0,0.0,0.0,1.0,5.242385668680072e-06,0.0037504069041460752,-0.008217495866119862,0.5188997387886047,0.321380078792572,-0.0004830462858080864 +1769682027,445976320,0.0,0.0,0.0,1.0,0.00034818239510059357,0.003929989878088236,-0.008175578899681568,0.33985939621925354,0.03111487254500389,-0.016207195818424225 +1769682027,477207296,0.0,0.0,0.0,1.0,0.00028954300796613097,0.0038615369703620672,-0.008158594369888306,0.00016153781325556338,7.474260200979188e-05,-0.03337817266583443 +1769682027,511096832,0.0,0.0,0.0,1.0,0.00025449437089264393,0.0037359714042395353,-0.008127691224217415,-4.724450991488993e-05,-2.1299814761732705e-05,0.00953662022948265 +1769682027,549043200,0.0,0.0,0.0,1.0,0.00038543855771422386,0.003523502266034484,-0.008109590969979763,-0.08053421229124069,0.12961232662200928,0.00822281651198864 +1769682027,567848448,0.0,0.0,0.0,1.0,0.0003280571836512536,0.003293144516646862,-0.00806086789816618,0.08059262484312057,-0.129583477973938,-0.015369178727269173 +1769682027,644677376,0.0,0.0,0.0,1.0,1.218502438860014e-05,0.0032394416630268097,-0.008021627552807331,0.2591286301612854,0.16108621656894684,0.011266455054283142 +1769682027,657280256,0.0,0.0,0.0,1.0,0.00035539170494303107,0.002974833594635129,-0.007951408624649048,-0.08062143623828888,0.12955573201179504,0.004618329927325249 +1769682027,685291008,0.0,0.0,0.0,1.0,0.0004901747452095151,0.00294070434756577,-0.00789621938019991,0.35685956478118896,0.5815713405609131,0.01516962330788374 +1769682027,698618624,0.0,0.0,0.0,1.0,3.425265458645299e-05,0.0031575793400406837,-0.007862850092351437,8.632887329440564e-05,3.417849802644923e-05,-0.015496963635087013 +1769682027,752586240,0.0,0.0,0.0,1.0,0.0003084804047830403,0.003104948904365301,-0.0077286832965910435,0.25897306203842163,0.16138285398483276,0.006605618167668581 +1769682027,768605440,0.0,0.0,0.0,1.0,0.0003736128855962306,0.0031775981187820435,-0.007664551492780447,0.3395683169364929,0.03189561143517494,0.023493807762861252 +1769682027,814326016,0.0,0.0,0.0,1.0,0.00011793569137807935,0.003115937579423189,-0.007561386097222567,0.3396472930908203,0.03203295171260834,0.008038920350372791 +1769682027,867164928,0.0,0.0,0.0,1.0,0.00033669197000563145,0.0030914924573153257,-0.007439594715833664,0.5984638333320618,0.19370609521865845,0.018339253962039948 +1769682027,876033792,0.0,0.0,0.0,1.0,0.0003471581148914993,0.0030860917177051306,-0.007366688456386328,-0.17797374725341797,-0.2910553812980652,-0.008873858489096165 +1769682027,911251200,0.0,0.0,0.0,1.0,0.00044372337288223207,0.003152557648718357,-0.007288537919521332,0.6792864203453064,0.06458485126495361,0.00913647934794426 +1769682027,963968768,0.0,0.0,0.0,1.0,7.696660759393126e-06,0.003078578505665064,-0.00719173438847065,-9.841246355790645e-05,-3.344086871948093e-05,0.015496891923248768 +1769682027,970380032,0.0,0.0,0.0,1.0,0.00012385322770569474,0.0030121139716356993,-0.007165239192545414,0.08083940297365189,-0.1293942630290985,0.010969089344143867 +1769682028,10911744,0.0,0.0,0.0,1.0,-2.8468850359786302e-05,0.003013220615684986,-0.0070879640989005566,-0.015776455402374268,-0.5499082207679749,-0.013206406496465206 +1769682028,49575680,0.0,0.0,0.0,1.0,0.0011768231634050608,0.0044905198737978935,-0.0057405102998018265,0.258800208568573,0.16200168430805206,-0.020574145019054413 +1769682028,81022720,0.0,0.0,0.0,1.0,0.0019652927294373512,0.005112511105835438,-0.005039618816226721,0.3398320972919464,0.03274349495768547,-0.02860325202345848 +1769682028,111458048,0.0,0.0,0.0,1.0,0.002964996499940753,0.005504020489752293,-0.004486400168389082,-0.16178883612155914,0.25867703557014465,-0.0351865291595459 +1769682028,146592768,0.0,0.0,0.0,1.0,0.003131832927465439,0.005559518933296204,-0.003996967803686857,0.1773977279663086,0.29132866859436035,0.02090313471853733 +1769682028,177469952,0.0,0.0,0.0,1.0,0.0037684114649891853,0.005534959491342306,-0.0036925000604242086,0.5982290506362915,0.19494318962097168,-0.004770857281982899 +1769682028,212163328,0.0,0.0,0.0,1.0,0.003968323115259409,0.005089656449854374,-0.0034703039564192295,0.33932220935821533,0.03279770910739899,0.03957150876522064 +1769682028,254877440,0.0,0.0,0.0,1.0,0.004027035553008318,0.005070093087852001,-0.0032416668254882097,0.33952227234840393,0.032890163362026215,0.012218605726957321 +1769682028,277649152,0.0,0.0,0.0,1.0,0.004031319636851549,0.004758841823786497,-0.003111709840595722,0.16227352619171143,-0.2584930956363678,-0.00980349536985159 +1769682028,310662912,0.0,0.0,0.0,1.0,0.004262862727046013,0.004477494861930609,-0.0030037029646337032,-0.08116361498832703,0.12923748791217804,0.006663087289780378 +1769682028,361385728,0.0,0.0,0.0,1.0,0.003932512830942869,0.004337050952017307,-0.0029330833349376917,0.5980093479156494,0.19524957239627838,0.009889932349324226 +1769682028,369136896,0.0,0.0,0.0,1.0,0.0037609946448355913,0.00408543273806572,-0.0028962676879018545,0.25845393538475037,0.1622609794139862,0.002307528629899025 +1769682028,413135616,0.0,0.0,0.0,1.0,0.0034690112806856632,0.003922650590538979,-0.0028508752584457397,0.33948788046836853,0.03305886685848236,0.013626793399453163 +1769682028,446268672,0.0,0.0,0.0,1.0,0.003503011306747794,0.0040520369075238705,-0.002831061603501439,0.33962562680244446,0.03311152011156082,-0.0030122888274490833 +1769682028,481980928,0.0,0.0,0.0,1.0,0.0031020469032227993,0.0037271250039339066,-0.0028009761590510607,0.6791008114814758,0.06626883894205093,0.010734781622886658 +1769682028,510642944,0.0,0.0,0.0,1.0,0.0031395484693348408,0.003780998755246401,-0.0027836065273731947,0.17716121673583984,0.29156380891799927,0.007686781696975231 +1769682028,561065216,0.0,0.0,0.0,1.0,0.003052219282835722,0.0035414325539022684,-0.0027496907860040665,0.5019837021827698,-0.22517715394496918,0.0008382401429116726 +1769682028,567333888,0.0,0.0,0.0,1.0,0.0029665541369467974,0.003624201053753495,-0.0027410276234149933,0.5980309247970581,0.19563323259353638,-0.006432804279029369 +1769682028,615123200,0.0,0.0,0.0,1.0,0.002913279691711068,0.0035609565675258636,-0.0027069139759987593,0.6790608167648315,0.06651587039232254,0.012226186692714691 +1769682028,661559552,0.0,0.0,0.0,1.0,0.0028754095546901226,0.0036435346119105816,-0.002677565673366189,-0.2583363652229309,-0.16246414184570312,-0.00124498107470572 +1769682028,674843904,0.0,0.0,0.0,1.0,0.0025771940127015114,0.003642346942797303,-0.0026642000302672386,-3.381857095519081e-05,-2.2637163965555374e-07,0.003576121060177684 +1769682028,710533376,0.0,0.0,0.0,1.0,0.0026347681414335966,0.0036114153917878866,-0.002641022438183427,0.5978578925132751,0.1958557814359665,0.0045239911414682865 +1769682028,761024768,0.0,0.0,0.0,1.0,0.002344178268685937,0.003403309965506196,-0.0026195039972662926,0.1625133603811264,-0.2582932114601135,0.002799683017656207 +1769682028,769295104,0.0,0.0,0.0,1.0,0.0026736094150692225,0.00315260561183095,-0.0025916765443980694,0.42075276374816895,-0.09573731571435928,0.01008899137377739 +1769682028,812236032,0.0,0.0,0.0,1.0,0.002435983158648014,0.0031091717537492514,-0.002566616516560316,0.5165348052978516,0.32514622807502747,0.002644972875714302 +1769682028,846302720,0.0,0.0,0.0,1.0,0.0025112233124673367,0.003001660108566284,-0.0025514562148600817,0.8560616374015808,0.3586747646331787,0.0036880625411868095 +1769682028,883245312,0.0,0.0,0.0,1.0,0.0026263254694640636,0.0029834031593054533,-0.0025427204091101885,-0.08151035010814667,0.12912802398204803,0.019385764375329018 +1769682028,911951360,0.0,0.0,0.0,1.0,0.002547742333263159,0.002835798542946577,-0.002537349471822381,0.16271521151065826,-0.25823017954826355,-0.006553865969181061 +1769682028,945649152,0.0,0.0,0.0,1.0,0.0020425072871148586,0.002710652071982622,-0.002510388381779194,0.679233729839325,0.0671120136976242,-0.010915498249232769 +1769682028,979298048,0.0,0.0,0.0,1.0,0.0023948540911078453,0.002810936886817217,-0.0024881071876734495,0.5976317524909973,0.19627729058265686,0.013239312916994095 +1769682029,13224704,0.0,0.0,0.0,1.0,0.0025468093808740377,0.002714455360546708,-0.0024586464278399944,0.8559280633926392,0.3590196669101715,0.0027489159256219864 +1769682029,56903424,0.0,0.0,0.0,1.0,0.002350759692490101,0.002894311212003231,-0.0024482838343828917,0.16293400526046753,-0.25818535685539246,-0.018327699974179268 +1769682029,77354240,0.0,0.0,0.0,1.0,0.002226946409791708,0.002821381203830242,-0.0024317277129739523,0.1627507209777832,-0.25815773010253906,0.0007756651611998677 +1769682029,111149056,0.0,0.0,0.0,1.0,0.002344390144571662,0.003059073118492961,-0.0023878118954598904,0.6789683103561401,0.06739674508571625,0.012017679400742054 +1769682029,158210304,0.0,0.0,0.0,1.0,0.0019790565129369497,0.0029621149878948927,-0.0023668401408940554,0.5974791646003723,0.19653554260730743,0.019416091963648796 +1769682029,167836672,0.0,0.0,0.0,1.0,0.0023430429864674807,0.002877251710742712,-0.002332872012630105,0.5975210666656494,0.19655922055244446,0.014673631638288498 +1769682029,210779904,0.0,0.0,0.0,1.0,0.002317659556865692,0.0027939025312662125,-0.002274799859151244,0.7603306770324707,-0.06149204447865486,0.015637429431080818 +1769682029,247722240,0.0,0.0,0.0,1.0,0.0021778352092951536,0.0028087443206459284,-0.002224049298092723,-0.1765541434288025,-0.2919122278690338,-0.011141980066895485 +1769682029,283359744,0.0,0.0,0.0,1.0,0.0021708118729293346,0.0027858978137373924,-0.0021830901969224215,0.3395233154296875,0.033824242651462555,0.0013927756808698177 +1769682029,311098624,0.0,0.0,0.0,1.0,0.0021004150621593,0.0027468129992485046,-0.0021376507356762886,-0.2581506669521332,-0.16287541389465332,0.005642644129693508 +1769682029,348210944,0.0,0.0,0.0,1.0,0.002101142657920718,0.0026878314092755318,-0.0020761305931955576,0.08128320425748825,-0.12900710105895996,0.015425466932356358 +1769682029,377788416,0.0,0.0,0.0,1.0,0.0022401446476578712,0.0025904865469783545,-0.0020155846141278744,0.5161876082420349,0.3258330821990967,-0.005275443196296692 +1769682029,411589632,0.0,0.0,0.0,1.0,0.00219173775985837,0.0025507002137601376,-0.0019576719496399164,0.5975341200828552,0.1968584954738617,0.004238024353981018 +1769682029,449197312,0.0,0.0,0.0,1.0,0.001824679085984826,0.0024699545465409756,-0.0018982645124197006,0.16311165690422058,-0.2580472230911255,-0.01196865364909172 +1769682029,477979648,0.0,0.0,0.0,1.0,0.0017975919181481004,0.002567259594798088,-0.0018331152386963367,0.8556198477745056,0.35989630222320557,-0.0024580340832471848 +1769682029,512004096,0.0,0.0,0.0,1.0,0.0018171236151829362,0.0023380948696285486,-0.0017827858682721853,0.5976377129554749,0.1969495266675949,-0.007572201080620289 +1769682029,561514752,0.0,0.0,0.0,1.0,0.0020619945134967566,0.006576817948371172,-0.0015633365837857127,0.8554909825325012,0.36001190543174744,0.004885315895080566 +1769682029,588624640,0.0,0.0,0.0,1.0,0.0018259972566738725,0.009962248615920544,-0.0013919544871896505,-0.09435582906007767,-0.4210999608039856,-0.05043204501271248 +1769682029,600660224,0.0,0.0,0.0,1.0,0.0023661653976887465,0.011270301416516304,-0.0012744419509544969,2.989718268509023e-05,-4.644700311473571e-06,-0.002383995335549116 +1769682029,650961152,0.0,0.0,0.0,1.0,0.002026936272159219,0.01140604354441166,-0.0010105855762958527,0.420833557844162,-0.09491249173879623,0.01644972525537014 +1769682029,678506496,0.0,0.0,0.0,1.0,0.0016711630159989,0.009354624897241592,-0.0009411810315214097,0.7599417567253113,-0.06078238785266876,0.04729915037751198 +1769682029,713577728,0.0,0.0,0.0,1.0,0.0017290336545556784,0.006063555367290974,-0.0007751936209388077,0.2571669816970825,0.16317768394947052,0.06038690730929375 +1769682029,750017280,0.0,0.0,0.0,1.0,0.0011621149023994803,0.002217184752225876,-0.0005718221073038876,0.5022513270378113,-0.2238416075706482,0.02529590204358101 +1769682029,779745024,0.0,0.0,0.0,1.0,0.0011121006682515144,0.0018973505357280374,-0.00038828703691251576,0.5969191193580627,0.19722580909729004,0.04239461198449135 +1769682029,810792448,0.0,0.0,0.0,1.0,0.0010718185221776366,-0.00011294515570625663,-0.0002937907993327826,0.6782066226005554,0.06829258799552917,0.06050979346036911 +1769682029,861618176,0.0,0.0,0.0,1.0,0.00030215512379072607,0.0005465361755341291,-0.00015161058399826288,0.33942511677742004,0.03409650921821594,0.007013453170657158 +1769682029,871611136,0.0,0.0,0.0,1.0,0.00020607640908565372,0.0004017199680674821,-9.15414493647404e-05,0.42081546783447266,-0.0948580726981163,0.017977330833673477 +1769682029,911834112,0.0,0.0,0.0,1.0,8.125551539706066e-05,-0.0010219610994681716,-3.352707062731497e-05,0.17636162042617798,0.2920559048652649,0.005352981388568878 +1769682029,954703872,0.0,0.0,0.0,1.0,6.64159597363323e-05,-0.00018001103308051825,5.55094302399084e-05,0.5031962990760803,-0.2239762544631958,-0.04260484129190445 +1769682029,979652864,0.0,0.0,0.0,1.0,-2.6590037123241927e-06,0.00031921613845042884,0.000115031267341692,0.4207513928413391,-0.09484697878360748,0.022727081552147865 +1769682030,11193088,0.0,0.0,0.0,1.0,-0.00017305805522482842,0.00014482012193184346,0.00013695363304577768,0.33954086899757385,0.03407636657357216,-0.0013413340784609318 +1769682030,50846208,0.0,0.0,0.0,1.0,1.0784365258587059e-05,-0.0017454870976507664,0.00014128483599051833,0.6921440362930298,0.6182015538215637,0.018865425139665604 +1769682030,77498368,0.0,0.0,0.0,1.0,0.00016447810048703104,-0.0027438115794211626,0.0001491958973929286,0.0815214291214943,-0.12897902727127075,0.0014115269295871258 +1769682030,113682432,0.0,0.0,0.0,1.0,0.00012547991354949772,-0.002851474331691861,0.00014662924513686448,0.5974165201187134,0.19714723527431488,0.006505382712930441 +1769682030,155673600,0.0,0.0,0.0,1.0,-0.00024176471924874932,-0.002044274006038904,0.00016371106903534383,-0.1763559877872467,-0.29205238819122314,-0.00649432884529233 +1769682030,177664256,0.0,0.0,0.0,1.0,-8.40743159642443e-05,-0.0012411115458235145,0.0001810417597880587,0.2447672039270401,-0.386974036693573,-0.01132049411535263 +1769682030,210632448,0.0,0.0,0.0,1.0,-3.601967546273954e-05,-0.0005167574854567647,0.0001968193391803652,0.3397030532360077,0.034038592129945755,-0.013383833691477776 +1769682030,257307136,0.0,0.0,0.0,1.0,-4.441969849722227e-06,0.003312939079478383,0.0003081048489548266,0.2579439878463745,0.16305680572986603,0.0031242016702890396 +1769682030,265699328,0.0,0.0,0.0,1.0,0.00032731436658650637,0.003943128511309624,0.0003497162542771548,0.2583026885986328,0.16299587488174438,-0.02308060973882675 +1769682030,312763136,0.0,0.0,0.0,1.0,0.00015109271043911576,0.003111510304734111,0.00036663160426542163,0.5973918437957764,0.19712300598621368,0.008967540226876736 +1769682030,347392256,0.0,0.0,0.0,1.0,-0.00010172859765589237,0.000862687302287668,0.00035359468893148005,0.855029821395874,0.3602139949798584,0.03484754264354706 +1769682030,380841984,0.0,0.0,0.0,1.0,-1.8449236449669115e-05,-0.0002205822238465771,0.0003563151112757623,-0.0003628005215432495,6.008385025779717e-05,0.026223501190543175 +1769682030,411250944,0.0,0.0,0.0,1.0,0.0001467241527279839,-0.0005673383711837232,0.00036357968929223716,0.5974146127700806,0.19709880650043488,0.007803100626915693 +1769682030,450874368,0.0,0.0,0.0,1.0,-0.00023089657770469785,-0.0011151904473081231,0.0003640132490545511,0.2578074634075165,0.1630631536245346,0.013908260501921177 +1769682030,478796288,0.0,0.0,0.0,1.0,0.0005009474698454142,-0.000950092391576618,0.0003803119179792702,0.5976334810256958,0.1970476359128952,-0.00773357879370451 +1769682030,515211008,0.0,0.0,0.0,1.0,9.88454048638232e-05,-0.0007242556312121451,0.00038964292616583407,0.2580079436302185,0.16302426159381866,-0.0004099926445633173 +1769682030,558183424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,3.6327757835388184,-0.045523352921009064,0.5105931162834167 +1769682030,571731200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682030,611339264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682030,663609856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682030,670123008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682030,712016384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682030,750270464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682030,778947072,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682030,810851328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682030,850557440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682030,878174720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682030,917642240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682030,949836800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682030,977879808,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,10845184,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,58234112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,78320384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,111869952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,144519168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,185522688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,211424256,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,251529472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,277553920,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.6502453945577145e-05,-2.7473738555272575e-06,-0.0011919771786779165 +1769682031,311709696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,350011648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,378861824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,410696704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,462021632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,471788544,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,500995840,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,547059712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,581390848,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,611162624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,648738304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,678070528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,715066880,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,750628608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,777578240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,811026688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,854071552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,878556672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,913678592,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,946924544,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682031,979210496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,11377152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,49400832,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,82734848,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,108392192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,155360512,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,179929088,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,213450752,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,262922496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,276468992,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,311689984,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,346452224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,377740032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,411197440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,445129984,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,477652480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,502947840,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,546707712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,577845760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,611078400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,648402176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,681295616,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,710871808,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,746621952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,777797632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,811848448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,845209600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,877726464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,912600064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,946242816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682032,978406400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,12372480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,61505024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,70274816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,111634688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,159100416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,166728704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,211319040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,245384960,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,282350592,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,311781376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,347533568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,377772800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,414825216,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,450795776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,479134464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,511519488,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,557248512,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,577633536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,612048384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,645363200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,681189888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,711333888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,747664384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,777905920,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,812289024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,848697088,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,877864448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,911946752,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,964591616,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682033,973344000,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,13382656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,51960832,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,77891328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,112025856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,147638016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,179844864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,211773184,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,252028672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,280393728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,311640064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,346922496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,378348032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,411443712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,445796608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,479119104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,500278528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,559286528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,566961152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,611458560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,650323200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,679268608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,711802368,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,745378304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,771014144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,811464192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,844611328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,878637312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,911930112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,948014080,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682034,977696000,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,11129344,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,49461760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,78797824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,111402240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,144793600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,181099008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,212116992,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,246288128,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,278978560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,313133056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,351391488,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,378870016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,411292928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,450381056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,479203584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,511301120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,561080576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,569321728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,613810688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,647053824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,679617280,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,711772160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,746349824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,778652160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,814568960,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,862341888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,870393600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,911488768,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,958452992,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682035,965532160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,12424192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,46929408,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,80359936,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,113310208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,148203520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,178740480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,214591744,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,260915712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,268467456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,311744768,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,358122496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,368203776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,411479808,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,448038144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,479938560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,512060160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,545702656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,565383680,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,612162816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,665920768,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,667873536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,711476480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,754042112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,778427904,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,811377664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,847370240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,879692032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,914024704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,949178112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682036,978002944,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,14582528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,57843968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,79708160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,112044288,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,163064320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,171528704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,212333568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,245576960,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,279631872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,311670272,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,345665792,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,378479616,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,416046080,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,450149888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,478817024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,511467008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,559165952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,569948928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,613846784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,645503232,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,682215424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,714024192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,755554304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,778846976,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,799450112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,850049536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,878531584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,912243712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,965666304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682037,976624640,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,13554688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,47470336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,67068928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,112064000,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,147207424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,178462208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,211831808,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,247365888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,278778112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,311895296,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,351762176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,379607552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,412187136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,463856128,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,471176192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,512236032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,546020864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,582853632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,613069568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,652952320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,678461952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,714208000,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,760796672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,770784512,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,813428224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,861756672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,869817856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,913715712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,946550784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682038,980776704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682039,12069120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682039,47049216,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682039,78833408,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682039,114717696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682039,149966592,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682039,180276736,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682039,212010240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682039,259262464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682039,268079360,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682039,314959872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682039,346130432,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682039,381626112,0.0,0.0,0.0,1.0,0.00026938109658658504,-0.00809188187122345,-0.0001024187877192162,0.3375019133090973,0.034369416534900665,0.14761614799499512 +1769682039,412721920,0.0,0.0,0.0,1.0,-0.00035969173768535256,-0.016518445685505867,-0.00025394049589522183,0.3379439413547516,0.03430526703596115,0.11886721104383469 +1769682039,447689728,0.0,0.0,0.0,1.0,-0.0005818635108880699,-0.02194395288825035,-0.000404674734454602,-0.17742310464382172,-0.2918454110622406,0.07594113051891327 +1769682039,478940416,0.0,0.0,0.0,1.0,-0.0006081858882680535,-0.023035304620862007,-0.0005132384249009192,-0.5163168907165527,-0.32599982619285583,0.028021538630127907 +1769682039,515946240,0.0,0.0,0.0,1.0,-0.0009474008693359792,-0.0208891611546278,-0.000608638278208673,-0.2444590926170349,0.38694119453430176,-0.010750520043075085 +1769682039,556187904,0.0,0.0,0.0,1.0,-0.0002921606646850705,-0.01575901173055172,-0.0006755596841685474,-0.5018238425254822,0.22375616431236267,-0.07131313532590866 +1769682039,578546176,0.0,0.0,0.0,1.0,-0.0005627862992696464,-0.01145839411765337,-0.0007374855922535062,-0.4204076826572418,0.09478022903203964,-0.06285697966814041 +1769682039,611490048,0.0,0.0,0.0,1.0,-0.0005657674046233296,-0.007538528181612492,-0.0007942421943880618,-0.5153895020484924,-0.3262360394001007,-0.05678831785917282 +1769682039,659447296,0.0,0.0,0.0,1.0,-9.850550122791901e-05,-0.0031791427172720432,-0.000838636769913137,-0.6783886551856995,-0.06831113249063492,-0.06478775292634964 +1769682039,668338176,0.0,0.0,0.0,1.0,0.00013132741150911897,-0.0016921334899961948,-0.0008711065747775137,-0.08115394413471222,0.1288900375366211,-0.040400128811597824 +1769682039,712194560,0.0,0.0,0.0,1.0,0.00018191267736256123,0.0005855263443663716,-0.000911933311726898,-0.502087414264679,0.22373177111148834,-0.052982695400714874 +1769682039,747727872,0.0,0.0,0.0,1.0,9.971555846277624e-05,0.0016063605435192585,-0.0009363461867906153,-0.678679883480072,-0.06830386072397232,-0.033799491822719574 +1769682039,783837440,0.0,0.0,0.0,1.0,0.0003128133830614388,0.0018264034297317266,-0.0009641830110922456,-0.33930903673171997,-0.03416863828897476,-0.019896946847438812 +1769682039,812576256,0.0,0.0,0.0,1.0,7.016367453616112e-05,0.001840367098338902,-0.0009940004674717784,-0.33923739194869995,-0.034194499254226685,-0.027067089453339577 +1769682039,849977088,0.0,0.0,0.0,1.0,0.0002884371788240969,0.0015900031430646777,-0.000998383853584528,-0.855323076248169,-0.3603861927986145,-0.005199396517127752 +1769682039,878766336,0.0,0.0,0.0,1.0,-2.1464140445459634e-05,0.001632452942430973,-0.0010123117826879025,-0.6789568662643433,-0.06832601130008698,-0.0041499980725348 +1769682039,914870528,0.0,0.0,0.0,1.0,0.0002813593891914934,0.0012187075335532427,-0.0010184957645833492,-0.6789554357528687,-0.06834826618432999,-0.004177185706794262 +1769682039,962689280,0.0,0.0,0.0,1.0,0.00021778490918222815,0.00024773101904429495,-0.0010611237958073616,-0.32640373706817627,0.5158461332321167,0.009919306263327599 +1769682039,970454272,0.0,0.0,0.0,1.0,0.0001323339674854651,-0.0003337480593472719,-0.001078074797987938,-0.8551831245422363,-0.3605138659477234,-0.014827065169811249 +1769682040,11732224,0.0,0.0,0.0,1.0,0.0003549540415406227,-0.0008469423046335578,-0.0010911674471572042,-0.5842890739440918,0.3526555001735687,0.0041639842092990875 +1769682040,69177856,0.0,0.0,0.0,1.0,0.00034832401433959603,-0.001418404863215983,-0.0011363574303686619,-0.08170859515666962,0.12897399067878723,0.012019244022667408 +1769682040,71721984,0.0,0.0,0.0,1.0,0.0003232717572245747,-0.0013625110732391477,-0.0011537193786352873,-0.0815359354019165,0.12893173098564148,-0.0058597382158041 +1769682040,112058112,0.0,0.0,0.0,1.0,0.0003759331302717328,-0.001081707770936191,-0.0011800017673522234,-0.8550586104393005,-0.3606662452220917,-0.021831147372722626 +1769682040,146454016,0.0,0.0,0.0,1.0,0.0003905893536284566,-0.0016885095974430442,-0.0012102695181965828,-0.6790058612823486,-0.06851477921009064,0.0031108781695365906 +1769682040,178842368,0.0,0.0,0.0,1.0,0.00048505133599974215,-0.0011416904162615538,-0.00123997638002038,-0.3393404185771942,-0.03430832549929619,-0.015119414776563644 +1769682040,212729344,0.0,0.0,0.0,1.0,0.0006080810562707484,-0.0007123039104044437,-0.0012431970098987222,-0.16303719580173492,0.2578158676624298,-0.020049061626195908 +1769682040,254289408,0.0,0.0,0.0,1.0,0.00031325058080255985,-0.0006703257095068693,-0.001299506169743836,-0.24486836791038513,0.38678163290023804,0.00032285554334521294 +1769682040,280650496,0.0,0.0,0.0,1.0,0.000682951183989644,-0.0005390279111452401,-0.001295479480177164,-0.24476909637451172,0.38674411177635193,-0.01160041056573391 +1769682040,311553024,0.0,0.0,0.0,1.0,0.0005352983134798706,-0.000362930673873052,-0.0013226141454651952,-0.2449101358652115,0.38676518201828003,0.0015102922916412354 +1769682040,366385664,0.0,0.0,0.0,1.0,0.0007594042108394206,-0.000299489387543872,-0.0013445165241137147,-0.5026733875274658,0.223460853099823,-0.00891678687185049 +1769682040,375312384,0.0,0.0,0.0,1.0,0.000754808948840946,-4.833695129491389e-05,-0.0013505641836673021,-1.2761310338974,-0.26639601588249207,-0.013940555974841118 +1769682040,412107520,0.0,0.0,0.0,1.0,0.00042632565600797534,0.0007807661895640194,-0.001350732403807342,-0.5027117729187012,0.22342711687088013,-0.006546205375343561 +1769682040,463079424,0.0,0.0,0.0,1.0,0.0009242973173968494,0.0014235057169571519,-0.0013400816824287176,-0.8420636653900146,0.18897132575511932,-0.020490160211920738 +1769682040,474602496,0.0,0.0,0.0,1.0,0.0006884371978230774,0.001594819943420589,-0.0013504758244380355,-0.760419487953186,0.060037676244974136,-0.019422363489866257 +1769682040,513824000,0.0,0.0,0.0,1.0,0.0009233758901245892,0.0017683780752122402,-0.0013495590537786484,-0.5028218626976013,0.22337990999221802,0.0017053843475878239 +1769682040,547593472,0.0,0.0,0.0,1.0,0.0004314800025895238,0.0015929453074932098,-0.0013484138762578368,-0.9365468621253967,-0.23226279020309448,-0.019308313727378845 +1769682040,578507008,0.0,0.0,0.0,1.0,0.0005760341882705688,0.0022949171252548695,-0.0013371609384194016,-0.5971701741218567,-0.1978207528591156,-0.008950884453952312 +1769682040,601486080,0.0,0.0,0.0,1.0,0.001076420652680099,0.0028309293556958437,-0.0012919943546876311,-0.7604363560676575,0.05991695821285248,-0.018414607271552086 +1769682040,664126976,0.0,0.0,0.0,1.0,0.0010342084569856524,0.005190538242459297,-0.0012265845434740186,-1.2756956815719604,-0.26694709062576294,-0.04795278608798981 +1769682040,671759616,0.0,0.0,0.0,1.0,0.0010028784163296223,0.007140820380300283,-0.0011401382507756352,-0.6781987547874451,-0.06918002665042877,-0.07117870450019836 +1769682040,700733440,0.0,0.0,0.0,1.0,0.0016273317160084844,0.007977897301316261,-0.0010855825385078788,-0.5845004320144653,0.352119505405426,-0.005868951324373484 +1769682040,757932544,0.0,0.0,0.0,1.0,0.001288138679228723,0.008662889711558819,-0.0009957668371498585,-1.0184217691421509,-0.1035521924495697,0.002303890883922577 +1769682040,769073408,0.0,0.0,0.0,1.0,0.0011063090059906244,0.00749201187863946,-0.0009894256945699453,-1.1128143072128296,-0.5247052907943726,0.007045680657029152 +1769682040,815112960,0.0,0.0,0.0,1.0,0.0010565012926235795,0.005886301398277283,-0.0009121369803324342,-0.8423380851745605,0.1886594593524933,-0.0017127329483628273 +1769682040,869888000,0.0,0.0,0.0,1.0,0.0012060124427080154,0.003923699259757996,-0.0008584587485529482,-0.9365319609642029,-0.23255470395088196,-0.012474246323108673 +1769682040,873987328,0.0,0.0,0.0,1.0,0.0012694321339949965,0.0037122436333447695,-0.0008234422421082854,-0.32694563269615173,0.5154818296432495,0.005452635232359171 +1769682040,912297472,0.0,0.0,0.0,1.0,0.0010591032914817333,0.0036800154484808445,-0.0007263976149260998,-0.8421714305877686,0.18854406476020813,-0.01757156290113926 +1769682040,949785600,0.0,0.0,0.0,1.0,0.001053106738254428,0.00422301609069109,-0.0006266169366426766,-1.100132703781128,0.025141075253486633,0.0011714864522218704 +1769682040,978572032,0.0,0.0,0.0,1.0,-0.00011821977386716753,0.0055561307817697525,-0.00046209667925722897,-0.9359028935432434,-0.23279234766960144,-0.06299804151058197 +1769682041,14001664,0.0,0.0,0.0,1.0,-0.0017592593794688582,0.007861296646296978,-0.0002847244613803923,-0.5019409656524658,0.2228948324918747,-0.08072234690189362 +1769682041,53171456,0.0,0.0,0.0,1.0,-0.002079625613987446,0.010242070071399212,-9.373789362143725e-05,-0.7596244812011719,0.05944867432117462,-0.08247292041778564 +1769682041,78659072,0.0,0.0,0.0,1.0,-0.0022834015544503927,0.011881958693265915,5.232020703260787e-05,-0.42063233256340027,0.09414955973625183,-0.04386637732386589 +1769682041,112680704,0.0,0.0,0.0,1.0,-0.002093879273161292,0.013447415083646774,0.00019299615814816207,-1.0176090002059937,-0.10391603410243988,-0.0597851537168026 +1769682041,150612480,0.0,0.0,0.0,1.0,-0.00234384648501873,0.013499977067112923,0.0003238021454308182,-0.33958983421325684,-0.03455611318349838,0.008489077910780907 +1769682041,171299584,0.0,0.0,0.0,1.0,-0.002272090408951044,0.012669498100876808,0.0003883840108755976,-0.08208145946264267,0.1289268136024475,0.024726679548621178 +1769682041,200558336,0.0,0.0,0.0,1.0,-0.002236292464658618,0.011723940260708332,0.00047759065637364984,-1.1004433631896973,0.025199629366397858,0.019730418920516968 +1769682041,266690048,0.0,0.0,0.0,1.0,-0.0028775206301361322,0.009722525253891945,0.0002765190147329122,-1.0188387632369995,-0.10362236201763153,0.02664749138057232 +1769682041,279589120,0.0,0.0,0.0,1.0,-0.0044122240506112576,0.005133772734552622,8.065062866080552e-05,-0.3429676294326782,-0.03403691202402115,0.22852300107479095 +1769682041,312080384,0.0,0.0,0.0,1.0,-0.004127432592213154,0.0009926698403432965,0.00023578126274514943,-1.1971454620361328,-0.39559033513069153,0.17446330189704895 +1769682041,354259456,0.0,0.0,0.0,1.0,-0.003654219675809145,-0.00238171243108809,0.0004298637213651091,-0.8568647503852844,-0.36115023493766785,0.12236663699150085 +1769682041,378787072,0.0,0.0,0.0,1.0,-0.0038007975090295076,-0.003295416245236993,0.0005312150460667908,-0.8434193134307861,0.18876251578330994,0.06671621650457382 +1769682041,414512640,0.0,0.0,0.0,1.0,-0.0037552257999777794,-0.003315775189548731,0.0006503126351162791,-1.0188812017440796,-0.10357965528964996,0.028933430090546608 +1769682041,451037440,0.0,0.0,0.0,1.0,-0.003400266170501709,-0.0023738311138004065,0.0007585170096717775,-0.8423613905906677,0.1886705607175827,-0.002194228582084179 +1769682041,478709760,0.0,0.0,0.0,1.0,-0.0034047355875372887,-0.0018830070039257407,0.0008276950102299452,-0.7603676319122314,0.05979364737868309,-0.02096867375075817 +1769682041,512204288,0.0,0.0,0.0,1.0,-0.003698502667248249,-0.0010559215443208814,0.0008878515800461173,-0.7600800395011902,0.05978316068649292,-0.04000402241945267 +1769682041,552282368,0.0,0.0,0.0,1.0,-0.0037776301614940166,0.0003323942655697465,0.0009673641761764884,-1.1811885833740234,0.15418481826782227,-0.04517846554517746 +1769682041,579981824,0.0,0.0,0.0,1.0,-0.0036319680511951447,0.0011199235450476408,0.0010285094613209367,-1.099433183670044,0.025340262800455093,-0.04859244078397751 +1769682041,612225792,0.0,0.0,0.0,1.0,-0.0038047032430768013,0.0018420073902234435,0.0010701949940994382,-1.0992522239685059,0.02536754310131073,-0.060562267899513245 +1769682041,657598720,0.0,0.0,0.0,1.0,-0.0037922263145446777,0.0023367032408714294,0.0011305951047688723,-0.40795114636421204,0.6444094181060791,-0.03296497091650963 +1769682041,682868224,0.0,0.0,0.0,1.0,-0.00397592643275857,0.002787070581689477,0.001169068505987525,-0.7601320147514343,0.05994774401187897,-0.03537491336464882 +1769682041,698441216,0.0,0.0,0.0,1.0,-0.0031888787634670734,0.003058764385059476,0.0011920906836166978,-1.0182439088821411,-0.10335659980773926,-0.015360753983259201 +1769682041,749657600,0.0,0.0,0.0,1.0,-0.0014334018342196941,0.004002212546765804,0.002052552532404661,-1.1823537349700928,0.1545577198266983,0.03422647342085838 +1769682041,779604480,0.0,0.0,0.0,1.0,-0.00043517202720977366,0.004940292797982693,0.0025176883209496737,-1.4399040937423706,-0.008670799434185028,0.015868816524744034 +1769682041,814586112,0.0,0.0,0.0,1.0,-0.0002991810324601829,0.005717388819903135,0.002823739079758525,-0.5030525922775269,0.22346337139606476,0.015840191394090652 +1769682041,859165952,0.0,0.0,0.0,1.0,8.781484211795032e-05,0.006367875728756189,0.0031041037291288376,-0.7606493234634399,0.06026593595743179,-0.00020028091967105865 +1769682041,870967296,0.0,0.0,0.0,1.0,-0.00010846026270883158,0.006632473319768906,0.00315488432534039,-0.4214310646057129,0.09463133662939072,0.01822792924940586 +1769682041,912493824,0.0,0.0,0.0,1.0,0.00048486102605238557,0.008098815567791462,0.0032917996868491173,-0.6663256883621216,0.481498658657074,0.022204970940947533 +1769682041,959129088,0.0,0.0,0.0,1.0,0.00045398963266052306,0.009245418012142181,0.003359869820997119,-0.8424186110496521,0.18946906924247742,0.010870948433876038 +1769682041,970955520,0.0,0.0,0.0,1.0,0.0007107359706424177,0.009624644182622433,0.0033757355995476246,-0.7611074447631836,0.06058431416749954,0.027663197368383408 +1769682042,14436864,0.0,0.0,0.0,1.0,0.0006521929753944278,0.009949381463229656,0.0033955934923142195,-0.9236832857131958,0.3185936510562897,-0.005433843471109867 +1769682042,95924736,0.0,0.0,0.0,1.0,0.0007878769538365304,0.010154248215258121,0.0033704896923154593,-0.8418806791305542,0.18973445892333984,-0.01739322766661644 +1769682042,98007552,0.0,0.0,0.0,1.0,0.0008536081295460463,0.010170763358473778,0.0033367243595421314,-1.3578135967254639,-0.13628560304641724,-0.020713940262794495 +1769682042,117401088,0.0,0.0,0.0,1.0,0.0006924096378497779,0.010037146508693695,0.003296742681413889,-0.9236575365066528,0.3189060688018799,-0.0016257800161838531 +1769682042,146598400,0.0,0.0,0.0,1.0,0.0008136892574839294,0.010268384590744972,0.0032462456729263067,-1.0047849416732788,0.4480139911174774,-0.02032734453678131 +1769682042,166163968,0.0,0.0,0.0,1.0,0.00046490764361806214,0.010169855318963528,0.0031848617363721132,-1.1813607215881348,0.1560981571674347,-0.01766655221581459 +1769682042,212120064,0.0,0.0,0.0,1.0,0.0006600644555874169,0.009888718836009502,0.0030771626625210047,-1.0189273357391357,-0.10176518559455872,0.01144273579120636 +1769682042,261508352,0.0,0.0,0.0,1.0,0.00043491640826687217,0.010288109071552753,0.0029446417465806007,-0.9368471503257751,-0.2306978404521942,-0.020623700693249702 +1769682042,270506752,0.0,0.0,0.0,1.0,0.00013742255396209657,0.010517796501517296,0.0028834345284849405,-0.6790802478790283,-0.06773227453231812,-0.0039104800671339035 +1769682042,315729152,0.0,0.0,0.0,1.0,0.00032129170722328126,0.010906916111707687,0.00276302732527256,-1.0183383226394653,-0.10149656236171722,-0.02060743421316147 +1769682042,348126208,0.0,0.0,0.0,1.0,-0.0021359645761549473,0.009320417419075966,0.0015906585613265634,-0.5852933526039124,0.35340210795402527,0.06626324355602264 +1769682042,379514112,0.0,0.0,0.0,1.0,-0.003234421368688345,0.008350210264325142,0.001113763777539134,-0.9386032223701477,-0.23037192225456238,0.06046391651034355 +1769682042,412504576,0.0,0.0,0.0,1.0,-0.00441170996055007,0.0073705376125872135,0.00037157273618504405,-1.1961175203323364,-0.39321187138557434,0.0285536777228117 +1769682042,450495232,0.0,0.0,0.0,1.0,-0.005465069320052862,0.007224510423839092,-0.00016361192683689296,-0.9377588033676147,-0.230394184589386,0.01810980960726738 +1769682042,467196672,0.0,0.0,0.0,1.0,-0.005932466592639685,0.007356821559369564,-0.00036364010884426534,-0.9373631477355957,-0.23040157556533813,6.879493594169617e-05 +1769682042,517232384,0.0,0.0,0.0,1.0,-0.0062245093286037445,0.0076059154234826565,-0.000659121316857636,-0.5979720950126648,-0.19663093984127045,0.009555891156196594 +1769682042,557021952,0.0,0.0,0.0,1.0,-0.006777750328183174,0.007966695353388786,-0.0008707264205440879,-0.5833562612533569,0.35334450006484985,-0.026020780205726624 +1769682042,578538496,0.0,0.0,0.0,1.0,-0.006915976293385029,0.008344719186425209,-0.0009942548349499702,-0.42100027203559875,0.09523409605026245,-0.0022734496742486954 +1769682042,611986176,0.0,0.0,0.0,1.0,-0.007152541074901819,0.008506895042955875,-0.0010951356962323189,-0.7604379057884216,0.06141361594200134,-0.010099625214934349 +1769682042,661170944,0.0,0.0,0.0,1.0,-0.007159385364502668,0.0087777990847826,-0.0011876651551574469,-0.5018450021743774,0.2242649644613266,-0.029270663857460022 +1769682042,673413632,0.0,0.0,0.0,1.0,-0.006804140284657478,0.00896378979086876,-0.0012392037315294147,-0.5019568800926208,0.22424724698066711,-0.02459079772233963 +1769682042,701107968,0.0,0.0,0.0,1.0,-0.0009009167551994324,0.005975453648716211,-0.0015252925222739577,-0.30631953477859497,1.066415786743164,-0.24681130051612854 +1769682042,746386688,0.0,0.0,0.0,1.0,0.012407698668539524,-0.004865741822868586,-0.001769709400832653,-0.7425401210784912,0.6113872528076172,-0.18984736502170563 +1769682042,782361856,0.0,0.0,0.0,1.0,0.01712026633322239,-0.009534835815429688,-0.0019360706210136414,-0.5000063180923462,0.22416779398918152,-0.1105109453201294 +1769682042,812984320,0.0,0.0,0.0,1.0,0.020386207848787308,-0.012390854768455029,-0.002135084243491292,-0.40567806363105774,0.645060122013092,-0.07861734926700592 +1769682042,848213504,0.0,0.0,0.0,1.0,0.024201001971960068,-0.01411316730082035,-0.0024794992059469223,-0.8414735794067383,0.19005568325519562,-0.03212796896696091 +1769682042,879065856,0.0,0.0,0.0,1.0,0.025842195376753807,-0.014287249185144901,-0.002785429125651717,-0.9239702224731445,0.31905078887939453,0.011340170167386532 +1769682042,918121984,0.0,0.0,0.0,1.0,0.02743050828576088,-0.013777795247733593,-0.003101971233263612,-1.100563406944275,0.026974769309163094,0.014445202425122261 +1769682042,966776320,0.0,0.0,0.0,1.0,0.02849261462688446,-0.01311273593455553,-0.003550398861989379,-0.5030561089515686,0.22397381067276,0.01840302348136902 +1769682042,969018624,0.0,0.0,0.0,1.0,0.02883300743997097,-0.012527101673185825,-0.0037764583248645067,-0.679253101348877,-0.06815614551305771,0.006522379815578461 +1769682043,11999488,0.0,0.0,0.0,1.0,0.029072705656290054,-0.01202415581792593,-0.004184754099696875,-0.4218449592590332,0.09501461684703827,0.03506132960319519 +1769682043,68529152,0.0,0.0,0.0,1.0,0.032873183488845825,-0.013789480552077293,-0.004523620940744877,-0.16587218642234802,0.2588290274143219,0.13446055352687836 +1769682043,70641152,0.0,0.0,0.0,1.0,0.03374062478542328,-0.014799782074987888,-0.004641740117222071,-0.5994186401367188,-0.196660116314888,0.1019386500120163 +1769682043,112501504,0.0,0.0,0.0,1.0,0.034379031509160995,-0.01674557849764824,-0.004898052662611008,-0.7621399760246277,0.06099871173501015,0.0769726037979126 +1769682043,148651776,0.0,0.0,0.0,1.0,0.034426163882017136,-0.020090533420443535,-0.004998228047043085,-0.34165874123573303,-0.03315107896924019,0.11938727647066116 +1769682043,195656192,0.0,0.0,0.0,1.0,0.03466359153389931,-0.021999439224600792,-0.00504649942740798,-0.08320341259241104,0.1298840045928955,0.08651059120893478 +1769682043,216336896,0.0,0.0,0.0,1.0,0.034300945699214935,-0.02315700426697731,-0.005144429858773947,-1.1010937690734863,0.02609393559396267,0.05403999611735344 +1769682043,249314560,0.0,0.0,0.0,1.0,0.03441901132464409,-0.023972153663635254,-0.0052864630706608295,-0.5032747983932495,0.22344745695590973,0.018820246681571007 +1769682043,278817280,0.0,0.0,0.0,1.0,0.034298498183488846,-0.02397025376558304,-0.005410392303019762,-0.5970343351364136,-0.19823546707630157,-0.00842639897018671 +1769682043,313944064,0.0,0.0,0.0,1.0,0.032286178320646286,-0.02374717779457569,-0.006314204540103674,-0.6778183579444885,-0.07057933509349823,-0.0765494629740715 +1769682043,362656000,0.0,0.0,0.0,1.0,0.011599941179156303,-0.034241706132888794,-0.009583726525306702,-0.34798526763916016,-0.5893890857696533,-0.27148929238319397 +1769682043,372835840,0.0,0.0,0.0,1.0,0.003084193216636777,-0.03937715291976929,-0.011774932965636253,0.16487017273902893,-0.2591342031955719,-0.09267989546060562 +1769682043,402473472,0.0,0.0,0.0,1.0,-0.00033129664370790124,-0.03138050064444542,-0.01331030111759901,-0.8567053079605103,-0.3591372072696686,0.21480681002140045 +1769682043,445948416,0.0,0.0,0.0,1.0,-0.0025100745260715485,-0.02056029997766018,-0.014577101916074753,-0.9381565451622009,-0.2311473786830902,0.2019454538822174 +1769682043,483740672,0.0,0.0,0.0,1.0,-0.004398165736347437,-0.014487141743302345,-0.01516970805823803,-0.9375008344650269,-0.23237690329551697,0.1547059565782547 +1769682043,500572416,0.0,0.0,0.0,1.0,-0.00447291461750865,-0.01156783476471901,-0.015417689457535744,-0.16556403040885925,0.2597256302833557,0.14802654087543488 +1769682043,552570368,0.0,0.0,0.0,1.0,-0.0051895370706915855,-0.006983380299061537,-0.015699148178100586,-0.9362066388130188,-0.23516015708446503,0.049177780747413635 +1769682043,565238784,0.0,0.0,0.0,1.0,-0.005796246696263552,-0.005501755513250828,-0.01569990999996662,-0.6786863803863525,-0.07167685776948929,0.007155942730605602 +1769682043,612154112,0.0,0.0,0.0,1.0,-0.0053075277246534824,-0.0034282421693205833,-0.015587467700242996,-0.3390445411205292,-0.03655815124511719,-0.028558077290654182 +1769682043,658463488,0.0,0.0,0.0,1.0,-0.004842557944357395,-0.004851440899074078,-0.015429454855620861,-0.25688210129737854,-0.16475093364715576,0.0015854928642511368 +1769682043,675653632,0.0,0.0,0.0,1.0,-0.00413181446492672,-0.008050528354942799,-0.015101291239261627,-0.6784715056419373,-0.07300151884555817,-0.0032645324245095253 +1769682043,712623872,0.0,0.0,0.0,1.0,0.008375382982194424,-0.004356165416538715,-0.012511327862739563,-0.9032288789749146,1.4038101434707642,-0.5440205931663513 +1769682043,748436736,0.0,0.0,0.0,1.0,0.022571509703993797,0.004527695011347532,-0.008568769320845604,-0.4090571701526642,0.6342720985412598,-0.46306219696998596 +1769682043,769977600,0.0,0.0,0.0,1.0,0.027186043560504913,0.008230683393776417,-0.007048598490655422,-0.24437075853347778,0.37819838523864746,-0.4089401960372925 +1769682043,812493824,0.0,0.0,0.0,1.0,0.03464248403906822,0.013280688785016537,-0.00476027000695467,-0.667415976524353,0.47182631492614746,-0.25633442401885986 +1769682043,850071552,0.0,0.0,0.0,1.0,0.03973208740353584,0.01588299311697483,-0.0032376155722886324,-0.24683836102485657,0.38274601101875305,-0.11349183320999146 +1769682043,879690496,0.0,0.0,0.0,1.0,0.04232413321733475,0.016265233978629112,-0.0024624248035252094,-0.33032411336898804,0.512730598449707,-0.02578648179769516 +1769682043,913712896,0.0,0.0,0.0,1.0,0.04389994591474533,0.01588083617389202,-0.0019488749094307423,-0.0743773803114891,0.6791952848434448,0.029592974111437798 +1769682043,949588224,0.0,0.0,0.0,1.0,0.04498798027634621,0.014558946713805199,-0.001536308554932475,-1.018450379371643,-0.10908801853656769,0.07855410873889923 +1769682043,966529280,0.0,0.0,0.0,1.0,0.04576031491160393,0.013534543104469776,-0.001460220548324287,-0.5880541205406189,0.3498213291168213,0.07541533559560776 +1769682044,13090304,0.0,0.0,0.0,1.0,0.04617849364876747,0.011481409892439842,-0.0015057820128276944,-0.6793386936187744,-0.0718717873096466,0.08104485273361206 +1769682044,50744320,0.0,0.0,0.0,1.0,0.04558455944061279,0.009930710308253765,-0.0017849182477220893,-0.9355717897415161,-0.23782137036323547,0.056271303445100784 +1769682044,68443136,0.0,0.0,0.0,1.0,0.04548210650682449,0.009344291873276234,-0.0019803389441221952,-0.5964316725730896,-0.2006363421678543,0.06057710573077202 +1769682044,102892288,0.0,0.0,0.0,1.0,0.04480283707380295,0.008802901022136211,-0.0024548883084207773,-0.42225518822669983,0.09210638701915741,0.027581673115491867 +1769682044,145985280,0.0,0.0,0.0,1.0,0.044114112854003906,0.00839245319366455,-0.002997476141899824,-0.9349967837333679,-0.23929527401924133,0.011237205937504768 +1769682044,180992768,0.0,0.0,0.0,1.0,0.04370160028338432,0.008352411910891533,-0.003394391853362322,-0.8523440361022949,-0.36732861399650574,0.02155476063489914 +1769682044,213332480,0.0,0.0,0.0,1.0,0.043068673461675644,0.008534306660294533,-0.003764789318665862,-0.3392980694770813,-0.0368705615401268,0.00865820050239563 +1769682044,248295680,0.0,0.0,0.0,1.0,0.01896626502275467,0.022700056433677673,-0.004452027380466461,-0.5870365500450134,-0.22475063800811768,-0.6013877987861633 +1769682044,295713280,0.0,0.0,0.0,1.0,0.004598565399646759,0.026578370481729507,-0.005566941574215889,-0.5304561257362366,-1.4275448322296143,0.12341952323913574 +1769682044,316119808,0.0,0.0,0.0,1.0,0.003968176897615194,0.017214076593518257,-0.005997879896312952,-0.18006663024425507,-0.27834904193878174,0.42028599977493286 +1769682044,371316992,0.0,0.0,0.0,1.0,0.00041475327452644706,0.006980790290981531,-0.006357864011079073,-0.08880741894245148,0.14199434220790863,0.3703218102455139 +1769682044,381223424,0.0,0.0,0.0,1.0,-0.0019970741122961044,0.001248016720637679,-0.006584553513675928,-0.5177707076072693,-0.3194326162338257,0.32440295815467834 +1769682044,400929536,0.0,0.0,0.0,1.0,-0.0026489384472370148,-0.0016326520126312971,-0.006729624234139919,-0.5167035460472107,-0.3218514621257782,0.2612679600715637 +1769682044,466486272,0.0,0.0,0.0,1.0,-0.0037473649717867374,-0.005852805450558662,-0.0070754108019173145,-0.16821527481079102,0.2617645561695099,0.14517714083194733 +1769682044,476774912,0.0,0.0,0.0,1.0,-0.0046583907678723335,-0.006531291641294956,-0.007340980228036642,-0.24929232895374298,0.3854048550128937,0.022517690435051918 +1769682044,513973760,0.0,0.0,0.0,1.0,-0.005608824547380209,-0.0058998363092541695,-0.00760216498747468,-0.5964095592498779,-0.20098981261253357,0.07560111582279205 +1769682044,547636992,0.0,0.0,0.0,1.0,-0.004850372672080994,-0.0030587748624384403,-0.0077573820017278194,-0.16543389856815338,0.25473958253860474,-0.04280655086040497 +1769682044,579086080,0.0,0.0,0.0,1.0,-0.004098329693078995,-0.0009952634572982788,-0.007840175181627274,-0.42118436098098755,0.08782055974006653,-0.06452172994613647 +1769682044,602490368,0.0,0.0,0.0,1.0,-0.0036981089506298304,0.0003155340673401952,-0.007860766723752022,-0.5944952964782715,-0.2055615782737732,-0.03870445489883423 +1769682044,652424704,0.0,0.0,0.0,1.0,-0.0026262153405696154,0.0025766727048903704,-0.007897640578448772,-0.6769692897796631,-0.07907651364803314,-0.07682421803474426 +1769682044,681627904,0.0,0.0,0.0,1.0,-0.0021665345411747694,0.0033852877095341682,-0.007973574101924896,-0.6773696541786194,-0.07825078815221786,-0.049496181309223175 +1769682044,712697856,0.0,0.0,0.0,1.0,-0.0015665395185351372,0.00408877432346344,-0.0080306027084589,-0.7672781348228455,-0.4997193515300751,-0.018021566793322563 +1769682044,758744064,0.0,0.0,0.0,1.0,-0.0010049301199615002,0.004061270970851183,-0.008166056126356125,-0.7610159516334534,0.05040838569402695,-0.021032294258475304 +1769682044,771433472,0.0,0.0,0.0,1.0,-0.0011107644531875849,0.0041134716011583805,-0.008230708539485931,-0.08321473002433777,0.12787412106990814,-0.0035070618614554405 +1769682044,812482304,0.0,0.0,0.0,1.0,0.00043029856169596314,0.004471151623874903,-0.008240636438131332,-0.3321990966796875,0.5095584392547607,-0.06530175358057022 +1769682044,846908160,0.0,0.0,0.0,1.0,0.0010405578650534153,0.004767398815602064,-0.00825920607894659,-0.5942381620407104,-0.20632591843605042,-0.027387138456106186 +1769682044,867213824,0.0,0.0,0.0,1.0,0.0014336199965327978,0.0046767923049628735,-0.008292063139379025,-0.5054466128349304,0.21640659868717194,-0.019619803875684738 +1769682044,912427008,0.0,0.0,0.0,1.0,0.0020081358961760998,0.0046705398708581924,-0.008351154625415802,-0.08367764204740524,0.12845967710018158,0.015482046641409397 +1769682044,952273152,0.0,0.0,0.0,1.0,0.0024931838270276785,0.004295472055673599,-0.008436297997832298,-0.42230135202407837,0.08857300877571106,-0.00908932276070118 +1769682044,981229568,0.0,0.0,0.0,1.0,0.0024927554186433554,0.004314782097935677,-0.00851772353053093,-0.16684992611408234,0.25541162490844727,-0.008437370881438255 +1769682045,12488448,0.0,0.0,0.0,1.0,0.0026513587217777967,0.004100817255675793,-0.00860843900591135,-0.3394263684749603,-0.03819088637828827,0.02659541927278042 +1769682045,51590144,0.0,0.0,0.0,1.0,0.0025138866622000933,0.004100722726434469,-0.008670155890285969,-0.42282581329345703,0.08915495127439499,0.016918303444981575 +1769682045,80544768,0.0,0.0,0.0,1.0,-0.003914522472769022,0.008075904101133347,-0.00870407372713089,-0.3456501364707947,-0.5853482484817505,0.12483371794223785 +1769682045,112524800,0.0,0.0,0.0,1.0,-0.006802773103117943,0.011119646020233631,-0.008818513713777065,-0.17336051166057587,-0.29153361916542053,0.09566420316696167 +1769682045,165629952,0.0,0.0,0.0,1.0,-0.008948172442615032,0.013419950380921364,-0.00887211225926876,-0.5948227047920227,-0.20554929971694946,0.03468829765915871 +1769682045,176739072,0.0,0.0,0.0,1.0,-0.010985098779201508,0.015044140629470348,-0.008907150477170944,-0.9330185055732727,-0.24667522311210632,-0.0016669351607561111 +1769682045,213086208,0.0,0.0,0.0,1.0,-0.011689763516187668,0.015290874056518078,-0.008904422633349895,-0.3390009105205536,-0.039565619081258774,0.004402040969580412 +1769682045,262163712,0.0,0.0,0.0,1.0,-0.01316765695810318,0.015309715643525124,-0.008945389650762081,-0.16731347143650055,0.2548234164714813,-0.014467254281044006 +1769682045,285475072,0.0,0.0,0.0,1.0,-0.01569599285721779,0.014905297197401524,-0.00906321220099926,-0.3393196165561676,-0.039216913282871246,0.020676741376519203 +1769682045,301684736,0.0,0.0,0.0,1.0,-0.01559152640402317,0.01363416388630867,-0.009137739427387714,-0.8465458750724792,0.17698848247528076,0.05056603252887726 +1769682045,346559744,0.0,0.0,0.0,1.0,-0.016533134505152702,0.010945114307105541,-0.009327803738415241,-0.17218941450119019,-0.29352667927742004,0.05368547886610031 +1769682045,379405824,0.0,0.0,0.0,1.0,-0.01672499068081379,0.01012877095490694,-0.009469619952142239,-0.5938673615455627,-0.20787768065929413,0.0034560877829790115 +1769682045,418441984,0.0,0.0,0.0,1.0,-0.016551963984966278,0.00945114903151989,-0.009592779912054539,-0.5937047004699707,-0.20820096135139465,-0.0015817619860172272 +1769682045,458506752,0.0,0.0,0.0,1.0,-0.015970664098858833,0.009235158562660217,-0.009755418635904789,-0.5068392753601074,0.21444277465343475,-0.003625893034040928 +1769682045,480585472,0.0,0.0,0.0,1.0,-0.01574096269905567,0.009305956773459911,-0.009806475602090359,-0.33880484104156494,-0.04058220237493515,-0.001613069325685501 +1769682045,513985280,0.0,0.0,0.0,1.0,-0.017709892243146896,0.010029797442257404,-0.012168225832283497,-0.1682104766368866,0.2548570930957794,-0.0007739751599729061 +1769682045,558905600,0.0,0.0,0.0,1.0,-0.006333354394882917,0.0036242548376321793,-0.011761708185076714,0.0074094124138355255,0.5436043739318848,-0.22946198284626007 +1769682045,571543296,0.0,0.0,0.0,1.0,-0.0031669633463025093,-0.0004026693932246417,-0.01055779680609703,-0.16445152461528778,0.24970583617687225,-0.17103251814842224 +1769682045,614188288,0.0,0.0,0.0,1.0,-0.0004115944029763341,-0.006270089186728001,-0.008729798719286919,-0.08141088485717773,0.12370187044143677,-0.1236175149679184 +1769682045,646834688,0.0,0.0,0.0,1.0,0.001059725065715611,-0.009318866766989231,-0.007544280961155891,-0.08251702785491943,0.12500827014446259,-0.07832521945238113 +1769682045,682696704,0.0,0.0,0.0,1.0,0.0019412680994719267,-0.010269910097122192,-0.006977915298193693,-0.2520976662635803,0.380767285823822,-0.03835786506533623 +1769682045,712591872,0.0,0.0,0.0,1.0,0.0022936430759727955,-0.010358097031712532,-0.006643788889050484,0.08566281944513321,0.4231931269168854,0.002487808931618929 +1769682045,753290240,0.0,0.0,0.0,1.0,0.002498228568583727,-0.009470665827393532,-0.00644235173240304,-0.42347806692123413,0.08639691025018692,0.016888609156012535 +1769682045,779184640,0.0,0.0,0.0,1.0,0.0025322139263153076,-0.008641545660793781,-0.006418908946216106,-0.3396424949169159,-0.04015842825174332,0.042832400649785995 +1769682045,854785280,0.0,0.0,0.0,1.0,-0.003057517111301422,-0.010963156819343567,-0.007702221628278494,-0.09088991582393646,-0.41549623012542725,0.25855115056037903 +1769682045,870551808,0.0,0.0,0.0,1.0,-0.008517423644661903,-0.014697746373713017,-0.009054840542376041,-0.34282201528549194,-0.03573068231344223,0.20035888254642487 +1769682045,878705408,0.0,0.0,0.0,1.0,-0.011340383440256119,-0.016568008810281754,-0.00979275070130825,-0.8496600985527039,-0.3757268190383911,0.12983578443527222 +1769682045,899479808,0.0,0.0,0.0,1.0,-0.012877140194177628,-0.01747516356408596,-0.010184308513998985,-0.5947747230529785,-0.20788981020450592,0.09920887649059296 +1769682045,946252032,0.0,0.0,0.0,1.0,-0.015531686134636402,-0.01840122416615486,-0.010957368649542332,-0.339557409286499,-0.040630318224430084,0.04840574041008949 +1769682045,976464640,0.0,0.0,0.0,1.0,-0.016465984284877777,-0.01851610839366913,-0.011192960664629936,-0.5084632039070129,-0.3376322388648987,0.02382561005651951 +1769682046,13157632,0.0,0.0,0.0,1.0,-0.017530661076307297,-0.018166977912187576,-0.011536285281181335,-0.7612924575805664,0.041654594242572784,-0.03376275300979614 +1769682046,61526528,0.0,0.0,0.0,1.0,-0.02013825811445713,-0.017676346004009247,-0.010946578346192837,0.5078948736190796,0.33847755193710327,-0.010974064469337463 +1769682046,69278976,0.0,0.0,0.0,1.0,-0.02107791043817997,-0.01772712916135788,-0.009649734012782574,7.981507224030793e-05,-0.00012361930566839874,-0.004766103811562061 +1769682046,114405888,0.0,0.0,0.0,1.0,-0.01906486786901951,-0.018008360639214516,-0.007689529564231634,-0.08458889275789261,0.1266150325536728,-0.01288729626685381 +1769682046,150141440,0.0,0.0,0.0,1.0,-0.017415395006537437,-0.017672793939709663,-0.006255496758967638,-0.5504459738731384,-0.0002142135053873062,0.014228842221200466 +1769682046,179814912,0.0,0.0,0.0,1.0,-0.01681523211300373,-0.016665905714035034,-0.005427278112620115,-0.6352578997612,0.12653428316116333,0.012604955583810806 +1769682046,212658432,0.0,0.0,0.0,1.0,-0.015920715406537056,-0.016080858185887337,-0.004768869373947382,0.08465132117271423,-0.12653087079524994,0.014909610152244568 +1769682046,258580480,0.0,0.0,0.0,1.0,-0.015657013282179832,-0.006320989690721035,-0.004002251662313938,-0.7479875087738037,-0.5304917693138123,-0.9331483840942383 +1769682046,267818240,0.0,0.0,0.0,1.0,-0.0072839530184865,-0.00042109392234124243,-0.005400886293500662,-0.5877519845962524,0.32872140407562256,-0.39478859305381775 +1769682046,314642688,0.0,0.0,0.0,1.0,-0.0012584271607920527,0.006008808966726065,-0.006805035751312971,-0.6731858849525452,-0.09211187064647675,-0.27325332164764404 +1769682046,347116288,0.0,0.0,0.0,1.0,-0.0010806104401126504,0.009339611977338791,-0.007728532422333956,-0.0828968808054924,0.12354855984449387,-0.14468657970428467 +1769682046,381208064,0.0,0.0,0.0,1.0,-0.001246239640749991,0.01001538522541523,-0.008286776021122932,-0.04077679663896561,-0.21324467658996582,-0.06615862250328064 +1769682046,412968192,0.0,0.0,0.0,1.0,-0.0015357688535004854,0.009663049131631851,-0.008750849403440952,-0.08496981859207153,0.1266741156578064,-0.004110403824597597 +1769682046,451868416,0.0,0.0,0.0,1.0,-0.0018439809791743755,0.00805803295224905,-0.009215953759849072,-0.0008551346254535019,0.0012529826490208507,0.056007884442806244 +1769682046,479519232,0.0,0.0,0.0,1.0,-0.0019887860398739576,0.006586150731891394,-0.009471118450164795,0.16697163879871368,0.29867106676101685,0.0805932879447937 +1769682046,516469504,0.0,0.0,0.0,1.0,-0.0020228151697665453,0.005016669165343046,-0.009618275798857212,-0.086577869951725,0.12871593236923218,0.09118414670228958 +1769682046,557797632,0.0,0.0,0.0,1.0,-0.002408920554444194,0.0034613017924129963,-0.009705431759357452,-0.29817625880241394,0.16977980732917786,0.07380391657352448 +1769682046,579449856,0.0,0.0,0.0,1.0,-0.0022909753024578094,0.0025089059490710497,-0.00970787275582552,0.12563447654247284,0.08651924133300781,0.059717874974012375 +1769682046,612569600,0.0,0.0,0.0,1.0,-0.0006945792702026665,-0.0002353734744247049,-0.009563238359987736,0.16874811053276062,0.29583948850631714,-0.056301042437553406 +1769682046,661017856,0.0,0.0,0.0,1.0,-0.0023386997636407614,-0.0045256055891513824,-0.009566491469740868,0.08627430349588394,-0.12789508700370789,-0.060221124440431595 +1769682046,670382336,0.0,0.0,0.0,1.0,-0.001578735071234405,-0.00575944222509861,-0.009450986050069332,0.16819046437740326,0.29646506905555725,-0.03247256204485893 +1769682046,732853760,0.0,0.0,0.0,1.0,-0.0002665573265403509,-0.006530363578349352,-0.009039533324539661,-0.21115945279598236,0.040161941200494766,-0.04588824883103371 +1769682046,745804544,0.0,0.0,0.0,1.0,1.818475720938295e-05,-0.0065312995575368404,-0.008782690390944481,-0.1263829916715622,-0.08549748361110687,-0.0048323748633265495 +1769682046,783858944,0.0,0.0,0.0,1.0,0.00043653647298924625,-0.0059580388478934765,-0.00847635604441166,0.04075165465474129,0.21221043169498444,0.013855486176908016 +1769682046,815229952,0.0,0.0,0.0,1.0,0.0009185961680486798,-0.005510371644049883,-0.008220799267292023,-0.3386034667491913,-0.04405297711491585,0.019772592931985855 +1769682046,848610816,0.0,0.0,0.0,1.0,-8.277107554022223e-05,-0.005439789034426212,-0.008176393806934357,0.2518619894981384,0.17235109210014343,0.060739289969205856 +1769682046,879282688,0.0,0.0,0.0,1.0,-0.001153328688815236,-0.0056084515526890755,-0.0081937862560153,-0.0005020800163038075,0.0007565675769001245,0.03455884009599686 +1769682046,915500800,0.0,0.0,0.0,1.0,-0.0018396144732832909,-0.005864973645657301,-0.008240241557359695,-0.4243395924568176,0.08232440799474716,0.032652348279953 +1769682046,956880896,0.0,0.0,0.0,1.0,-0.0027517976704984903,-0.005825096741318703,-0.008482521399855614,-0.000387523730751127,0.0005958908586762846,0.027408940717577934 +1769682046,981132800,0.0,0.0,0.0,1.0,-0.003211495466530323,-0.005690309219062328,-0.008872020989656448,-0.0002164464385714382,0.0003352973726578057,0.015492125414311886 +1769682047,12931072,0.0,0.0,0.0,1.0,-0.00394235597923398,-0.005730911158025265,-0.009389429353177547,-0.2977043390274048,0.16695864498615265,0.0018362877890467644 +1769682047,64286208,0.0,0.0,0.0,1.0,-0.0042170509696006775,-0.00573074771091342,-0.010128903202712536,0.12638843059539795,0.08547724783420563,-0.012033620849251747 +1769682047,71650560,0.0,0.0,0.0,1.0,-0.0046245944686234,-0.005737206898629665,-0.010514184832572937,-0.25710421800613403,0.3783491849899292,-0.01866433396935463 +1769682047,112809472,0.0,0.0,0.0,1.0,-0.004327458795160055,-0.005707764998078346,-0.011178193613886833,-0.21185018122196198,0.040140971541404724,-0.01200135052204132 +1769682047,149410304,0.0,0.0,0.0,1.0,-0.003854733658954501,-0.0057245478965342045,-0.0116534773260355,0.08601926267147064,-0.12636566162109375,-0.009351608343422413 +1769682047,180968192,0.0,0.0,0.0,1.0,-0.0033412750344723463,-0.005683044902980328,-0.011859632097184658,-0.16615548729896545,-0.2981412410736084,-0.007857004180550575 +1769682047,214180352,0.0,0.0,0.0,1.0,-0.00323736690916121,-0.005716943182051182,-0.011899827979505062,-0.126010000705719,-0.08605962246656418,-0.004588721785694361 +1769682047,247298304,0.0,0.0,0.0,1.0,-0.0026716331485658884,-0.005647934507578611,-0.011719896458089352,0.040164198726415634,0.2117905467748642,-0.014591449871659279 +1769682047,279141376,0.0,0.0,0.0,1.0,-0.0008441485115326941,-0.0033853754866868258,-0.011173957027494907,-0.12471865862607956,-0.08819426596164703,-0.10347145050764084 +1769682047,317534976,0.0,0.0,0.0,1.0,-0.0029716866556555033,0.0006814716034568846,-0.010793638415634632,-0.4620875418186188,-0.1355520635843277,-0.15794965624809265 +1769682047,355675904,0.0,0.0,0.0,1.0,-0.002848717151209712,0.004347043111920357,-0.010237806476652622,-0.25123265385627747,-0.1733568161725998,-0.05088762938976288 +1769682047,379195392,0.0,0.0,0.0,1.0,-0.0019195745699107647,0.005287694279104471,-0.009836161509156227,-0.2513088285923004,-0.17321136593818665,-0.04021043702960014 +1769682047,412718336,0.0,0.0,0.0,1.0,-0.002134912647306919,0.00552163552492857,-0.009494980797171593,0.12613028287887573,0.08584597706794739,-0.019196730107069016 +1769682047,461868032,0.0,0.0,0.0,1.0,-0.002493535866960883,0.0051908306777477264,-0.009178878739476204,0.12571394443511963,0.08649381250143051,0.01063158642500639 +1769682047,469157120,0.0,0.0,0.0,1.0,-0.0021272727753967047,0.00481471698731184,-0.00905747339129448,-0.03990500792860985,-0.2115757167339325,0.02995505928993225 +1769682047,514745600,0.0,0.0,0.0,1.0,-0.0023139650002121925,0.004116037394851446,-0.008825545199215412,-0.04726514592766762,0.3385292589664459,0.02480710856616497 +1769682047,548134400,0.0,0.0,0.0,1.0,-0.0026152394711971283,0.0032146144658327103,-0.008667810820043087,-0.3777490556240082,-0.25855401158332825,0.031048323959112167 +1769682047,581364480,0.0,0.0,0.0,1.0,-0.0022259210236370564,0.0026139223482459784,-0.00849922839552164,0.2512513995170593,0.17322136461734772,0.019060416147112846 +1769682047,613623808,0.0,0.0,0.0,1.0,-0.002245228737592697,0.002202418865635991,-0.008308209478855133,-0.00032515142811462283,0.00046970456605777144,0.02383505180478096 +1769682047,650556928,0.0,0.0,0.0,1.0,-0.0010736332042142749,0.001329431775957346,-0.007926068268716335,-0.08583135157823563,0.12475761771202087,-0.050130702555179596 +1769682047,679687168,0.0,0.0,0.0,1.0,0.0006555491709150374,-0.0022698440589010715,-0.00756949232891202,0.5518479347229004,0.0056945085525512695,-0.12372098863124847 +1769682047,716227840,0.0,0.0,0.0,1.0,-0.0003180234634783119,-0.0061892191879451275,-0.007361353375017643,0.12707141041755676,0.08451531827449799,-0.10367901623249054 +1769682047,753724928,0.0,0.0,0.0,1.0,-0.0008676145225763321,-0.009662630967795849,-0.007139013614505529,0.1659153699874878,0.29700589179992676,-0.09425125271081924 +1769682047,780526080,0.0,0.0,0.0,1.0,-0.0012462702579796314,-0.011064746417105198,-0.006941451691091061,-0.047006845474243164,0.33694979548454285,-0.05012401193380356 +1769682047,813103104,0.0,0.0,0.0,1.0,-0.000265141308773309,-0.011330009438097477,-0.006634608376771212,0.12574003636837006,0.08642994612455368,-0.010840295813977718 +1769682047,854576384,0.0,0.0,0.0,1.0,-0.00010444257350172848,-0.010681577026844025,-0.00625515216961503,0.0863339751958847,-0.12503573298454285,0.029722273349761963 +1769682047,879515392,0.0,0.0,0.0,1.0,0.0003430734504945576,-0.009884601458907127,-0.006043287459760904,-0.2990884482860565,0.1646486073732376,0.007553237024694681 +1769682047,914082816,0.0,0.0,0.0,1.0,0.0003523963678162545,-0.009069767780601978,-0.005883354227989912,-0.039072416722774506,-0.21186059713363647,0.022768761962652206 +1769682047,947035904,0.0,0.0,0.0,1.0,-0.00042196258436888456,-0.008875411935150623,-0.005966423079371452,-0.000707741011865437,0.0012349854223430157,0.06316493451595306 +1769682047,983950336,0.0,0.0,0.0,1.0,-0.0011911365436390042,-0.0092110401019454,-0.0060150823555886745,0.12496788799762726,0.08774644881486893,0.049734219908714294 +1769682048,15117312,0.0,0.0,0.0,1.0,-0.0015494480030611157,-0.00951224472373724,-0.006000582594424486,-0.04861404746770859,0.33874285221099854,0.04535054787993431 +1769682048,50893312,0.0,0.0,0.0,1.0,-0.0021953529212623835,-0.00972192082554102,-0.005881773307919502,0.0383029468357563,0.21295951306819916,0.03203582763671875 +1769682048,79179520,0.0,0.0,0.0,1.0,-0.0021637254394590855,-0.009853377006947994,-0.005703261587768793,-0.29930442571640015,0.16436143219470978,0.011722439900040627 +1769682048,115536128,0.0,0.0,0.0,1.0,-0.0024059091228991747,-0.009773089550435543,-0.0055182212963700294,0.12552981078624725,0.08670397102832794,-0.008798506110906601 +1769682048,157581824,0.0,0.0,0.0,1.0,-0.002976605435833335,-0.009671500883996487,-0.005286520346999168,0.00016638585657346994,-0.0003419874410610646,-0.017877358943223953 +1769682048,182011904,0.0,0.0,0.0,1.0,-0.0031673945486545563,-0.009563050232827663,-0.005122724454849958,-0.125265970826149,-0.08722861111164093,-0.01616278663277626 +1769682048,212926720,0.0,0.0,0.0,1.0,-0.0031980739440768957,-0.00949935708194971,-0.004996865522116423,0.00017706991638988256,-0.0003837646800093353,-0.020261183381080627 +1769682048,263594752,0.0,0.0,0.0,1.0,-0.003166157053783536,-0.009332550689578056,-0.0048361485823988914,0.12553556263446808,0.08661825209856033,-0.018464671447873116 +1769682048,272795648,0.0,0.0,0.0,1.0,-0.002903869142755866,-0.009311058558523655,-0.004735011141747236,2.8917609597556293e-05,-6.692696479149163e-05,-0.003575537819415331 +1769682048,313358848,0.0,0.0,0.0,1.0,-0.0020861169323325157,-0.008914854377508163,-0.004520726390182972,0.038945119827985764,0.2109660506248474,-0.07635888457298279 +1769682048,347725824,0.0,0.0,0.0,1.0,-0.0003434991231188178,-0.0038512784522026777,-0.004169900435954332,-0.33588331937789917,-0.05317171663045883,-0.24121376872062683 +1769682048,381629696,0.0,0.0,0.0,1.0,-0.0011256884317845106,1.5161134797381237e-05,-0.004058096557855606,-0.33620190620422363,-0.05248833820223808,-0.2018716186285019 +1769682048,413614848,0.0,0.0,0.0,1.0,-0.0012428418267518282,0.0030249394476413727,-0.003959945868700743,-0.2111918181180954,0.03539739549160004,-0.1560756266117096 +1769682048,447243520,0.0,0.0,0.0,1.0,-0.0014679167652502656,0.005338422954082489,-0.003804492764174938,-0.38576236367225647,0.2870844900608063,-0.10013265162706375 +1769682048,479675392,0.0,0.0,0.0,1.0,-0.00032122674747370183,0.005464629270136356,-0.003671014681458473,0.0383947491645813,0.2119724005460739,-0.023883694782853127 +1769682048,515773184,0.0,0.0,0.0,1.0,-6.577942258445546e-06,0.004877825733274221,-0.0035554911009967327,-0.00024194778234232217,0.0005508069880306721,0.029796268790960312 +1769682048,552247296,0.0,0.0,0.0,1.0,-2.2373027604771778e-05,0.0038089517038315535,-0.0033984759356826544,0.17371277511119843,-0.2494214028120041,0.06447665393352509 +1769682048,579719424,0.0,0.0,0.0,1.0,-0.0003110886609647423,0.0028801513835787773,-0.0033192832488566637,0.0867207944393158,-0.12438254803419113,0.04952850192785263 +1769682048,612779008,0.0,0.0,0.0,1.0,5.3730913350591436e-05,0.0019793289247900248,-0.0032902436796575785,-0.1257680058479309,-0.08602921664714813,0.06014314666390419 +1769682048,666255872,0.0,0.0,0.0,1.0,-7.21076867193915e-05,0.0011136147659271955,-0.0032436372712254524,-0.00037580414209514856,0.0008151526562869549,0.04409833252429962 +1769682048,675630592,0.0,0.0,0.0,1.0,-0.0001760259474394843,0.0008838421781547368,-0.0032327028457075357,0.08694743365049362,-0.12477279454469681,0.02689650095999241 +1769682048,713865472,0.0,0.0,0.0,1.0,-0.0015818008687347174,0.0003796683740802109,-0.003349258564412594,0.21241940557956696,-0.038076967000961304,0.00013782666064798832 +1769682048,747872000,0.0,0.0,0.0,1.0,-0.002377444878220558,-0.00014885648852214217,-0.0033932970836758614,0.12516221404075623,0.08732011169195175,0.006623637862503529 +1769682048,780532224,0.0,0.0,0.0,1.0,-0.0029672530945390463,-0.00047684682067483664,-0.003394933184608817,-0.12535741925239563,-0.08689676225185394,0.017207486554980278 +1769682048,815930112,0.0,0.0,0.0,1.0,-0.0032937023788690567,-0.0006694020703434944,-0.0033469584304839373,0.3375769555568695,0.049339305609464645,0.006756337359547615 +1769682048,858105088,0.0,0.0,0.0,1.0,-0.0035667407792061567,-0.0004480522475205362,-0.0032334753777831793,0.1253669708967209,0.08686543256044388,-0.020768040791153908 +1769682048,879495168,0.0,0.0,0.0,1.0,-0.0037037371657788754,-0.0005010571330785751,-0.0031617656350135803,0.12504398822784424,0.08754201978445053,0.016187181696295738 +1769682048,919402240,0.0,0.0,0.0,1.0,-0.0014381872024387121,0.0004913210868835449,-0.0027328936848789454,-0.212687686085701,0.03844954073429108,0.02850312553346157 +1769682048,957943040,0.0,0.0,0.0,1.0,-0.000423324090661481,0.0017616106197237968,-0.002300403779372573,0.16304154694080353,0.29975825548171997,0.0008243530755862594 +1769682048,967055104,0.0,0.0,0.0,1.0,-0.0004969009896740317,0.002265537390485406,-0.002145172795280814,-0.03803673014044762,-0.21213306486606598,0.018950628116726875 +1769682049,12908544,0.0,0.0,0.0,1.0,0.0004649737384170294,0.0027611972764134407,-0.0018979753367602825,-0.1745138168334961,0.2501975893974304,-0.009553862735629082 +1769682049,57871360,0.0,0.0,0.0,1.0,0.0003151193377561867,0.002787723671644926,-0.0018462209263816476,-0.04952583089470863,0.33777251839637756,0.0066593424417078495 +1769682049,71392768,0.0,0.0,0.0,1.0,0.00014450632443185896,0.002669622888788581,-0.0018459203420206904,0.33755338191986084,0.04953339695930481,0.005693784914910793 +1769682049,113104384,0.0,0.0,0.0,1.0,0.00020291260443627834,0.0023930727038532495,-0.001854565809480846,-6.425708124879748e-05,0.00012746930588036776,0.007151137106120586 +1769682049,148845568,0.0,0.0,0.0,1.0,0.00012913576210848987,0.0019544237293303013,-0.0018737342907115817,0.12492049485445023,0.08773898333311081,0.02341526746749878 +1769682049,183933952,0.0,0.0,0.0,1.0,0.00019457025337032974,0.0017090006731450558,-0.0018826195737347007,0.12519705295562744,0.08719349652528763,-0.007566394284367561 +1769682049,213902336,0.0,0.0,0.0,1.0,0.00023295448045246303,0.001661414047703147,-0.001887702033855021,-2.187191421398893e-05,4.2512448999332264e-05,0.0023837080225348473 +1769682049,248982016,0.0,0.0,0.0,1.0,-0.0002432269393466413,0.001381654990836978,-0.0019023478962481022,3.3024916774593294e-05,-6.376562669174746e-05,-0.0035755597054958344 +1769682049,279448064,0.0,0.0,0.0,1.0,-0.0002466622681822628,0.00123108911793679,-0.0019180836388841271,0.2124052345752716,-0.03765663504600525,0.007411088794469833 +1769682049,316302592,0.0,0.0,0.0,1.0,-0.00013464876974467188,0.0011734487488865852,-0.0019397949799895287,0.12511025369167328,0.0873519703745842,-0.0003922387259081006 +1769682049,355079424,0.0,0.0,0.0,1.0,-0.0005482463166117668,0.0008960868581198156,-0.002003271132707596,-8.920896652853116e-05,0.0001698869455140084,0.009534819051623344 +1769682049,367723264,0.0,0.0,0.0,1.0,-0.0014680895255878568,0.0011678561568260193,-0.002109596272930503,-0.21225471794605255,0.037322185933589935,-0.02411654219031334 +1769682049,413149440,0.0,0.0,0.0,1.0,-0.0027272962033748627,0.0018155076541006565,-0.0023025753907859325,0.2126167118549347,-0.037980347871780396,-0.014012688770890236 +1769682049,467838464,0.0,0.0,0.0,1.0,-0.0033607662189751863,0.002179419621825218,-0.0024168225936591625,-0.12486789375543594,-0.08778806775808334,-0.02230207808315754 +1769682049,478321920,0.0,0.0,0.0,1.0,-0.004186644684523344,0.002843882655724883,-0.002452912973240018,0.08735333383083344,-0.12498701363801956,0.006597629748284817 +1769682049,513776640,0.0,0.0,0.0,1.0,-0.004760566633194685,0.003333891974762082,-0.0024934234097599983,6.941251922398806e-05,-0.0001237928809132427,-0.007151153404265642 +1769682049,547899648,0.0,0.0,0.0,1.0,-0.005278883036226034,0.0036251803394407034,-0.0025062449276447296,0.03758295625448227,0.21257884800434113,0.003887401893734932 +1769682049,583193344,0.0,0.0,0.0,1.0,-0.0034746499732136726,0.0026328249368816614,-0.0025379417929798365,-0.08786801993846893,0.12579834461212158,0.042298175394535065 +1769682049,613524736,0.0,0.0,0.0,1.0,-0.002571867546066642,0.001678181579336524,-0.0025403096806257963,-0.0006672546151094139,0.0011283603962510824,0.06674455851316452 +1769682049,651232768,0.0,0.0,0.0,1.0,-0.002386349020525813,0.0006491245003417134,-0.002549236873164773,-0.00026325020007789135,0.0004407480591908097,0.026221035048365593 +1769682049,666341120,0.0,0.0,0.0,1.0,-0.0019047276582568884,0.00023664627224206924,-0.0025604115799069405,-0.12535881996154785,-0.08692001551389694,0.03239072486758232 +1769682049,717778688,0.0,0.0,0.0,1.0,-0.0012182332575321198,-0.0003210660070180893,-0.002555878134444356,-0.00011971704952884465,0.00019906804664060473,0.011918674223124981 +1769682049,759984896,0.0,0.0,0.0,1.0,-0.0008221714524552226,-0.0005314364680089056,-0.002562023466452956,-0.212680846452713,0.03782437741756439,0.0163146760314703 +1769682049,771245824,0.0,0.0,0.0,1.0,-0.0005802276427857578,-0.00048751680878922343,-0.002588982693850994,3.58109173248522e-05,-5.953048457740806e-05,-0.003575606271624565 +1769682049,813595904,0.0,0.0,0.0,1.0,-0.0002955766976810992,-0.0005152568337507546,-0.0026328079402446747,-0.08743209391832352,0.12487922608852386,-0.008912485092878342 +1769682049,859547648,0.0,0.0,0.0,1.0,-5.7152126828441396e-05,-0.0004153694899287075,-0.0026737269945442677,-0.04980133846402168,0.337099552154541,-0.0275613684207201 +1769682049,870165248,0.0,0.0,0.0,1.0,0.00019456389418337494,-0.0003079746966250241,-0.002698203781619668,-0.13743843138217926,0.46223950386047363,-0.01978343352675438 +1769682049,913644032,0.0,0.0,0.0,1.0,8.622936729807407e-05,-0.0001714501267997548,-0.0027504281606525183,0.037490468472242355,0.21243378520011902,-0.00673338770866394 +1769682049,949422336,0.0,0.0,0.0,1.0,9.92763671092689e-06,-0.00010390098032075912,-0.002811802551150322,0.12502993643283844,0.08745332062244415,-0.006169082596898079 +1769682049,982635520,0.0,0.0,0.0,1.0,6.553063576575369e-05,0.00010987679706886411,-0.0028076174203306437,-0.30000364780426025,0.16221323609352112,-0.01164831779897213 +1769682050,13639424,0.0,0.0,0.0,1.0,0.00046549830585718155,0.000228428456466645,-0.0027916538529098034,-0.12499149143695831,-0.08751386404037476,0.0037865499034523964 +1769682050,48580096,0.0,0.0,0.0,1.0,0.0006348887109197676,0.0004991197492927313,-0.0027909644413739443,-0.037276528775691986,-0.21266652643680573,-0.006368191912770271 +1769682050,81010944,0.0,0.0,0.0,1.0,0.0004705706378445029,0.0005532598006539047,-0.0028164659161120653,0.00011929706670343876,-0.00019873687415383756,-0.011918683536350727 +1769682050,117970688,0.0,0.0,0.0,1.0,0.00033999717561528087,0.0005692074191756546,-0.0028477704618126154,0.037276167422533035,0.21261334419250488,0.0027880240231752396 +1769682050,151896576,0.0,0.0,0.0,1.0,-0.000249994162004441,0.00018994453421328217,-0.003011808032169938,-0.03745468333363533,-0.2122795581817627,0.01747490093111992 +1769682050,168070400,0.0,0.0,0.0,1.0,-0.0001297907583648339,7.042653305688873e-05,-0.003098458983004093,0.03708234801888466,0.21287864446640015,0.018281402066349983 +1769682050,213036288,0.0,0.0,0.0,1.0,-0.0007172154146246612,-0.0003755705838557333,-0.0032221416477113962,0.12497623264789581,0.08752749115228653,-0.007357658818364143 +1769682050,261969408,0.0,0.0,0.0,1.0,-0.0007487966795451939,-0.00044581954716704786,-0.0033012907952070236,1.1952481145272031e-05,-1.9824563423753716e-05,-0.0011918689124286175 +1769682050,283305728,0.0,0.0,0.0,1.0,-0.0011200432199984789,-0.0005569419590756297,-0.003364156698808074,-0.1248602569103241,-0.08771516382694244,-0.0021787635050714016 +1769682050,299518976,0.0,0.0,0.0,1.0,-0.0010236029047518969,-0.0005271381814964116,-0.0033809731248766184,-0.12485436350107193,-0.08772352337837219,-0.0021792154293507338 +1769682050,347144960,0.0,0.0,0.0,1.0,-0.0012405990855768323,-0.0004502591327764094,-0.0034147053956985474,-0.4250873327255249,0.07422620803117752,-0.007854225113987923 +1769682050,386021632,0.0,0.0,0.0,1.0,-0.000779231486376375,-0.00010489493433851749,-0.0034080669283866882,0.00019029001123271883,-0.00031445379136130214,-0.019069956615567207 +1769682050,413124352,0.0,0.0,0.0,1.0,-0.0006525904755108058,7.821850886102766e-05,-0.0033954866230487823,0.16216321289539337,0.29996785521507263,-0.02239750511944294 +1769682050,449825536,0.0,0.0,0.0,1.0,-0.0008071373449638486,0.0003266959683969617,-0.003428225638344884,7.145789277274162e-05,-0.00011753793660318479,-0.007151239085942507 +1769682050,480102912,0.0,0.0,0.0,1.0,-0.00025054728030227125,0.0003333714557811618,-0.003431183286011219,-0.161960631608963,-0.30022287368774414,0.009272577241063118 +1769682050,514117120,0.0,0.0,0.0,1.0,-0.0002704146027099341,0.00043320725671947,-0.0034377845004200935,0.21263547241687775,-0.037114545702934265,-0.003222367260605097 +1769682050,565619968,0.0,0.0,0.0,1.0,-0.0005117395194247365,0.0005367855192162097,-0.0034775398671627045,-0.12480315566062927,-0.08779086172580719,0.00018653844017535448 +1769682050,574864384,0.0,0.0,0.0,1.0,-0.0005599195719696581,0.000721067248377949,-0.00349634001031518,0.08782666176557541,-0.12482764571905136,-0.0006487423088401556 +1769682050,601031424,0.0,0.0,0.0,1.0,-0.0005635607521981001,0.0006835149833932519,-0.0035280624870210886,0.05065498873591423,-0.3370850086212158,0.02152736485004425 +1769682050,655711744,0.0,0.0,0.0,1.0,-0.0003850462380796671,0.0006286694551818073,-0.003577857743948698,0.12472392618656158,0.0879128947854042,0.004593655467033386 +1769682050,665691648,0.0,0.0,0.0,1.0,-0.00012497084389906377,0.0005546158645302057,-0.0036115495022386312,-0.30059584975242615,0.1619107574224472,0.011003161780536175 +1769682050,704380928,0.0,0.0,0.0,1.0,-0.0005402110400609672,0.0001655461237533018,-0.003644570242613554,0.1248134970664978,0.08776473253965378,-0.006129146087914705 +1769682050,746630912,0.0,0.0,0.0,1.0,-0.0009017789852805436,-0.0002104664163198322,-0.003705278504639864,-0.3374922573566437,-0.05081231892108917,0.01171373762190342 +1769682050,813801472,0.0,0.0,0.0,1.0,-0.0007851985283195972,-0.0005317730247043073,-0.003728399286046624,-0.03680100664496422,-0.21267767250537872,-0.0016785621410235763 +1769682050,815830272,0.0,0.0,0.0,1.0,-0.0008098644902929664,-0.0006434055976569653,-0.0037601867225021124,0.08794330060482025,-0.12477332353591919,-0.001851043663918972 +1769682050,856601088,0.0,0.0,0.0,1.0,-0.0010543897515162826,-0.0005341885262168944,-0.0037901627365499735,0.12481532990932465,0.08775333315134048,-0.010894550010561943 +1769682050,867826944,0.0,0.0,0.0,1.0,-0.0009199813939630985,-0.0006971778930164874,-0.003790240501984954,0.12461631745100021,0.08807194232940674,0.008175335824489594 +1769682050,913074432,0.0,0.0,0.0,1.0,-0.0013636794174090028,-0.0005621794844046235,-0.003778597805649042,-0.2126295119524002,0.03670724108815193,-0.002731612417846918 +1769682050,961755136,0.0,0.0,0.0,1.0,-0.0010874932631850243,-0.0005183013272471726,-0.0037527570966631174,-0.08803301304578781,0.12476499378681183,0.004259271547198296 +1769682050,972520704,0.0,0.0,0.0,1.0,-0.001134630641900003,-0.00048083701403811574,-0.00375121901743114,-0.2125900685787201,0.03658273071050644,-0.007489623036235571 +1769682051,13717760,0.0,0.0,0.0,1.0,-0.0013145571574568748,-0.0004472786094993353,-0.0037508581299334764,-0.0880608856678009,0.1247449517250061,0.004270025994628668 +1769682051,50011392,0.0,0.0,0.0,1.0,-0.0008075676742009819,-0.0003133787540718913,-0.0036853658966720104,-0.00013103391393087804,0.00020990974735468626,0.013110695406794548 +1769682051,83005952,0.0,0.0,0.0,1.0,-0.0003008721978403628,-2.9216631446615793e-05,-0.0036190066020935774,-0.16136033833026886,-0.3004860281944275,0.0151186753064394 +1769682051,113906176,0.0,0.0,0.0,1.0,-8.590488869231194e-05,0.0002179963339585811,-0.0035723885521292686,0.0363963283598423,0.2129511535167694,0.016034340485930443 +1769682051,150282496,0.0,0.0,0.0,1.0,5.0259350246051326e-05,0.00044883761438541114,-0.0035849171690642834,0.21259038150310516,-0.03640526905655861,0.009865515865385532 +1769682051,179867904,0.0,0.0,0.0,1.0,3.131869016215205e-05,0.000565685739275068,-0.003644295735284686,-4.7837769670877606e-05,7.627726154169068e-05,0.0047675250098109245 +1769682051,219624960,0.0,0.0,0.0,1.0,0.00014626991469413042,0.00046859600115567446,-0.0037431276869028807,0.3373318314552307,0.05150582268834114,-0.0045877303928136826 +1769682051,259592704,0.0,0.0,0.0,1.0,8.745735976845026e-05,0.00026985263684764504,-0.0038797094020992517,0.036465395241975784,0.2126840204000473,-0.0018451064825057983 +1769682051,272496384,0.0,0.0,0.0,1.0,0.00013290741480886936,0.00024347232829313725,-0.003952591214329004,-0.21270237863063812,0.03646170347929001,-0.0003419418353587389 +1769682051,314373120,0.0,0.0,0.0,1.0,5.1943614380434155e-05,0.00015024458116386086,-0.004091672599315643,6.01020255999174e-05,-9.540297469357029e-05,-0.0059594023041427135 +1769682051,366801408,0.0,0.0,0.0,1.0,7.744885078864172e-05,7.409342651953921e-05,-0.004192659631371498,-0.08808955550193787,0.1244213730096817,-0.008841775357723236 +1769682051,376104704,0.0,0.0,0.0,1.0,0.0001222965947818011,0.00016414659330621362,-0.00425150478258729,0.12468581646680832,0.08793080598115921,-0.015648791566491127 +1769682051,413108480,0.0,0.0,0.0,1.0,-0.0003775650402531028,0.0004281705478206277,-0.004305196460336447,-0.12442167848348618,-0.08834732323884964,-0.00938313826918602 +1769682051,447313408,0.0,0.0,0.0,1.0,-0.0005588686908595264,0.000800976762548089,-0.004341105930507183,-0.12438192218542099,-0.08840670436620712,-0.011772653087973595 +1769682051,483056128,0.0,0.0,0.0,1.0,-0.0006690745940431952,0.0009183203219436109,-0.004361703991889954,0.0362812764942646,0.21269863843917847,-0.0030241303611546755 +1769682051,514812672,0.0,0.0,0.0,1.0,-0.0011623486643657088,0.0010005882941186428,-0.004391204100102186,-0.3370610475540161,-0.05225071310997009,-0.015721069648861885 +1769682051,549228544,0.0,0.0,0.0,1.0,-0.0010611442849040031,0.0012303589610382915,-0.004416791722178459,0.00024424970615655184,-0.0003782764251809567,-0.0238376222550869 +1769682051,579906304,0.0,0.0,0.0,1.0,-0.001271162647753954,0.001205941429361701,-0.00448014959692955,-0.3371293544769287,-0.05222182720899582,-0.00740942545235157 +1769682051,614728192,0.0,0.0,0.0,1.0,-0.0014294879510998726,0.001380787929520011,-0.004506625700742006,-0.21290311217308044,0.03637625277042389,0.013919666409492493 +1769682051,656379392,0.0,0.0,0.0,1.0,-0.0022027846425771713,0.0016178588848561049,-0.004546568728983402,0.12436249852180481,0.08842058479785919,0.0058646732941269875 +1769682051,667546880,0.0,0.0,0.0,1.0,0.0003465178597252816,0.0007101750234141946,-0.004437379539012909,-0.051623065024614334,0.3362087309360504,-0.06423594057559967 +1769682051,713800448,0.0,0.0,0.0,1.0,0.0018668785924091935,-0.00395518634468317,-0.004229058511555195,0.3023119866847992,-0.16225871443748474,-0.1123528778553009 +1769682051,765276928,0.0,0.0,0.0,1.0,0.002497732173651457,-0.008864525705575943,-0.00415502255782485,0.03670283034443855,0.211665540933609,-0.0709502175450325 +1769682051,775452416,0.0,0.0,0.0,1.0,0.0024830298498272896,-0.011033953167498112,-0.004136295989155769,-0.08801155537366867,0.12374408543109894,-0.040983639657497406 +1769682051,813892096,0.0,0.0,0.0,1.0,0.00250478507950902,-0.01240650936961174,-0.004093199502676725,0.036278266459703445,0.2122172862291336,-0.03644246980547905 +1769682051,847602432,0.0,0.0,0.0,1.0,0.0027371689211577177,-0.013019231148064137,-0.004070150665938854,0.12425479292869568,0.08860412985086441,0.010404800064861774 +1769682051,896965376,0.0,0.0,0.0,1.0,0.0030101966112852097,-0.012902508489787579,-0.00402858154848218,-0.12442004680633545,-0.08829165995121002,0.009913839399814606 +1769682051,905440256,0.0,0.0,0.0,1.0,0.002945070154964924,-0.012612242251634598,-0.004044132772833109,-0.08876287937164307,0.12492584437131882,0.03539741039276123 +1769682051,950418688,0.0,0.0,0.0,1.0,0.002939588390290737,-0.011810177937150002,-0.004054342862218618,-0.12437736243009567,-0.08834429830312729,0.008848002180457115 +1769682051,980636160,0.0,0.0,0.0,1.0,0.0026415041647851467,-0.011227995157241821,-0.004114980343729258,0.03580278158187866,0.21279461681842804,-0.0020573895890265703 +1769682052,18264576,0.0,0.0,0.0,1.0,0.0028722223360091448,-0.01092575117945671,-0.004195652436465025,-0.017047781497240067,0.5500823259353638,0.0062592471949756145 +1769682052,58144768,0.0,0.0,0.0,1.0,0.002565186470746994,-0.010450680740177631,-0.004338480532169342,0.08842107653617859,-0.12397319823503494,0.01933886483311653 +1769682052,69092864,0.0,0.0,0.0,1.0,0.002630722476169467,-0.010441841557621956,-0.004434401169419289,0.03565104305744171,0.21298742294311523,0.008582918904721737 +1769682052,114415616,0.0,0.0,0.0,1.0,0.0020155685488134623,-0.010470219887793064,-0.004682862665504217,7.752105011604726e-05,-0.00022074744629207999,-0.013110943138599396 +1769682052,167725568,0.0,0.0,0.0,1.0,0.0011463164119049907,-0.01096212025731802,-0.00496217655017972,-0.12413842976093292,-0.0888865739107132,-0.01707838848233223 +1769682052,176651776,0.0,0.0,0.0,1.0,0.0006674713222309947,-0.011606400832533836,-0.005271001718938351,-0.12410334497690201,-0.08899326622486115,-0.021786915138363838 +1769682052,214003712,0.0,0.0,0.0,1.0,0.00045171749661676586,-0.011955136433243752,-0.0054121180437505245,0.24846720695495605,0.17705953121185303,-0.013728484511375427 +1769682052,247762432,0.0,0.0,0.0,1.0,0.00020175593090243638,-0.01236746460199356,-0.005533698946237564,0.21285606920719147,-0.03554457053542137,-0.000867912545800209 +1769682052,268187648,0.0,0.0,0.0,1.0,-0.0002738015027716756,-0.0124539565294981,-0.00560934841632843,-0.33712664246559143,-0.05276796966791153,0.024563174694776535 +1769682052,313898496,0.0,0.0,0.0,1.0,-0.0012057648273184896,-0.01289868913590908,-0.005763832945376635,0.12410761415958405,0.08892156183719635,0.012054329738020897 +1769682052,356923648,0.0,0.0,0.0,1.0,0.003695983672514558,-0.010872023180127144,-0.005402715411037207,0.07120658457279205,0.4234393537044525,-0.13929365575313568 +1769682052,380355072,0.0,0.0,0.0,1.0,0.0030257608741521835,-0.00650895107537508,-0.0052976468577980995,-0.08819902688264847,0.12076815217733383,-0.19783996045589447 +1769682052,414478336,0.0,0.0,0.0,1.0,0.003258239012211561,-0.0029767765663564205,-0.005244352389127016,-0.21234093606472015,0.03192802891135216,-0.1990417242050171 +1769682052,451327488,0.0,0.0,0.0,1.0,0.003567703301087022,-0.00010074293095385656,-0.0051514701917767525,0.00030987279023975134,-0.0019950219430029392,-0.11561545729637146 +1769682052,479774208,0.0,0.0,0.0,1.0,0.0033217419404536486,0.0009560594917275012,-0.0051459358073771,-0.21271473169326782,0.03410082310438156,-0.06674239039421082 +1769682052,513377536,0.0,0.0,0.0,1.0,0.003383347298949957,0.0014838875504210591,-0.005158145911991596,-0.1423535943031311,0.4602954089641571,-0.045389313250780106 +1769682052,544295936,0.0,0.0,0.0,1.0,0.003209856338799,0.0014579580165445805,-0.0052542248740792274,-1.9980441720690578e-05,0.00012558864546008408,0.007151431404054165 +1769682052,582632192,0.0,0.0,0.0,1.0,0.002995643997564912,0.0009116504224948585,-0.005583304446190596,0.17764681577682495,-0.24724699556827545,0.047798123210668564 +1769682052,613608960,0.0,0.0,0.0,1.0,0.002721767872571945,0.00046476873103529215,-0.0057832179591059685,-0.12412695586681366,-0.08817871659994125,0.041747868061065674 +1769682052,648284416,0.0,0.0,0.0,1.0,0.0030238195322453976,-0.00042849197052419186,-0.0059783183969557285,-0.03511966019868851,-0.21248896420001984,0.026348628103733063 +1769682052,681986560,0.0,0.0,0.0,1.0,0.004659936763346195,-0.002281083958223462,-0.006072487682104111,0.42585232853889465,-0.06993499398231506,0.006036118604242802 +1769682052,707896832,0.0,0.0,0.0,1.0,0.004816789645701647,-0.004221535753458738,-0.006186909042298794,0.2479238063097,0.17788031697273254,-0.006129333283752203 +1769682052,747514112,0.0,0.0,0.0,1.0,0.005113794934004545,-0.006048159208148718,-0.006273272912949324,-0.2670278549194336,0.371664434671402,-0.01105847954750061 +1769682052,780491776,0.0,0.0,0.0,1.0,0.004569062497466803,-0.006628280505537987,-0.006272614933550358,0.05421530082821846,-0.33729687333106995,-0.019870666787028313 +1769682052,817535488,0.0,0.0,0.0,1.0,0.0039495560340583324,-0.0063271853141486645,-0.006227047182619572,0.034916527569293976,0.21225976943969727,-0.03964586555957794 +1769682052,864080896,0.0,0.0,0.0,1.0,0.0038678785786032677,-0.005765003617852926,-0.006153320427983999,-0.2128995954990387,0.03407992050051689,-0.038002386689186096 +1769682052,871236096,0.0,0.0,0.0,1.0,0.0038151098415255547,-0.005404303781688213,-0.00610570190474391,-0.12383319437503815,-0.08945436775684357,-0.01761108636856079 +1769682052,913735680,0.0,0.0,0.0,1.0,0.0035919388756155968,-0.004825611133128405,-0.006016937550157309,2.4445107555948198e-05,-0.0002942777646239847,-0.01549440436065197 +1769682052,963251200,0.0,0.0,0.0,1.0,0.0034963423386216164,-0.004417855758219957,-0.005928858648985624,0.24764584004878998,0.17833071947097778,-0.0018718186765909195 +1769682052,970182912,0.0,0.0,0.0,1.0,0.0032390051055699587,-0.004239344969391823,-0.005919403396546841,-1.885714300442487e-05,0.00027444944134913385,0.014302479103207588 +1769682053,13470976,0.0,0.0,0.0,1.0,0.002877984195947647,-0.004031057003885508,-0.005893264897167683,0.03457073122262955,0.21312545239925385,0.004270520061254501 +1769682053,48062720,0.0,0.0,0.0,1.0,0.002743830904364586,-0.004006430506706238,-0.005874537397176027,-0.08924684673547745,0.12386126816272736,0.003465439658612013 +1769682053,85405952,0.0,0.0,0.0,1.0,0.0029464743565768003,-0.004051324911415577,-0.005834643263369799,-0.03449809551239014,-0.2128380686044693,0.011277788318693638 +1769682053,114077952,0.0,0.0,0.0,1.0,0.002945146057754755,-0.0040737660601735115,-0.005787390749901533,0.21302549540996552,-0.034491054713726044,-0.0015446408651769161 +1769682053,153005312,0.0,0.0,0.0,1.0,0.002745454665273428,-0.004115986172109842,-0.005664255004376173,0.0,-0.0,0.0 +1769682053,180358144,0.0,0.0,0.0,1.0,0.0014346904354169965,-0.0046349880285561085,-0.005484344437718391,0.24740540981292725,0.17868287861347198,-0.001032671658322215 +1769682053,216071936,0.0,0.0,0.0,1.0,0.000560771964956075,-0.005387214943766594,-0.005407373420894146,-0.03433067351579666,-0.2131904810667038,-0.005326245911419392 +1769682053,255607296,0.0,0.0,0.0,1.0,0.00020940459216944873,-0.006089157424867153,-0.005193283781409264,1.6669509932398796e-06,-0.00033084943424910307,-0.016686031594872475 +1769682053,280912640,0.0,0.0,0.0,1.0,9.917710849549621e-05,-0.0064018419943749905,-0.005016706418246031,0.08939933776855469,-0.12391478568315506,-0.011858150362968445 +1769682053,314231296,0.0,0.0,0.0,1.0,-5.266985681373626e-05,-0.006527474615722895,-0.004817286040633917,-0.15786509215831757,-0.3024671673774719,0.003658855566754937 +1769682053,368527872,0.0,0.0,0.0,1.0,0.0019278193358331919,-0.005491460207849741,-0.004473288077861071,0.034166380763053894,0.2118866890668869,-0.06145784631371498 +1769682053,376118272,0.0,0.0,0.0,1.0,0.0017854656325653195,-0.0032141206320375204,-0.004154966212809086,0.12355943769216537,0.08768043667078018,-0.09005653113126755 +1769682053,399266048,0.0,0.0,0.0,1.0,0.0021405392326414585,-0.002372896997258067,-0.004059717059135437,-0.0341838113963604,-0.21441270411014557,-0.06484893709421158 +1769682053,447159808,0.0,0.0,0.0,1.0,0.0023712378460913897,-0.0010441674385219812,-0.003973336890339851,-0.0554269440472126,0.33581259846687317,-0.046052027493715286 +1769682053,470721792,0.0,0.0,0.0,1.0,0.0025582413654774427,-0.0006197342881932855,-0.003932307008653879,-0.12358912825584412,-0.08969900012016296,-0.008832830004394054 +1769682053,513666816,0.0,0.0,0.0,1.0,0.0028320075944066048,-0.00038320390740409493,-0.0038764108903706074,-0.08951961994171143,0.12361561506986618,0.0011426707496866584 +1769682053,548939776,0.0,0.0,0.0,1.0,0.002945384243503213,-0.0005879865493625402,-0.0037536185700446367,-0.15756309032440186,-0.30249786376953125,0.009858932346105576 +1769682053,580294144,0.0,0.0,0.0,1.0,0.0032109010498970747,-0.0008524364675395191,-0.003573874244466424,0.30267202854156494,-0.1570170372724533,0.026817981153726578 +1769682053,614168576,0.0,0.0,0.0,1.0,0.003211777191609144,-0.0010584697593003511,-0.003409632947295904,9.838724508881569e-06,0.0002449959865771234,0.011918415315449238 +1769682053,656985856,0.0,0.0,0.0,1.0,0.0038571960758417845,-0.0017904604319483042,-0.0031064501963555813,0.12353742122650146,0.08990763872861862,0.014722548425197601 +1769682053,682085376,0.0,0.0,0.0,1.0,0.003631558269262314,-0.002435416914522648,-0.0028998316265642643,-0.33662956953048706,-0.05578039586544037,-0.004481317475438118 +1769682053,746948352,0.0,0.0,0.0,1.0,0.003211663570255041,-0.003059983951970935,-0.0026689202059060335,0.03389444574713707,0.21291546523571014,-0.011641757562756538 +1769682053,757750016,0.0,0.0,0.0,1.0,0.0032092288602143526,-0.003275135299190879,-0.002372436923906207,6.930989911779761e-06,0.00012540574243757874,0.00595914525911212 +1769682053,790865408,0.0,0.0,0.0,1.0,0.0029476042836904526,-0.003504473250359297,-0.0021813856437802315,2.4130713427439332e-05,0.0004029081610497087,0.019069228321313858 +1769682053,803402496,0.0,0.0,0.0,1.0,0.002719985553994775,-0.003461109474301338,-0.0020195720717310905,0.12348418682813644,0.08958534896373749,-0.0032613519579172134 +1769682053,854890496,0.0,0.0,0.0,1.0,0.001599014620296657,-0.0029745951760560274,-0.001824108068831265,-0.12353593856096268,-0.0904320478439331,-0.03604452684521675 +1769682053,871082496,0.0,0.0,0.0,1.0,0.0006484006298705935,-0.0024646499659866095,-0.0017800781643018126,-6.284797564148903e-05,-0.000863663328345865,-0.040521930903196335 +1769682053,914370304,0.0,0.0,0.0,1.0,-0.00021518062567338347,-0.0014522894052788615,-0.0017317908350378275,0.08961666375398636,-0.12397798895835876,-0.022541223093867302 +1769682053,958818560,0.0,0.0,0.0,1.0,-0.00023232058447320014,-0.0009430958307348192,-0.0017295503057539463,0.1234031394124031,0.08887926489114761,-0.037871405482292175 +1769682053,981193728,0.0,0.0,0.0,1.0,-0.0004736889386549592,-0.0008429668960161507,-0.0016910210251808167,-3.023789031431079e-05,-0.00038077979115769267,-0.017877323552966118 +1769682054,13901824,0.0,0.0,0.0,1.0,-0.0006102306069806218,-0.0005991312209516764,-0.0016368108335882425,0.12342918664216995,0.08934950828552246,-0.016420530155301094 +1769682054,66970112,0.0,0.0,0.0,1.0,-0.0006509993690997362,-0.0005712476558983326,-0.0015503381146118045,-1.2315060303080827e-05,-0.00015204530791379511,-0.007150935009121895 +1769682054,77933312,0.0,0.0,0.0,1.0,-0.0005373473977670074,-0.0005838823853991926,-0.0013204284477978945,0.12346707284450531,0.0899452418088913,0.010990253649652004 +1769682054,99044608,0.0,0.0,0.0,1.0,-0.0004599678504746407,-0.0006438401760533452,-0.0011427056742832065,-0.12344202399253845,-0.08966977149248123,0.002120549790561199 +1769682054,148752384,0.0,0.0,0.0,1.0,-0.0002948673500213772,-0.0008941906853578985,-0.0005990934441797435,0.08970601856708527,-0.1233382448554039,0.006032585632055998 +1769682054,173427968,0.0,0.0,0.0,1.0,-0.0003577921015676111,-0.0010630866745486856,-0.0003747384180314839,-0.03371072933077812,-0.21278588473796844,0.018883561715483665 +1769682054,214278656,0.0,0.0,0.0,1.0,-0.00027255865279585123,-0.00101754954084754,4.873746001976542e-05,-0.2131449431180954,0.0336606465280056,-0.0038952906616032124 +1769682054,248122880,0.0,0.0,0.0,1.0,-1.3046648746239953e-05,-0.0010240987176075578,0.0004332025127951056,0.21314698457717896,-0.033637892454862595,0.005077717825770378 +1769682054,280194560,0.0,0.0,0.0,1.0,-3.998220927314833e-05,-0.0010185318533331156,0.0006687114364467561,0.08976233005523682,-0.12270824611186981,0.035813990980386734 +1769682054,301949184,0.0,0.0,0.0,1.0,0.0003051165258511901,-0.0008282744092866778,0.0008208384388126433,0.24688391387462616,0.17936719954013824,-0.0030910365749150515 +1769682054,355055616,0.0,0.0,0.0,1.0,0.0002429423329886049,-8.045144204515964e-05,0.0011542412685230374,-0.24696367979049683,-0.18011309206485748,-0.032653845846652985 +1769682054,382706432,0.0,0.0,0.0,1.0,0.00017895884229801595,0.00029209087369963527,0.00130114471539855,-0.1794380396604538,0.24611623585224152,-0.03945009410381317 +1769682054,413716736,0.0,0.0,0.0,1.0,0.0002631474344525486,0.0006185736274346709,0.0014106931630522013,-1.8621693016029894e-05,-0.00020242865139152855,-0.009534582495689392 +1769682054,473553920,0.0,0.0,0.0,1.0,-0.00024041387951001525,0.0007741947192698717,0.0015716616762802005,-0.21312347054481506,0.03386275842785835,0.003268875414505601 +1769682054,477318144,0.0,0.0,0.0,1.0,-9.887598571367562e-05,0.0006332453340291977,0.0016974544851109385,0.3365616202354431,0.05551483854651451,-0.017321504652500153 +1769682054,513253120,0.0,0.0,0.0,1.0,-0.0001978367508854717,0.0007360893068835139,0.0018115374259650707,0.21312010288238525,-0.0338846780359745,-0.003260249737650156 +1769682054,548129792,0.0,0.0,0.0,1.0,-6.55574694974348e-07,0.0005952249630354345,0.002022029599174857,0.0676712691783905,0.4264034926891327,0.0027474593371152878 +1769682054,577868288,0.0,0.0,0.0,1.0,-0.00021613632270600647,0.0005871891626156867,0.0022241331171244383,-0.33654943108558655,-0.055170804262161255,0.030408605933189392 +1769682054,615524608,0.0,0.0,0.0,1.0,-0.000504022988025099,0.0008307516691274941,0.0024496978148818016,0.033866774290800095,0.21322238445281982,0.0025697345845401287 +1769682054,652375040,0.0,0.0,0.0,1.0,6.064474655431695e-05,0.0013666143640875816,0.002880870131775737,-0.12345384061336517,-0.08908965438604355,0.025956004858016968 +1769682054,697037056,0.0,0.0,0.0,1.0,-7.775040285196155e-05,0.0018449067138135433,0.0032755890861153603,-0.12347806245088577,-0.08925490826368332,0.017606593668460846 +1769682054,717963264,0.0,0.0,0.0,1.0,4.4246822653803974e-05,0.0020382124930620193,0.0036994502879679203,-0.15739493072032928,-0.30212506651878357,0.03051607683300972 +1769682054,756093952,0.0,0.0,0.0,1.0,8.126627653837204e-05,0.002337019657716155,0.004195678047835827,0.30265894532203674,-0.15771180391311646,-0.009062772616744041 +1769682054,769201152,0.0,0.0,0.0,1.0,-0.00043579054181464016,0.0025903359055519104,0.004425257910043001,-0.08951549232006073,0.12416934967041016,0.028507892042398453 +1769682054,813349632,0.0,0.0,0.0,1.0,-0.00114694912917912,0.00303493975661695,0.004794389475136995,0.21314038336277008,-0.03333202376961708,0.03259329870343208 +1769682054,861101312,0.0,0.0,0.0,1.0,-0.0017802580259740353,0.003405787516385317,0.00503211934119463,0.12357679754495621,0.08956748247146606,0.0015258843777701259 +1769682054,882000640,0.0,0.0,0.0,1.0,-0.002178970957174897,0.003321028547361493,0.005110656376928091,0.0894932821393013,-0.12361115217208862,0.00010739022400230169 +1769682054,915626752,0.0,0.0,0.0,1.0,-0.002116624964401126,0.0032372577115893364,0.0051415241323411465,0.08948484063148499,-0.12342497706413269,0.009643475525081158 +1769682054,948027648,0.0,0.0,0.0,1.0,-0.0023932731710374355,0.0030620386824011803,0.005136151798069477,1.1834690667456016e-06,2.489845428499393e-05,0.0011918330565094948 +1769682054,981501952,0.0,0.0,0.0,1.0,-0.0021323072724044323,0.002861686749383807,0.005126448348164558,0.21307529509067535,-0.033949173986911774,0.01243721041828394 +1769682055,14120448,0.0,0.0,0.0,1.0,-0.0017341997008770704,0.0027371691539883614,0.005137245170772076,0.21305915713310242,-0.03423023223876953,0.0005347896367311478 +1769682055,66983424,0.0,0.0,0.0,1.0,-0.0019268807955086231,0.0025305424351245165,0.005273248068988323,-0.055102452635765076,0.3367941677570343,0.00022792734671384096 +1769682055,75242496,0.0,0.0,0.0,1.0,-0.0015264613321051002,0.002535047475248575,0.005557630676776171,0.2130478471517563,-0.034260399639606476,0.0029529021121561527 +1769682055,116718080,0.0,0.0,0.0,1.0,-0.0013125324621796608,0.002514504361897707,0.0058990586549043655,-0.21304857730865479,0.034052103757858276,-0.014885799027979374 +1769682055,156527104,0.0,0.0,0.0,1.0,-0.0012287453282624483,0.0024227353278547525,0.006540838163346052,0.08931023627519608,-0.12381568551063538,-0.0034615914337337017 +1769682055,168150016,0.0,0.0,0.0,1.0,-0.0011582038132473826,0.0025080598425120115,0.006849200464785099,0.08929364383220673,-0.12382771074771881,-0.003459736704826355 +1769682055,213348608,0.0,0.0,0.0,1.0,-0.0010102904634550214,0.0025744205340743065,0.007460991386324167,0.12375465780496597,0.08911856263875961,-0.007829055190086365 +1769682055,265400576,0.0,0.0,0.0,1.0,-0.0013857323210686445,0.002583960071206093,0.007915331982076168,-0.15834566950798035,-0.3019932806491852,0.014554583467543125 +1769682055,275572992,0.0,0.0,0.0,1.0,-0.0010895048035308719,0.0026830679271370173,0.008223552256822586,-0.12380053102970123,-0.0884673148393631,0.03640322387218475 +1769682055,316045824,0.0,0.0,0.0,1.0,-0.0009323335252702236,0.002602210035547614,0.008422184735536575,0.08916564285755157,-0.12259018421173096,0.06210436299443245 +1769682055,349820160,0.0,0.0,0.0,1.0,-0.0005230332026258111,0.002191648818552494,0.008532123640179634,0.08911792188882828,-0.12300992757081985,0.043040212243795395 +1769682055,386270720,0.0,0.0,0.0,1.0,-0.00047388969687744975,0.0018546951469033957,0.008541224524378777,-0.21296976506710052,0.035612769424915314,0.03980676084756851 +1769682055,414122240,0.0,0.0,0.0,1.0,-0.0002879306848626584,0.0017547656316310167,0.00855724886059761,-0.034852366894483566,-0.2127942144870758,0.010279026813805103 +1769682055,458215424,0.0,0.0,0.0,1.0,-0.0003892128588631749,0.0014379251515492797,0.008532088249921799,-5.139561835676432e-06,0.0006771145854145288,0.033371757715940475 +1769682055,480408064,0.0,0.0,0.0,1.0,-0.0009801844134926796,0.0010107076959684491,0.008495022542774677,-0.034986212849617004,-0.21214570105075836,0.04125555604696274 +1769682055,515834112,0.0,0.0,0.0,1.0,-0.0009568683453835547,0.0007460078340955079,0.008595796301960945,0.053910885006189346,-0.33660027384757996,0.018747031688690186 +1769682055,554648576,0.0,0.0,0.0,1.0,-0.000945927225984633,0.0004474168526940048,0.008834325708448887,-0.08890363574028015,0.12393885850906372,-0.004907466471195221 +1769682055,580162048,0.0,0.0,0.0,1.0,-0.0009260496008209884,0.0005233559058979154,0.009116494096815586,-0.07033178955316544,-0.42577651143074036,0.006186038255691528 +1769682055,613778432,0.0,0.0,0.0,1.0,-0.0027692890726029873,0.002235389780253172,0.009370225481688976,-0.035239361226558685,-0.21180137991905212,0.056707821786403656 +1769682055,665056000,0.0,0.0,0.0,1.0,-0.0016427922528237104,0.005296352319419384,0.009997586719691753,-2.540135756134987e-05,0.0011920833494514227,0.05959275737404823 +1769682055,675640320,0.0,0.0,0.0,1.0,-0.0016267253085970879,0.007207595743238926,0.010496914386749268,0.12411471456289291,0.0890413448214531,0.013799916952848434 +1769682055,714818304,0.0,0.0,0.0,1.0,-0.0016391478711739182,0.008252223022282124,0.01096153911203146,-0.2128790318965912,0.03586266562342644,0.02056710049510002 +1769682055,750262016,0.0,0.0,0.0,1.0,-0.0014551420463249087,0.00883547868579626,0.011487625539302826,0.12420681118965149,0.08842287212610245,-0.012339835986495018 +1769682055,780083456,0.0,0.0,0.0,1.0,-0.0015891711227595806,0.008970595896244049,0.011827506124973297,-0.24844104051589966,-0.1773262619972229,-0.003999472130089998 +1769682055,803663616,0.0,0.0,0.0,1.0,-0.0016111843287944794,0.008722878061234951,0.01199934259057045,0.12426063418388367,0.0883975476026535,-0.009894238784909248 +1769682055,849206016,0.0,0.0,0.0,1.0,-0.0025381946470588446,0.008835554122924805,0.01232939027249813,0.08852079510688782,-0.12448561191558838,-0.008099716156721115 +1769682055,881560064,0.0,0.0,0.0,1.0,-0.00284408638253808,0.00889401976019144,0.01248131413012743,0.052609559148550034,-0.3374064862728119,-0.01114999782294035 +1769682055,914262016,0.0,0.0,0.0,1.0,-0.003039818024262786,0.008961193263530731,0.01258939690887928,-0.21278850734233856,0.036063577979803085,0.004710999317467213 +1769682055,965416448,0.0,0.0,0.0,1.0,-0.0024908699560910463,0.008569247089326382,0.012778809294104576,-0.3011188805103302,0.1606038212776184,0.0043530636467039585 +1769682055,972596736,0.0,0.0,0.0,1.0,-0.001765857683494687,0.007929591462016106,0.012955959886312485,-0.12450504302978516,-0.08793691545724869,0.01919468864798546 +1769682056,14769408,0.0,0.0,0.0,1.0,-0.0017177100526168942,0.007545081432908773,0.013199344277381897,-0.0883060023188591,0.12482369691133499,0.016370467841625214 +1769682056,47250688,0.0,0.0,0.0,1.0,-0.0013299661222845316,0.007201101165264845,0.013553941622376442,-2.1761617972515523e-05,0.00011469861055957153,0.0059593250043690205 +1769682056,67680000,0.0,0.0,0.0,1.0,-0.0011900741374120116,0.007049776613712311,0.013761173002421856,0.08818026632070541,-0.12473355233669281,-0.007999076507985592 +1769682056,114263296,0.0,0.0,0.0,1.0,-0.0010184182319790125,0.007027802988886833,0.01417844370007515,0.08807870000600815,-0.12462259083986282,0.00036347040440887213 +1769682056,154793216,0.0,0.0,0.0,1.0,-0.0010160639649257064,0.0071298847906291485,0.014545135200023651,-0.2493443638086319,-0.17584611475467682,0.009437884204089642 +1769682056,180073984,0.0,0.0,0.0,1.0,-0.0008495349902659655,0.007189200725406408,0.014778872951865196,-0.08801131695508957,0.1249626949429512,0.012711982242763042 +1769682056,201247232,0.0,0.0,0.0,1.0,-0.0011574305826798081,0.0072720726020634174,0.014913193881511688,-0.21258628368377686,0.036634087562561035,-0.010041726753115654 +1769682056,251143936,0.0,0.0,0.0,1.0,-0.0011849808506667614,0.007506853900849819,0.015155612491071224,-0.1617327779531479,-0.30050644278526306,-0.0022480525076389313 +1769682056,280451584,0.0,0.0,0.0,1.0,-0.0032773830462247133,0.006120574194937944,0.015056627802550793,0.21208716928958893,-0.0352647490799427,0.09597239643335342 +1769682056,313719808,0.0,0.0,0.0,1.0,-0.0023192742373794317,0.0036719772033393383,0.01513079833239317,0.26238709688186646,-0.372062623500824,0.1383986920118332 +1769682056,359076352,0.0,0.0,0.0,1.0,-0.0011039169039577246,0.0015386452432721853,0.01538813952356577,-0.12555067241191864,-0.08543848246335983,0.11658217012882233 +1769682056,373337088,0.0,0.0,0.0,1.0,-0.0008587466436438262,0.0008868284057825804,0.015523586422204971,-0.2504834234714508,-0.1731364130973816,0.10920218378305435 +1769682056,414621952,0.0,0.0,0.0,1.0,-0.000296467769658193,0.00016464455984532833,0.015825685113668442,-0.12519928812980652,-0.08682676404714584,0.03671956807374954 +1769682056,452648704,0.0,0.0,0.0,1.0,0.00013495345774572343,0.00017485031276009977,0.01620790734887123,0.2124287337064743,-0.037433259189128876,0.011398745700716972 +1769682056,474314752,0.0,0.0,0.0,1.0,0.0003024832403752953,0.0002738355833571404,0.016531728208065033,-0.33763042092323303,-0.04941581189632416,0.011016100645065308 +1769682056,514769920,0.0,0.0,0.0,1.0,-0.00016778300050646067,0.000320804858347401,0.016737643629312515,0.21244314312934875,-0.0378233976662159,0.0018671909347176552 +1769682056,547510272,0.0,0.0,0.0,1.0,-0.0002914404321927577,0.0004898992483504117,0.01705789938569069,0.00018814468057826161,-0.000650097499601543,-0.03456409275531769 +1769682056,582110720,0.0,0.0,0.0,1.0,-0.0008746804087422788,0.0007029527914710343,0.017231401056051254,0.2615046501159668,-0.37589019536972046,-0.0034354091621935368 +1769682056,600484352,0.0,0.0,0.0,1.0,-0.0008750098058953881,0.0008059723768383265,0.017351321876049042,0.21248222887516022,-0.03848610445857048,-0.016002045944333076 +1769682056,649406720,0.0,0.0,0.0,1.0,-0.0016059016343206167,0.003190314630046487,0.017555277794599533,-0.00011244037887081504,0.00037875326233915985,0.020261740311980247 +1769682056,680296704,0.0,0.0,0.0,1.0,-0.0016484406078234315,0.00446052523329854,0.017639312893152237,-0.164001926779747,-0.2988273501396179,0.026105549186468124 +1769682056,715762176,0.0,0.0,0.0,1.0,-0.001991448225453496,0.005394017323851585,0.017675144597887993,-0.2895103394985199,-0.38593414425849915,0.009073360823094845 +1769682056,759163648,0.0,0.0,0.0,1.0,-0.0018831491470336914,0.005856143310666084,0.017691778019070625,0.173514723777771,-0.25071319937705994,0.017607592046260834 +1769682056,774487296,0.0,0.0,0.0,1.0,-0.0017089458415284753,0.006255302112549543,0.017699990421533585,0.13459676504135132,-0.463422954082489,0.0022422352340072393 +1769682056,815335680,0.0,0.0,0.0,1.0,-0.0017308053793385625,0.006172123830765486,0.017707131803035736,-0.42451798915863037,0.07798384130001068,0.001820241566747427 +1769682056,849694720,0.0,0.0,0.0,1.0,-0.0015404649311676621,0.005802363157272339,0.017768071964383125,0.17299818992614746,-0.25101059675216675,0.020058294758200645 +1769682056,869825536,0.0,0.0,0.0,1.0,-0.0014341744827106595,0.005909171421080828,0.017833609133958817,-0.12568844854831696,-0.08652588725090027,-0.0004494842141866684 +1769682056,915013888,0.0,0.0,0.0,1.0,-0.0017537862295284867,0.005802792496979237,0.01794445887207985,-0.12576168775558472,-0.0864710733294487,-0.0016769467620179057 +1769682056,950311424,0.0,0.0,0.0,1.0,-0.0018528526416048408,0.00569550646468997,0.01809586212038994,-0.3378334045410156,-0.04717952013015747,-0.019439920783042908 +1769682056,980088320,0.0,0.0,0.0,1.0,-0.0015623660292476416,0.005562669597566128,0.018223388120532036,-0.21201372146606445,0.03932541236281395,-0.0165688619017601 +1769682057,2164480,0.0,0.0,0.0,1.0,-0.0013074292801320553,0.005152685567736626,0.01829908788204193,-0.12604092061519623,-0.08586326986551285,0.01969991810619831 +1769682057,50532864,0.0,0.0,0.0,1.0,-0.0007838846649974585,0.004618651699274778,0.01851358264684677,0.2117937058210373,-0.03921185061335564,0.03809245675802231 +1769682057,83107328,0.0,0.0,0.0,1.0,-0.000906463828869164,0.004416930954903364,0.018639395013451576,-0.21218208968639374,0.04029905050992966,0.015514342114329338 +1769682057,114123520,0.0,0.0,0.0,1.0,-0.000995838432572782,0.004244474694132805,0.018740935251116753,-0.37824615836143494,-0.25781184434890747,0.004058151505887508 +1769682057,157167360,0.0,0.0,0.0,1.0,-0.0008129624184221029,0.004267110954970121,0.018801916390657425,-0.21211203932762146,0.04047263413667679,0.011885861866176128 +1769682057,174526464,0.0,0.0,0.0,1.0,-0.0007180061656981707,0.004120336379855871,0.018850507214665413,-0.2119864821434021,0.04041773080825806,-6.684986874461174e-05 +1769682057,214458112,0.0,0.0,0.0,1.0,-0.00044144035200588405,0.004180210642516613,0.018809910863637924,-0.21184565126895905,0.04028027504682541,-0.014395330101251602 +1769682057,249272832,0.0,0.0,0.0,1.0,-0.0009111297549679875,0.004335981793701649,0.018679911270737648,0.08562134951353073,-0.12629443407058716,0.0017943442799150944 +1769682057,270242304,0.0,0.0,0.0,1.0,-0.0010139874648302794,0.004394840449094772,0.018585175275802612,0.044996727257966995,-0.3386099934577942,-0.017392119392752647 +1769682057,314343936,0.0,0.0,0.0,1.0,-0.0011770258424803615,0.0026213533710688353,0.01833435148000717,0.04021815210580826,0.2133185863494873,0.07880152016878128 +1769682057,344763136,0.0,0.0,0.0,1.0,-0.000745354569517076,0.0014308338286355138,0.01821669563651085,0.12592792510986328,0.08647481352090836,0.059161487966775894 +1769682057,380600064,0.0,0.0,0.0,1.0,-0.0009488744544796646,0.00033787093707360327,0.0179994385689497,-0.04180514067411423,-0.21054163575172424,0.07373973727226257 +1769682057,400477184,0.0,0.0,0.0,1.0,-0.000677120522595942,0.00011228540824959055,0.017906665802001953,0.08505779504776001,-0.12608255445957184,0.026830827817320824 +1769682057,449866240,0.0,0.0,0.0,1.0,-0.0005733012221753597,-0.00013995886547490954,0.017664873972535133,0.21166060864925385,-0.0412098653614521,0.014486007392406464 +1769682057,480288256,0.0,0.0,0.0,1.0,-0.0002972037182189524,-0.00021251116413623095,0.01761762611567974,0.17021116614341736,-0.25334131717681885,0.0012086475035175681 +1769682057,513640960,0.0,0.0,0.0,1.0,-7.744230970274657e-05,-6.215247594809625e-06,0.017596159130334854,0.17002607882022858,-0.2533250153064728,0.007166936993598938 +1769682057,552159744,0.0,0.0,0.0,1.0,-0.00044186320155858994,0.0001921020884765312,0.01756877824664116,0.041873279958963394,0.21158617734909058,-0.008175746537744999 +1769682057,581444864,0.0,0.0,0.0,1.0,-0.0005100644193589687,0.00033120164880529046,0.017579885199666023,-0.12676502764225006,-0.08495617657899857,-0.004348458256572485 +1769682057,613709568,0.0,0.0,0.0,1.0,-0.00025838936562649906,0.0014405868714675307,0.017621206119656563,-0.42341548204421997,0.08429094403982162,0.009153894148766994 +1769682057,660426496,0.0,0.0,0.0,1.0,-0.0007370676612481475,0.0026899855583906174,0.017643461003899574,-0.08464960008859634,-0.4227070212364197,0.03420163691043854 +1769682057,668846592,0.0,0.0,0.0,1.0,-0.0007214259821921587,0.0031184684485197067,0.017630560323596,-0.21152792870998383,0.042094048112630844,-0.010947877541184425 +1769682057,715654144,0.0,0.0,0.0,1.0,-0.0008451623725704849,0.0037091702688485384,0.017517412081360817,-0.21177227795124054,0.04279289022088051,0.020012034103274345 +1769682057,750447360,0.0,0.0,0.0,1.0,-0.000898434198461473,0.003949496895074844,0.017239846289157867,-0.08515363931655884,-0.42304661870002747,0.006724540144205093 +1769682057,783156992,0.0,0.0,0.0,1.0,-0.0009978311136364937,0.0038876698818057775,0.01696927659213543,8.715147851034999e-05,-0.00016860890900716186,-0.009534860961139202 +1769682057,813944064,0.0,0.0,0.0,1.0,-0.0013618977973237634,0.003781951265409589,0.01665910892188549,0.04167039692401886,-0.3388071358203888,-0.005558636970818043 +1769682057,853365504,0.0,0.0,0.0,1.0,-0.0005630990490317345,0.00320503581315279,0.016297955065965652,0.00015636600437574089,-0.00029403751250356436,-0.016686175018548965 +1769682057,880767232,0.0,0.0,0.0,1.0,-0.0004254642117302865,0.002815943444147706,0.016096491366624832,-0.04292181879281998,-0.21164128184318542,-0.008601861074566841 +1769682057,917088768,0.0,0.0,0.0,1.0,4.3364838347770274e-05,0.002577900653705001,0.015937495976686478,-0.2955493628978729,0.17030726373195648,-0.00819764006882906 +1769682057,954927872,0.0,0.0,0.0,1.0,0.00046386459143832326,0.0023332941345870495,0.015953078866004944,-0.043088000267744064,-0.21171934902668,-0.015758642926812172 +1769682057,967955456,0.0,0.0,0.0,1.0,0.0008352013537660241,0.002211385639384389,0.016071267426013947,-0.12746550142765045,-0.0838460773229599,0.010981115512549877 +1769682058,14430976,0.0,0.0,0.0,1.0,0.001504047540947795,0.002091890899464488,0.016388431191444397,0.29516878724098206,-0.1705920249223709,0.019005054607987404 +1769682058,63295488,0.0,0.0,0.0,1.0,0.0017024963162839413,0.0018874058732762933,0.016697244718670845,-0.29859715700149536,-0.3789840042591095,0.007389415521174669 +1769682058,70527232,0.0,0.0,0.0,1.0,0.0012420008424669504,0.0018786274595186114,0.01677042618393898,4.680913843913004e-05,-8.486626029480249e-05,-0.004767389502376318 +1769682058,114053376,0.0,0.0,0.0,1.0,0.0013392185792326927,0.0018767775036394596,0.016816608607769012,-0.0437953844666481,-0.21133123338222504,-0.0002351836592424661 +1769682058,148743936,0.0,0.0,0.0,1.0,0.0008279446046799421,0.001941298833116889,0.01664564199745655,-0.171715646982193,-0.29465705156326294,0.01668545976281166 +1769682058,180868352,0.0,0.0,0.0,1.0,0.0007572102476842701,0.001896000001579523,0.016376225277781487,-0.00017866208509076387,0.00032067380379885435,0.01787782460451126 +1769682058,214981376,0.0,0.0,0.0,1.0,0.00045735284220427275,0.0019142216769978404,0.016007982194423676,-0.21113820374011993,0.044008102267980576,-0.010065159760415554 +1769682058,249071872,0.0,0.0,0.0,1.0,-0.0003939501475542784,0.0013694704975932837,0.015368036925792694,0.2944490611553192,-0.17168651521205902,0.022748978808522224 +1769682058,280862208,0.0,0.0,0.0,1.0,-0.0006666785920970142,7.426064985338598e-05,0.014910079538822174,0.29404598474502563,-0.1712426245212555,0.054929811507463455 +1769682058,315730176,0.0,0.0,0.0,1.0,-0.0008409741567447782,-0.0009659371571615338,0.014501743949949741,0.04418746009469032,0.21168296039104462,0.027652177959680557 +1769682058,354619136,0.0,0.0,0.0,1.0,-0.0010454908479005098,-0.0017522587440907955,0.013998478651046753,0.0828913077712059,-0.1271996647119522,0.03887612745165825 +1769682058,381903360,0.0,0.0,0.0,1.0,-0.0006985495565459132,-0.002126652980223298,0.013756955973803997,0.21099264919757843,-0.04447255656123161,0.013623163104057312 +1769682058,413780736,0.0,0.0,0.0,1.0,-0.000225231604417786,-0.0022411097306758165,0.013647293671965599,0.08319103717803955,-0.12799344956874847,-0.0016616464126855135 +1769682058,461575424,0.0,0.0,0.0,1.0,0.0002676042204257101,-0.002048788359388709,0.013784939423203468,0.0828530490398407,-0.1275491714477539,0.025742726400494576 +1769682058,470371840,0.0,0.0,0.0,1.0,0.0004226326127536595,-0.000916944001801312,0.013965246267616749,-0.04528048634529114,-0.21045319736003876,0.035514868795871735 +1769682058,513759744,0.0,0.0,0.0,1.0,0.0008970591006800532,0.0011860399972647429,0.014541435055434704,-0.1731996387243271,-0.29387396574020386,0.009539255872368813 +1769682058,553492480,0.0,0.0,0.0,1.0,0.0014587340410798788,0.0026796390302479267,0.01504240557551384,-0.04503845050930977,-0.2112969160079956,-0.014529149979352951 +1769682058,585112064,0.0,0.0,0.0,1.0,0.0014471916947513819,0.0032946583814918995,0.015288086608052254,0.12821140885353088,0.08271457254886627,-0.007375016342848539 +1769682058,614399232,0.0,0.0,0.0,1.0,0.0014101304113864899,0.003565039485692978,0.015453329309821129,0.1284172683954239,0.08235356956720352,-0.024050522595643997 +1769682058,652224768,0.0,0.0,0.0,1.0,0.0012370155891403556,0.003828194458037615,0.015612216666340828,0.0371863953769207,-0.3391706943511963,0.0029473700560629368 +1769682058,680232960,0.0,0.0,0.0,1.0,0.0020460220985114574,0.003219467820599675,0.015728145837783813,0.16547872126102448,-0.25686895847320557,-0.015098290517926216 +1769682058,719530240,0.0,0.0,0.0,1.0,0.0027616331353783607,0.0025080502964556217,0.01583080179989338,-0.08218758553266525,0.12760362029075623,-0.04014074429869652 +1769682058,758379520,0.0,0.0,0.0,1.0,0.0027813659980893135,0.0018801202531903982,0.015836643055081367,0.119272880256176,-0.4677996039390564,-0.006855648942291737 +1769682058,781555968,0.0,0.0,0.0,1.0,0.0027192342095077038,0.0013771469239145517,0.01568453200161457,-0.2107265591621399,0.045751769095659256,-0.012579260393977165 +1769682058,814852864,0.0,0.0,0.0,1.0,0.002765753073617816,0.0012280186638236046,0.015425785444676876,0.2107296735048294,-0.04589298740029335,0.010207547806203365 +1769682058,857315072,0.0,0.0,0.0,1.0,0.0028139157220721245,0.0011226818896830082,0.015099390409886837,0.08222011476755142,-0.1282888650894165,0.011599574238061905 +1769682058,874686976,0.0,0.0,0.0,1.0,0.0025665818247944117,0.0012323992559686303,0.014608283527195454,-0.2106180638074875,0.04600009322166443,-0.016191719099879265 +1769682058,914231808,0.0,0.0,0.0,1.0,0.0018314005574211478,0.0015329279704019427,0.014201980084180832,0.03587993234395981,-0.33940425515174866,-0.001580211566761136 +1769682058,948916992,0.0,0.0,0.0,1.0,0.0018988732481375337,0.0018854025984182954,0.013689721934497356,0.03562834486365318,-0.3393115997314453,0.004408061504364014 +1769682058,980824576,0.0,0.0,0.0,1.0,0.0015180469490587711,0.0022838287986814976,0.013203242793679237,-0.04649706557393074,-0.2108326107263565,-0.004844240844249725 +1769682059,1709568,0.0,0.0,0.0,1.0,0.0014880483504384756,0.002386012114584446,0.012915515340864658,-0.08177649229764938,0.12819704413414001,-0.025965964421629906 +1769682059,47930368,0.0,0.0,0.0,1.0,0.0003961628535762429,0.0017199880676344037,0.011979416012763977,0.00012864753080066293,-0.00022706150775775313,-0.011918080039322376 +1769682059,80668160,0.0,0.0,0.0,1.0,-0.00022263036225922406,0.001365813659504056,0.01142103597521782,-0.1637493073940277,0.2573445439338684,-0.01025392021983862 +1769682059,113809152,0.0,0.0,0.0,1.0,-0.00022840739984530956,0.000885175250004977,0.01093918364495039,0.30404630303382874,0.3750404417514801,0.03312312811613083 +1769682059,154386688,0.0,0.0,0.0,1.0,-0.0003334606590215117,-0.001273023197427392,0.010375462472438812,-0.04774010181427002,-0.20928813517093658,0.07143298536539078 +1769682059,181639168,0.0,0.0,0.0,1.0,-0.0006693886825814843,-0.0023949879687279463,0.010025708004832268,0.08103912323713303,-0.127523735165596,0.07007136195898056 +1769682059,214520576,0.0,0.0,0.0,1.0,-0.0008247633231803775,-0.0032414577435702085,0.009723425842821598,-0.09466658532619476,-0.4203823506832123,0.045131754130125046 +1769682059,248932608,0.0,0.0,0.0,1.0,-0.0008097885292954743,-0.003538548480719328,0.009361996315419674,0.37363186478614807,-0.30438369512557983,0.03474850952625275 +1769682059,270533888,0.0,0.0,0.0,1.0,-0.0004213284410070628,-0.0032391431741416454,0.009212914854288101,0.2574056088924408,0.16402697563171387,0.036545269191265106 +1769682059,314096640,0.0,0.0,0.0,1.0,-0.0008129141642712057,-0.0019597108475863934,0.008868766948580742,0.04715081304311752,0.21082593500614166,0.01318896934390068 +1769682059,348458496,0.0,0.0,0.0,1.0,0.0002168770442949608,-0.0004750463995151222,0.00867409072816372,-0.08138500154018402,0.1286056935787201,-0.01996707357466221 +1769682059,381685248,0.0,0.0,0.0,1.0,0.0009925743797793984,0.0003998007159680128,0.008530573919415474,-0.25770413875579834,-0.16352908313274384,-0.02340182662010193 +1769682059,400045824,0.0,0.0,0.0,1.0,0.00106512859929353,0.0009436281397938728,0.008436591364443302,-0.0812067911028862,0.1284133940935135,-0.0318920724093914 +1769682059,450987520,0.0,0.0,0.0,1.0,0.0015107940416783094,0.0017963267164304852,0.008160475641489029,0.08159680664539337,-0.1292622834444046,-0.0109979547560215 +1769682059,480444160,0.0,0.0,0.0,1.0,0.0026546332519501448,0.0015050959773361683,0.0079727154225111,-0.17631879448890686,-0.2925122380256653,-0.029629578813910484 +1769682059,513807616,0.0,0.0,0.0,1.0,0.003449380863457918,0.000997621682472527,0.0077728936448693275,-0.03336289897561073,0.3388162851333618,-0.04024993255734444 +1769682059,561808128,0.0,0.0,0.0,1.0,0.0037668661680072546,0.00040550241828896105,0.007474076934158802,0.25827157497406006,0.16254077851772308,-0.009980950504541397 +1769682059,573019392,0.0,0.0,0.0,1.0,0.0036575186531990767,0.0002630990347824991,0.007280812133103609,0.1292726695537567,0.0810193121433258,-0.016913866624236107 +1769682059,600102144,0.0,0.0,0.0,1.0,0.004064089618623257,-3.101408947259188e-05,0.006963970139622688,-0.08116364479064941,0.1288241446018219,-0.01648792438209057 +1769682059,660941056,0.0,0.0,0.0,1.0,0.004154169466346502,-0.00037787764449603856,0.006424191873520613,-0.08128314465284348,0.12915413081645966,-0.0010199191747233272 +1769682059,668027904,0.0,0.0,0.0,1.0,0.004262794740498066,-0.0004511668812483549,0.00619947724044323,0.08124209940433502,-0.12911687791347504,0.003413424827158451 +1769682059,714522624,0.0,0.0,0.0,1.0,0.003092473605647683,0.00018121357425116003,0.005722050555050373,0.09616830199956894,0.4202479124069214,-0.031249133870005608 +1769682059,748706048,0.0,0.0,0.0,1.0,0.0023955772630870342,0.0008693862473592162,0.005260375328361988,-0.21014806628227234,0.04752277210354805,-0.024617156013846397 +1769682059,784193024,0.0,0.0,0.0,1.0,0.0022129116114228964,0.0011254395358264446,0.004938317462801933,8.751475979806855e-05,-0.00016834892448969185,-0.008342497982084751 +1769682059,814369792,0.0,0.0,0.0,1.0,0.0023886235430836678,0.0014342612121254206,0.004663421772420406,0.12943871319293976,0.0807262659072876,-0.021735386922955513 +1769682059,849370880,0.0,0.0,0.0,1.0,0.0006039871950633824,0.0009021701407618821,0.004150988534092903,0.2916361093521118,-0.17755652964115143,-0.008814974687993526 +1769682059,880882688,0.0,0.0,0.0,1.0,0.00010754257527878508,0.00045347039122134447,0.0038328319787979126,-0.08113263547420502,0.12924808263778687,-0.0010988616850227118 +1769682059,918271232,0.0,0.0,0.0,1.0,0.00013777977437712252,0.00030604220228269696,0.0035569299943745136,-0.08109325915575027,0.1292085498571396,-0.003483280772343278 +1769682059,951097856,0.0,0.0,0.0,1.0,-0.0004823826893698424,-0.0010473837610334158,0.003294693771749735,0.5010849833488464,-0.22421793639659882,0.07185442000627518 +1769682059,982163200,0.0,0.0,0.0,1.0,-0.0005588184576481581,-0.002121306024491787,0.0031291835475713015,0.12883810698986053,0.08190140128135681,0.04023400694131851 +1769682060,14583040,0.0,0.0,0.0,1.0,-0.0007103110547177494,-0.0027366667054593563,0.0029438615310937166,0.3392467796802521,0.03357641026377678,0.03624722734093666 +1769682060,64837120,0.0,0.0,0.0,1.0,-0.0008805629331618547,-0.00319582037627697,0.0027429726906120777,0.08080455660820007,-0.12878552079200745,0.02609640173614025 +1769682060,73305344,0.0,0.0,0.0,1.0,-0.0006945420755073428,-0.0033223116770386696,0.0026060009840875864,0.3392855226993561,0.03346121683716774,0.03379061445593834 +1769682060,115079168,0.0,0.0,0.0,1.0,-0.0006959058227948844,-0.0030579897575080395,0.00245838169939816,0.12919653952121735,0.08122541010379791,0.009205072186887264 +1769682060,148312832,0.0,0.0,0.0,1.0,9.515765123069286e-05,-0.0020896559581160545,0.0023902871180325747,-0.04805540293455124,-0.21076621115207672,-0.020072583109140396 +1769682060,187371264,0.0,0.0,0.0,1.0,0.000545112940017134,-0.001339718233793974,0.0023538852110505104,-0.2583042085170746,-0.16264860332012177,-0.030288618057966232 +1769682060,214828032,0.0,0.0,0.0,1.0,0.0010216532973572612,-0.0008465350838378072,0.002296419581398368,0.08134382963180542,-0.12999960780143738,-0.032332055270671844 +1769682060,250360064,0.0,0.0,0.0,1.0,0.0017217485001310706,-0.00035258711432106793,0.002198218833655119,0.12956734001636505,0.08048243820667267,-0.025390611961483955 +1769682060,280790528,0.0,0.0,0.0,1.0,0.002644045278429985,-0.0005671128164976835,0.0021058605052530766,0.12950141727924347,0.08061815053224564,-0.018246661871671677 +1769682060,320055808,0.0,0.0,0.0,1.0,0.0026178418193012476,-0.0007178718806244433,0.0020041433162987232,0.03273402526974678,-0.3398514986038208,-0.007038073148578405 +1769682060,347613696,0.0,0.0,0.0,1.0,0.0031376592814922333,-0.0009758088272064924,0.0018873251974582672,0.12940452992916107,0.08081991970539093,-0.007540523540228605 +1769682060,381369600,0.0,0.0,0.0,1.0,0.003416679799556732,-0.0013738332781940699,0.0017167720943689346,-0.08087469637393951,0.12915432453155518,-0.010615982115268707 +1769682060,413751040,0.0,0.0,0.0,1.0,0.0037529950495809317,-0.0015266493428498507,0.0015668915584683418,-0.048393670469522476,-0.2102815955877304,0.002704667393118143 +1769682060,464611328,0.0,0.0,0.0,1.0,0.0035811131820082664,-0.0015891115181148052,0.0013316847616806626,0.04823241010308266,0.2106524109840393,0.015139021910727024 +1769682060,472744192,0.0,0.0,0.0,1.0,0.0032721126917749643,-0.0016080327332019806,0.0011224339250475168,-0.04842442274093628,-0.2102513462305069,0.0039541833102703094 +1769682060,514870528,0.0,0.0,0.0,1.0,0.002521154936403036,-0.0011255107820034027,0.0008959126425907016,0.4691215455532074,0.1131892204284668,-0.012196687050163746 +1769682060,548708608,0.0,0.0,0.0,1.0,0.002091745613142848,-0.0005218461155891418,0.0005960133858025074,0.2914234399795532,-0.1782063990831375,-0.01728513278067112 +1769682060,586947840,0.0,0.0,0.0,1.0,0.0019161226227879524,-0.0003160869237035513,0.00041368004167452455,-0.12917491793632507,-0.08133475482463837,-0.018584782257676125 +1769682060,615323136,0.0,0.0,0.0,1.0,0.0015445390017703176,-9.031474473886192e-05,0.00021958467550575733,0.2913053631782532,-0.17796102166175842,-0.005352922715246677 +1769682060,652421120,0.0,0.0,0.0,1.0,0.0004978313227184117,-0.0004253908118698746,-5.696468724636361e-05,-0.12922148406505585,-0.08123332262039185,-0.013809050433337688 +1769682060,680637952,0.0,0.0,0.0,1.0,0.00040468820952810347,-0.0007562488317489624,-0.00017833935271482915,0.12942557036876678,0.08077632635831833,-0.007646225392818451 +1769682060,717394944,0.0,0.0,0.0,1.0,-1.0120114893652499e-05,-0.0009353045024909079,-0.00025617374922148883,-0.08087313920259476,0.12921521067619324,-0.008294660598039627 +1769682060,762277120,0.0,0.0,0.0,1.0,-7.972696766955778e-05,-0.0013477711472660303,-0.00028074890724383295,-0.12958110868930817,-0.08042257279157639,0.024340834468603134 +1769682060,767685376,0.0,0.0,0.0,1.0,-0.0004195499059278518,-0.0015798198292031884,-0.00030608312226831913,0.21006321907043457,-0.04790046438574791,0.025655321776866913 +1769682060,815366656,0.0,0.0,0.0,1.0,-0.00034603537642396986,-0.0019069950794801116,-0.00033662255736999214,0.2587645351886749,0.16174031794071198,-0.006993877701461315 +1769682060,859237376,0.0,0.0,0.0,1.0,-0.00046857880079187453,-0.0021375096403062344,-0.000381422316422686,0.03251875936985016,-0.33961325883865356,0.005151825957000256 +1769682060,868052992,0.0,0.0,0.0,1.0,-0.0005867657600902021,-0.0021053545642644167,-0.00041095897904597223,-4.393140989122912e-05,0.00010150760499527678,0.004767091944813728 +1769682060,917038080,0.0,0.0,0.0,1.0,-0.0005936556844972074,-0.002675713738426566,-0.000520365487318486,0.12945960462093353,0.08068569004535675,-0.012459320947527885 +1769682060,950456832,0.0,0.0,0.0,1.0,-2.0251492969691753e-05,-0.003132438752800226,-0.0005505867302417755,-0.048073504120111465,-0.2110620141029358,-0.03410498425364494 +1769682060,980120064,0.0,0.0,0.0,1.0,0.00010271435166941956,-0.0030319951474666595,-0.000563410168979317,0.08127490431070328,-0.13011913001537323,-0.03466539829969406 +1769682061,14194688,0.0,0.0,0.0,1.0,0.00047630572225898504,-0.003077880246564746,-0.0006390282069332898,-2.1019095584051684e-05,5.06920441694092e-05,0.0023835559841245413 +1769682061,51581440,0.0,0.0,0.0,1.0,0.0009217383340001106,-0.0028476864099502563,-0.0007091188454069197,0.04847496375441551,0.21007674932479858,-0.012400186620652676 +1769682061,81461504,0.0,0.0,0.0,1.0,0.0015014938544481993,-0.0028687170706689358,-0.0007620920659974217,0.33973121643066406,0.03234916925430298,-0.00968707725405693 +1769682061,116055040,0.0,0.0,0.0,1.0,0.0016450159018859267,-0.002852728823199868,-0.0007993134786374867,-0.08080555498600006,0.12894359230995178,-0.020140619948506355 +1769682061,156891648,0.0,0.0,0.0,1.0,0.0017402784433215857,-0.002961917780339718,-0.0008616158156655729,-0.21032997965812683,0.04843951761722565,0.0019604077097028494 +1769682061,180825344,0.0,0.0,0.0,1.0,0.002000813838094473,-0.0029456026386469603,-0.0008893409394659102,0.339517205953598,0.032914113253355026,0.015236340463161469 +1769682061,215247872,0.0,0.0,0.0,1.0,0.0020457454957067966,-0.0029122987762093544,-0.0009525373461656272,-0.2104010432958603,0.04860824719071388,0.010333985090255737 +1769682061,263165184,0.0,0.0,0.0,1.0,0.0018726371927186847,-0.0029484762344509363,-0.0010077048791572452,-0.04834432899951935,-0.21031297743320465,0.0017761059571057558 +1769682061,270800896,0.0,0.0,0.0,1.0,0.002079316880553961,-0.002946802880614996,-0.001028218655847013,-0.04835915192961693,-0.21026217937469482,0.004170953296124935 +1769682061,314232576,0.0,0.0,0.0,1.0,0.0012976605212315917,-0.0024519406724721193,-0.0010973131284117699,-0.12920089066028595,-0.08131738007068634,-0.014760499820113182 +1769682061,349272320,0.0,0.0,0.0,1.0,0.0011106072925031185,-0.0021762242540717125,-0.0011550579220056534,-0.12921731173992157,-0.0812719464302063,-0.012361424043774605 +1769682061,384457472,0.0,0.0,0.0,1.0,0.0007243867730721831,-0.00200904393568635,-0.0011911875335499644,-0.08075295388698578,0.12862658500671387,-0.033248066902160645 +1769682061,415211776,0.0,0.0,0.0,1.0,0.0005640253075398505,-0.0019026591908186674,-0.0012093046680092812,-0.04823180288076401,-0.2105296105146408,-0.007699227426201105 +1769682061,448083712,0.0,0.0,0.0,1.0,0.00024207441310863942,-0.00199886504560709,-0.0012643506051972508,0.1619393676519394,-0.2583833336830139,0.014044279232621193 +1769682061,481067520,0.0,0.0,0.0,1.0,-7.568592263851315e-05,-0.0020745624788105488,-0.001299968222156167,-0.12906236946582794,-0.08171019703149796,-0.03139132633805275 +1769682061,516333312,0.0,0.0,0.0,1.0,0.00010063051013275981,-0.0020393042359501123,-0.0013078521005809307,0.048368435353040695,0.2100670039653778,-0.013765670359134674 +1769682061,556000512,0.0,0.0,0.0,1.0,-0.0005109055200591683,-0.00213174382224679,-0.0013410730753093958,-0.04821380600333214,-0.2104862928390503,-0.0052999272011220455 +1769682061,582216448,0.0,0.0,0.0,1.0,-0.0005157927516847849,-0.001514230971224606,-0.0013650222681462765,0.04842634126543999,0.2098376601934433,-0.024493539705872536 +1769682061,614109440,0.0,0.0,0.0,1.0,-0.00047303776955232024,-0.0010903187794610858,-0.0013899686746299267,0.12940724194049835,0.08069127798080444,-0.01630781590938568 +1769682061,665623040,0.0,0.0,0.0,1.0,-0.0002737698960117996,-0.0006020579021424055,-0.0014584368327632546,0.08111194521188736,-0.12948201596736908,-0.007312076166272163 +1769682061,673529600,0.0,0.0,0.0,1.0,-0.00024236160970758647,-0.00025269342586398125,-0.0015374644426628947,0.3397919535636902,0.03229513019323349,-0.02325146272778511 +1769682061,717522432,0.0,0.0,0.0,1.0,-0.0009363595745526254,-0.0006061416934244335,-0.0016687805764377117,0.00033181352773681283,-0.000986238126643002,-0.0452876091003418 +1769682061,764879104,0.0,0.0,0.0,1.0,-0.00047163551789708436,-0.0028279752004891634,-0.0017526170704513788,0.3398723006248474,0.032077107578516006,-0.03519976884126663 +1769682061,784994816,0.0,0.0,0.0,1.0,-0.00037021012394689023,-0.004101376049220562,-0.001821899670176208,0.00014455438940785825,-0.00044040154898539186,-0.020260289311408997 +1769682061,803153408,0.0,0.0,0.0,1.0,0.00013328046770766377,-0.005058190319687128,-0.0018916537519544363,0.2587151527404785,0.16157445311546326,-0.027934951707720757 +1769682061,848583168,0.0,0.0,0.0,1.0,0.00017203927563969046,-0.005614106543362141,-0.0019952075090259314,0.3396153450012207,0.03289277106523514,-0.0007980223745107651 +1769682061,881242112,0.0,0.0,0.0,1.0,-9.38472840061877e-06,-0.005686434451490641,-0.002023673616349697,-0.08115184307098389,0.1294221729040146,0.006190600339323282 +1769682061,915871488,0.0,0.0,0.0,1.0,-5.442504698294215e-05,-0.005667218007147312,-0.002075585536658764,-0.08112040907144547,0.12928767502307892,0.00024559651501476765 +1769682061,951442688,0.0,0.0,0.0,1.0,-1.419664840796031e-05,-0.00535236019641161,-0.0021026625763624907,-0.00011126237222924829,0.0003883764729835093,0.017876839265227318 +1769682061,980891904,0.0,0.0,0.0,1.0,5.8524779888102785e-05,-0.005114479921758175,-0.0021336665377020836,0.4687630832195282,0.11438620090484619,0.011091707274317741 +1769682062,15422720,0.0,0.0,0.0,1.0,4.082397936144844e-05,-0.004943062551319599,-0.002161799930036068,-0.0001622918643988669,0.000595437886659056,0.027411209419369698 +1769682062,47631360,0.0,0.0,0.0,1.0,-0.00013856809528078884,-0.004865480121225119,-0.0021664644591510296,0.08105966448783875,-0.12890280783176422,0.01638433337211609 +1769682062,82777856,0.0,0.0,0.0,1.0,3.818779805442318e-05,-0.004688176326453686,-0.002121174708008766,-0.17733724415302277,-0.2912890911102295,0.013684878125786781 +1769682062,114428416,0.0,0.0,0.0,1.0,-0.00018469311180524528,-0.004535980056971312,-0.002111992798745632,0.08111678808927536,-0.129020094871521,0.010398983024060726 +1769682062,147495680,0.0,0.0,0.0,1.0,-0.0004521500668488443,-0.004350882489234209,-0.002041808096691966,-0.12918151915073395,-0.081267349421978,-0.0036867123562842607 +1769682062,170418432,0.0,0.0,0.0,1.0,-0.00027051701908931136,-0.004313322715461254,-0.001995912054553628,-2.4738721549510956e-05,0.00010347097850171849,0.004767187405377626 +1769682062,214727424,0.0,0.0,0.0,1.0,-9.57758747972548e-05,-0.0042640650644898415,-0.0019100909121334553,-0.21035002171993256,0.047850705683231354,-0.008055860176682472 +1769682062,260874240,0.0,0.0,0.0,1.0,-0.0004897692706435919,-0.004249386489391327,-0.0018440485000610352,-0.08119921386241913,0.12917892634868622,-0.0020018049981445074 +1769682062,270494976,0.0,0.0,0.0,1.0,-0.0003419428539928049,-0.004216545727103949,-0.0018211358692497015,-0.03316967189311981,0.3393131494522095,-0.015857914462685585 +1769682062,306459904,0.0,0.0,0.0,1.0,-0.00023594064987264574,-0.004096328746527433,-0.0017697628354653716,0.04791844263672829,0.21060539782047272,0.007582669146358967 +1769682062,350722816,0.0,0.0,0.0,1.0,-0.00032450686558149755,-0.004113087896257639,-0.0017959977267310023,0.08125490695238113,-0.12931925058364868,-0.005186930298805237 +1769682062,381076992,0.0,0.0,0.0,1.0,-0.0010422051418572664,-0.003462578170001507,-0.0018742054235190153,-0.04762088879942894,-0.2119774967432022,-0.07074110954999924 +1769682062,420088320,0.0,0.0,0.0,1.0,-0.00037932663690298796,-0.0016415145946666598,-0.0019211015896871686,0.08166411519050598,-0.13131938874721527,-0.09816641360521317 +1769682062,458150912,0.0,0.0,0.0,1.0,9.187040996039286e-05,0.0002528869081288576,-0.0019881478510797024,0.2586175501346588,0.16095426678657532,-0.07273154705762863 +1769682062,481500672,0.0,0.0,0.0,1.0,-0.00017942997510544956,0.0010979862418025732,-0.002023184671998024,-0.25805529952049255,-0.1637764275074005,-0.05718258395791054 +1769682062,514173696,0.0,0.0,0.0,1.0,-1.9988867279607803e-05,0.0015551599208265543,-0.0020392362494021654,-0.17683550715446472,-0.29264816641807556,-0.04213649779558182 +1769682062,565570304,0.0,0.0,0.0,1.0,-6.538226443808526e-05,0.0017389842541888356,-0.0020699575543403625,-0.12907016277313232,-0.08162355422973633,-0.015496155247092247 +1769682062,576015616,0.0,0.0,0.0,1.0,-0.0006319154053926468,-0.00023371496354229748,-0.0021285463590174913,0.29195499420166016,-0.1782173365354538,-0.054489005357027054 +1769682062,614705664,0.0,0.0,0.0,1.0,-0.0005339134950190783,-0.002892144490033388,-0.002106931759044528,-0.08110467344522476,0.12819723784923553,-0.04484898969531059 +1769682062,651247360,0.0,0.0,0.0,1.0,-0.0005175728583708405,-0.005654257256537676,-0.0020722923800349236,0.4209694564342499,-0.09624025970697403,-0.02599007822573185 +1769682062,688560384,0.0,0.0,0.0,1.0,-0.0008927796152420342,-0.006883062422275543,-0.0020179764833301306,0.21048276126384735,-0.04809414595365524,-0.01244142185896635 +1769682062,714757120,0.0,0.0,0.0,1.0,-0.000686143699567765,-0.007642962504178286,-0.001978344516828656,0.12907099723815918,0.08156225085258484,0.010653024539351463 +1769682062,752143616,0.0,0.0,0.0,1.0,-0.0014082624111324549,-0.007564800791442394,-0.0018993940902873874,-0.00010635479702614248,0.0006647866684943438,0.030987124890089035 +1769682062,781166592,0.0,0.0,0.0,1.0,-0.0012318426743149757,-0.0071851215325295925,-0.0018401724519208074,-0.08137869834899902,0.12937574088573456,0.011276469565927982 +1769682062,817372416,0.0,0.0,0.0,1.0,-0.0016242752317339182,-0.006837255787104368,-0.0017740190960466862,0.033488236367702484,-0.33879876136779785,0.03834163397550583 +1769682062,854668032,0.0,0.0,0.0,1.0,-0.001699381391517818,-0.006322749424725771,-0.0016813596012070775,0.21042373776435852,-0.04756803438067436,0.008745616301894188 +1769682062,881362688,0.0,0.0,0.0,1.0,-0.001587543054483831,-0.0059942337684333324,-0.0016331642400473356,0.12906767427921295,0.08152320235967636,0.006944774650037289 +1769682062,914379264,0.0,0.0,0.0,1.0,-0.0018615989247336984,-0.005815146490931511,-0.001545313629321754,0.1627071052789688,-0.25792762637138367,0.014204446226358414 +1769682062,960131840,0.0,0.0,0.0,1.0,-0.0014949798351153731,-0.005789256654679775,-0.0014559444971382618,0.0813487321138382,-0.12882079184055328,0.013630674220621586 +1769682062,970407168,0.0,0.0,0.0,1.0,-0.0013841288164258003,-0.005675298627465963,-0.0014079082757234573,0.21045571565628052,-0.0477069690823555,0.0002459166571497917 +1769682063,14358528,0.0,0.0,0.0,1.0,-0.0010385969653725624,-0.0057938056997954845,-0.001304789213463664,-0.08138349652290344,0.12904112040996552,-0.0028655254282057285 +1769682063,54328320,0.0,0.0,0.0,1.0,-0.0014172886731103063,-0.005889187101274729,-0.0012083083856850863,-1.8902283045463264e-05,0.00025029698736034334,0.011918294243514538 +1769682063,83657472,0.0,0.0,0.0,1.0,-0.0012333136983215809,-0.005828579887747765,-0.0011629867367446423,0.047654278576374054,0.210641011595726,0.006382617633789778 +1769682063,115326208,0.0,0.0,0.0,1.0,-0.0012962346663698554,-0.005850664339959621,-0.0011194022372364998,-0.1290590763092041,-0.08143604546785355,-0.0008402204839512706 +1769682063,150501376,0.0,0.0,0.0,1.0,-0.0009619523189030588,-0.005815938115119934,-0.0010508728446438909,0.08141044527292252,-0.12910300493240356,-0.0008002594113349915 +1769682063,180758272,0.0,0.0,0.0,1.0,-0.000621666491497308,-0.00556657649576664,-0.0009737665532156825,-0.04764818772673607,-0.210322305560112,0.009116144850850105 +1769682063,217250304,0.0,0.0,0.0,1.0,-0.0005688997334800661,-0.0054891593754291534,-0.0009091407991945744,0.04761768877506256,0.2110441029071808,0.02544243447482586 +1769682063,254007808,0.0,0.0,0.0,1.0,-0.0006938702426850796,-0.003379658330231905,-0.000936869066208601,-0.08134584128856659,0.12584540247917175,-0.15528033673763275 +1769682063,283529728,0.0,0.0,0.0,1.0,-0.00018356683722231537,-0.0006859528948552907,-0.0009075103444047272,0.33957427740097046,0.031192749738693237,-0.12569519877433777 +1769682063,314435840,0.0,0.0,0.0,1.0,-1.324979166383855e-05,0.0011416046181693673,-0.0008912310586310923,-0.16280891001224518,0.2559497058391571,-0.10555881261825562 +1769682063,358909440,0.0,0.0,0.0,1.0,0.00011326731328153983,0.0023810239508748055,-0.0008754637674428523,0.04766150563955307,0.20846949517726898,-0.09850915521383286 +1769682063,368221184,0.0,0.0,0.0,1.0,0.00030848640017211437,0.0030823717825114727,-0.0008884347043931484,-0.047587230801582336,-0.21110005676746368,-0.027827883139252663 +1769682063,414724352,0.0,0.0,0.0,1.0,-0.00015582946070935577,0.003242019098252058,-0.0009598663891665637,0.08144021779298782,-0.12905867397785187,0.00036314886528998613 +1769682063,448334080,0.0,0.0,0.0,1.0,-0.0005901078693568707,0.002646882552653551,-0.0010520867072045803,-3.485253546386957e-05,0.0008430797606706619,0.04052240028977394 +1769682063,481045760,0.0,0.0,0.0,1.0,-0.0007210648036561906,0.0020228922367095947,-0.0010980915976688266,-0.17664411664009094,-0.2912732660770416,0.03450765833258629 +1769682063,501830144,0.0,0.0,0.0,1.0,-0.0008526078308932483,0.0014996356330811977,-0.001114723621867597,0.08141471445560455,-0.1282339245080948,0.03970479220151901 +1769682063,544813056,0.0,0.0,0.0,1.0,-0.0010856916196644306,0.0001867518585640937,-0.0011364687234163284,-3.1876348657533526e-05,0.0006672384915873408,0.03217959776520729 +1769682063,581277952,0.0,0.0,0.0,1.0,-0.00109388108830899,-0.0007873136200942099,-0.0011296954471617937,0.08145029842853546,-0.12874753773212433,0.014666961506009102 +1769682063,599037952,0.0,0.0,0.0,1.0,-0.000998354167677462,-0.0010801621247082949,-0.0010995051125064492,0.16290462017059326,-0.2574429214000702,0.03170841932296753 +1769682063,644664832,0.0,0.0,0.0,1.0,-0.0011972303036600351,-0.0014764845836907625,-0.0010267930338159204,-0.16294728219509125,0.2581257224082947,0.001683324109762907 +1769682063,681632256,0.0,0.0,0.0,1.0,-0.0015872225631028414,-0.001404628506861627,-0.0009400136768817902,0.16295522451400757,-0.2580702602863312,0.0006771606858819723 +1769682063,699901696,0.0,0.0,0.0,1.0,-0.001948406919836998,-0.0011492206249386072,-0.0008846304845064878,0.08146228641271591,-0.12859317660331726,0.021785041317343712 +1769682063,749128192,0.0,0.0,0.0,1.0,-0.0018323377007618546,-0.0006906449561938643,-0.0007862155907787383,0.0814833864569664,-0.12898163497447968,0.002700266893953085 +1769682063,777780480,0.0,0.0,0.0,1.0,-0.001970175886526704,-0.0005506653105840087,-0.0007409905665554106,-0.033961180597543716,0.33940714597702026,-0.008143371902406216 +1769682063,814932480,0.0,0.0,0.0,1.0,-0.0022825105115771294,-0.0003910787927452475,-0.0006845742464065552,-0.12900719046592712,-0.0814499706029892,0.0027504349127411842 +1769682063,848360960,0.0,0.0,0.0,1.0,-0.0015017901314422488,-0.0005749218398705125,-0.0006218444905243814,0.25801002979278564,0.16290700435638428,-0.005495460703969002 +1769682063,880963328,0.0,0.0,0.0,1.0,-0.0013012198032811284,-0.0006016368279233575,-0.000590460782404989,-7.65657750889659e-06,0.00021680774807464331,0.01072665024548769 +1769682063,915648256,0.0,0.0,0.0,1.0,-0.0012513877591118217,-0.0007610722677782178,-0.0005421246169134974,-9.907962521538138e-06,0.00028850746457464993,0.014302210882306099 +1769682063,949571840,0.0,0.0,0.0,1.0,-0.0009088314836844802,-0.0008705185609869659,-0.0004951009177602828,0.1289892941713333,0.0817968025803566,0.013939238153398037 +1769682063,981070592,0.0,0.0,0.0,1.0,-0.0011017958167940378,-0.0008810909348540008,-0.00048119682469405234,-0.16300329566001892,0.2579425573348999,-0.005285531282424927 +1769682064,14349824,0.0,0.0,0.0,1.0,-0.0012034527026116848,-0.0009721992537379265,-0.0004794101696461439,-7.210874173324555e-07,2.390308873145841e-05,0.00119185377843678 +1769682064,62610944,0.0,0.0,0.0,1.0,-0.000929835659917444,-0.0009449224453419447,-0.0004853280261158943,-0.09498081356287003,-0.4208485186100006,0.011946775019168854 +1769682064,72295680,0.0,0.0,0.0,1.0,-0.0010749647626653314,-0.0009013530216179788,-0.0004906264948658645,0.03400908783078194,-0.3390234410762787,0.02706744894385338 +1769682064,114809088,0.0,0.0,0.0,1.0,-0.0004904030356556177,-0.0007388204103335738,-0.0004667802422773093,-0.33950233459472656,-0.033785928040742874,0.012421783991158009 +1769682064,159883008,0.0,0.0,0.0,1.0,-0.0002568503259681165,-0.00043103579082526267,-0.00043543754145503044,0.3394932746887207,0.034123510122299194,0.004258804954588413 +1769682064,169710336,0.0,0.0,0.0,1.0,-0.00021512704552151263,-0.0002533493097871542,-0.0004338846483733505,0.08151880651712418,-0.12917837500572205,-0.008114092983305454 +1769682064,216145152,0.0,0.0,0.0,1.0,-2.301870335941203e-05,0.0006479122093878686,-0.0003970204561483115,-0.04745769500732422,-0.21110571920871735,-0.028005680069327354 +1769682064,248192512,0.0,0.0,0.0,1.0,0.00012157643504906446,0.001267240266315639,-0.0003449998330324888,0.12900088727474213,0.08105065673589706,-0.024200594052672386 +1769682064,281200640,0.0,0.0,0.0,1.0,0.0003128176904283464,0.0015444651944562793,-0.0002937716490123421,0.29203730821609497,-0.17684675753116608,-0.01775800809264183 +1769682064,315134464,0.0,0.0,0.0,1.0,0.00012823473662137985,0.0016620344249531627,-0.00025311383069492877,-0.21049879491329193,0.0472177155315876,-0.013001742772758007 +1769682064,353173504,0.0,0.0,0.0,1.0,3.541521437000483e-05,0.0015723651740700006,-0.0002474354696460068,0.08149836212396622,-0.1283404529094696,0.0336228646337986 +1769682064,381402368,0.0,0.0,0.0,1.0,-0.0003277529904153198,0.0012144556967541575,-0.00025544280651956797,0.1764524281024933,0.29192525148391724,-0.008083748631179333 +1769682064,415518976,0.0,0.0,0.0,1.0,-0.0004345700144767761,0.0010224571451544762,-0.0002502505376469344,0.08150532096624374,-0.12853018939495087,0.024091510102152824 +1769682064,454309120,0.0,0.0,0.0,1.0,-0.0005763124208897352,0.0006106776418164372,-0.00024047296028584242,0.21048657596111298,-0.04692564159631729,0.027338406071066856 +1769682064,467893760,0.0,0.0,0.0,1.0,-0.0007832420524209738,0.0006307254079729319,-0.00022599069052375853,-0.08152981102466583,0.12909983098506927,0.004514293745160103 +1769682064,514855424,0.0,0.0,0.0,1.0,-0.0007333831745199859,0.002660703146830201,-0.00020037377544213086,0.21047621965408325,-0.04673437029123306,0.036889463663101196 +1769682064,548548096,0.0,0.0,0.0,1.0,-0.0009603979997336864,0.003989215474575758,-0.00016697862884029746,0.04742560535669327,0.21108363568782806,0.026858016848564148 +1769682064,569998336,0.0,0.0,0.0,1.0,-0.0009328675805591047,0.004587937146425247,-0.00011234245175728574,-0.04748758673667908,-0.2099480926990509,0.03034350275993347 +1769682064,615154688,0.0,0.0,0.0,1.0,-0.0006331131444312632,0.0051405481062829494,-1.6982658053166233e-05,-0.04746929183602333,-0.21030336618423462,0.012449223548173904 +1769682064,652110336,0.0,0.0,0.0,1.0,-0.0009317376534454525,0.005479856394231319,0.00010149297304451466,-0.1289948970079422,-0.08137098699808121,0.00856372993439436 +1769682064,681381376,0.0,0.0,0.0,1.0,-0.0008848992874845862,0.005412200931459665,0.00021189305698499084,-0.08152728527784348,0.1290038377046585,-0.00030276726465672255 +1769682064,703337728,0.0,0.0,0.0,1.0,-0.0008841271046549082,0.005355700384825468,0.0002877872611861676,-4.334924597060308e-06,4.704171806224622e-05,0.0023837194312363863 +1769682064,748460544,0.0,0.0,0.0,1.0,-0.0010513665620237589,0.005144595168530941,0.00047231820644810796,1.4874596672598273e-05,-0.00014079792890697718,-0.007151160854846239 +1769682064,781901824,0.0,0.0,0.0,1.0,-0.0005454101483337581,0.00491768354550004,0.0005905131110921502,0.12896732985973358,0.08169399946928024,0.008219820447266102 +1769682064,814890240,0.0,0.0,0.0,1.0,-0.0003926142235286534,0.004550199490040541,0.0007039930205792189,-0.21050384640693665,0.047458112239837646,-0.00143167853821069 +1769682064,857575680,0.0,0.0,0.0,1.0,-0.0001189074173453264,0.004231571685522795,0.0008261853945441544,0.25796112418174744,0.1631891429424286,0.00697754742577672 +1769682064,873666304,0.0,0.0,0.0,1.0,-0.00018988517695106566,0.0038934475742280483,0.0009915356058627367,0.08149529248476028,-0.1288968175649643,0.006325681693851948 +1769682064,914503424,0.0,0.0,0.0,1.0,-0.00020107097225263715,0.003912101034075022,0.0011272416450083256,-0.17651335895061493,-0.29183652997016907,0.011202564463019371 +1769682064,949531648,0.0,0.0,0.0,1.0,9.663257515057921e-05,0.0039035461377352476,0.0013127689016982913,4.5438791858032346e-05,-0.000304358167340979,-0.01549416221678257 +1769682064,971125248,0.0,0.0,0.0,1.0,0.00015406739839818329,0.00384715897962451,0.0014035124331712723,-0.04745803773403168,-0.21083256602287292,-0.01507814135402441 +1769682065,15328768,0.0,0.0,0.0,1.0,-0.00010863556963158771,0.00389954075217247,0.0015818929532542825,1.8861355783883482e-05,-0.00011709345562849194,-0.005959288217127323 +1769682065,48721920,0.0,0.0,0.0,1.0,0.0003823346924036741,0.003981519024819136,0.0017864943947643042,0.08147210627794266,-0.12898650765419006,0.0028064721263945103 +1769682065,80981504,0.0,0.0,0.0,1.0,0.00012817390961572528,0.004074954893440008,0.0019677705131471157,-0.04759335517883301,-0.21023806929588318,0.01470138505101204 +1769682065,116196864,0.0,0.0,0.0,1.0,0.00040061335312202573,0.00418202206492424,0.00217933370731771,-0.0814516693353653,0.12897279858589172,-0.004020477645099163 +1769682065,154633216,0.0,0.0,0.0,1.0,0.0006427782354876399,0.0038598054088652134,0.0024710530415177345,0.1764424741268158,0.2928413450717926,0.04377581179141998 +1769682065,181611520,0.0,0.0,0.0,1.0,0.00041399867041036487,0.002354753203690052,0.0027024205774068832,-0.2584080100059509,-0.16116328537464142,0.08803979307413101 +1769682065,214542848,0.0,0.0,0.0,1.0,0.00019421798060648143,0.001012306078337133,0.0029282723553478718,-0.08170181512832642,0.13045072555541992,0.06984542310237885 +1769682065,262968320,0.0,0.0,0.0,1.0,0.0002929075271822512,-0.0003347863384988159,0.003171690972521901,-0.00024808908347040415,0.0012699415674433112,0.06436005234718323 +1769682065,274883328,0.0,0.0,0.0,1.0,0.00016983403475023806,-0.0007299479912035167,0.0033603848423808813,0.08126966655254364,-0.1284000426530838,0.03503907471895218 +1769682065,315156480,0.0,0.0,0.0,1.0,7.50465042074211e-05,-0.0009954074630513787,0.0035134986974298954,0.08131169527769089,-0.12869074940681458,0.02073507569730282 +1769682065,348409856,0.0,0.0,0.0,1.0,0.00011521320993779227,-0.0010360804153606296,0.00368844554759562,-0.08132527768611908,0.12886720895767212,-0.0123890470713377 +1769682065,370297600,0.0,0.0,0.0,1.0,4.863106005359441e-05,-0.0009356773225590587,0.0037765365559607744,8.025209535844624e-05,-0.0004236143722664565,-0.021453354507684708 +1769682065,415511040,0.0,0.0,0.0,1.0,-0.0003826417960226536,-0.0006679053185507655,0.003949977457523346,-0.3058933913707733,-0.3735218644142151,-0.017606832087039948 +1769682065,448700672,0.0,0.0,0.0,1.0,-0.000221018010051921,-0.00032449958962388337,0.0041138543747365475,0.081341452896595,-0.12925206124782562,-0.005495572462677956 +1769682065,481463296,0.0,0.0,0.0,1.0,-0.00043419847497716546,0.0011338680051267147,0.004229258745908737,-0.16270363330841064,0.25880661606788635,0.02529258467257023 +1769682065,515089920,0.0,0.0,0.0,1.0,-7.635002839379013e-05,0.0025602250825613737,0.004355074372142553,-8.080591214820743e-05,0.00042313264566473663,0.021453361958265305 +1769682065,551361280,0.0,0.0,0.0,1.0,0.00010948070121230558,0.00377836124971509,0.004513701889663935,0.04785702005028725,0.21058310568332672,0.006764780264347792 +1769682065,581227264,0.0,0.0,0.0,1.0,9.942601900547743e-05,0.004335206467658281,0.004638385958969593,-0.129197895526886,-0.08106660097837448,0.009425565600395203 +1769682065,615428864,0.0,0.0,0.0,1.0,1.8246937543153763e-06,0.004563564900308847,0.004762828350067139,-9.895135008264333e-06,4.699812416220084e-05,0.002383703365921974 +1769682065,660287744,0.0,0.0,0.0,1.0,5.1791153964586556e-05,0.004401359707117081,0.004880839493125677,0.1291266828775406,0.08147607743740082,0.013254542835056782 +1769682065,669043200,0.0,0.0,0.0,1.0,-3.1174233299680054e-05,0.00426979037001729,0.0050260210409760475,0.33954209089279175,0.03334483504295349,0.009186643175780773 +1769682065,714778880,0.0,0.0,0.0,1.0,0.0003612875589169562,0.004105324856936932,0.005246372893452644,-0.08108056336641312,0.1288803368806839,-0.018413538113236427 +1769682065,750295296,0.0,0.0,0.0,1.0,0.00023378044716082513,0.0038108977023512125,0.005491306073963642,-0.048128534108400345,-0.21025317907333374,0.007498479448258877 +1769682065,771294976,0.0,0.0,0.0,1.0,0.0001506009721197188,0.0037169698625802994,0.005622221622616053,0.16222259402275085,-0.2584485709667206,0.0046869986690580845 +1769682065,816030720,0.0,0.0,0.0,1.0,0.0007105401600711048,0.003413981990888715,0.0059589846059679985,0.032969191670417786,-0.3398445248603821,-0.00862455740571022 +1769682065,853338624,0.0,0.0,0.0,1.0,0.0004866492818109691,0.0033659408800303936,0.006274993531405926,-0.2585480511188507,-0.16215814650058746,-0.0016792949754744768 +1769682065,881689088,0.0,0.0,0.0,1.0,0.0003947959921788424,0.00331084500066936,0.006506169680505991,0.12932337820529938,0.08092441409826279,-0.0057039083912968636 +1769682065,911521792,0.0,0.0,0.0,1.0,0.0002850957971531898,0.0032132668420672417,0.006718092132359743,-0.2586864233016968,-0.1617734730243683,0.01257660798728466 +1769682065,944504832,0.0,0.0,0.0,1.0,0.0003986043739132583,0.0032958206720650196,0.006885422859340906,0.42056024074554443,-0.09652471542358398,0.0113137261942029 +1769682065,967592192,0.0,0.0,0.0,1.0,0.0004003573558293283,0.0032951722387224436,0.007015627343207598,-0.129271000623703,-0.08122289925813675,-0.013400914147496223 +1769682066,14743552,0.0,0.0,0.0,1.0,0.00033603806514292955,0.0033035119995474815,0.007148848846554756,0.2103080153465271,-0.04855510964989662,-0.003828497603535652 +1769682066,63951616,0.0,0.0,0.0,1.0,-7.21897158655338e-05,0.003363365773111582,0.007242071907967329,-0.12944279611110687,-0.08069977909326553,0.009210825897753239 +1769682066,73490432,0.0,0.0,0.0,1.0,0.00015537839499302208,0.0033963376190513372,0.007322611752897501,6.899893924128264e-05,-0.00023654317192267627,-0.011918390169739723 +1769682066,114445056,0.0,0.0,0.0,1.0,-3.108850069111213e-05,0.0034429088700562716,0.0074076284654438496,-0.25893229246139526,-0.1613801121711731,0.01360232662409544 +1769682066,155020288,0.0,0.0,0.0,1.0,-0.00015980511670932174,0.0026107782032340765,0.007533382624387741,0.08025136590003967,-0.12766538560390472,0.09124824404716492 +1769682066,169782528,0.0,0.0,0.0,1.0,-2.663792110979557e-05,0.0011303230421617627,0.007672930136322975,-0.13001300394535065,-0.07895112782716751,0.09140406548976898 +1769682066,215048960,0.0,0.0,0.0,1.0,-1.0609808668959886e-05,-0.00010079325875267386,0.007890713401138783,0.3394284248352051,0.032834116369485855,0.04551060497760773 +1769682066,248492544,0.0,0.0,0.0,1.0,-3.389491030247882e-05,-0.0009076974238269031,0.008095158264040947,-0.00012149734538979828,0.00040243694093078375,0.020261229947209358 +1769682066,286859520,0.0,0.0,0.0,1.0,0.00014726322842761874,-0.0010901937494054437,0.008265363052487373,-0.12963813543319702,-0.08030430227518082,0.01751566305756569 +1769682066,315307008,0.0,0.0,0.0,1.0,-0.0001114594197133556,-0.0010787098435685039,0.00840367004275322,0.2590542435646057,0.1614197939634323,0.009058668278157711 +1769682066,345708032,0.0,0.0,0.0,1.0,0.00013401669275481254,-0.0008041121764108539,0.008568703196942806,0.21026837825775146,-0.04937922582030296,-0.018049724400043488 +1769682066,381553408,0.0,0.0,0.0,1.0,-6.094500713516027e-05,-0.0005862288526259363,0.008765743114054203,-0.4202152192592621,0.09793313592672348,-0.012754172086715698 +1769682066,413714432,0.0,0.0,0.0,1.0,0.00012169532419648021,-0.00040216889465227723,0.008862702175974846,-0.08040423691272736,0.1292571723461151,-0.01973273605108261 +1769682066,454605568,0.0,0.0,0.0,1.0,0.00016481376951560378,0.0006935506244190037,0.009149967692792416,-0.2906348407268524,0.17911489307880402,0.010241208598017693 +1769682066,483993344,0.0,0.0,0.0,1.0,0.00023452653840649873,0.001780967228114605,0.009349796921014786,-0.12976446747779846,-0.08012298494577408,0.015140208415687084 +1769682066,514940928,0.0,0.0,0.0,1.0,0.0003225734399165958,0.002522889291867614,0.009559649042785168,-0.1607113927602768,0.25924596190452576,-0.01088578812777996 +1769682066,567768064,0.0,0.0,0.0,1.0,0.0005073013599030674,0.0031822752207517624,0.009799285791814327,0.03079543635249138,-0.3393672704696655,0.024834096431732178 +1769682066,569479936,0.0,0.0,0.0,1.0,0.00036462186835706234,0.0033205754589289427,0.009942387230694294,-0.00010926429240498692,0.00035642966395244,0.017877517268061638 +1769682066,617638656,0.0,0.0,0.0,1.0,0.000355868018232286,0.003247178392484784,0.010183006525039673,-0.21009047329425812,0.04972166568040848,0.008429219014942646 +1769682066,649973504,0.0,0.0,0.0,1.0,0.00013488862896338105,0.00322123896330595,0.010336474515497684,-0.17946089804172516,-0.29011285305023193,0.007034860551357269 +1769682066,681453824,0.0,0.0,0.0,1.0,3.0370705644600093e-05,0.003076514694839716,0.010400653816759586,0.16036872565746307,-0.2598535120487213,-0.0057005807757377625 +1769682066,701700096,0.0,0.0,0.0,1.0,0.00023304030764847994,0.0029605827294290066,0.010445863008499146,-0.20995347201824188,0.04963177442550659,-0.0059334710240364075 +1769682066,747170560,0.0,0.0,0.0,1.0,-4.179941606707871e-05,0.00286021176725626,0.010439462959766388,-0.049669910222291946,-0.21040120720863342,-0.019971609115600586 +1769682066,781495552,0.0,0.0,0.0,1.0,-0.00017090470646508038,0.0026667534839361906,0.010419554077088833,0.0499153807759285,0.20990416407585144,-0.0038587558083236217 +1769682066,816462848,0.0,0.0,0.0,1.0,0.00017898248916026205,0.002709031803533435,0.01043924130499363,0.00015365330909844488,-0.00045245158253237605,-0.022644925862550735 +1769682066,850797056,0.0,0.0,0.0,1.0,-6.03513399255462e-05,0.0026492751203477383,0.010485666804015636,-0.12984447181224823,-0.08031246811151505,-0.018363656476140022 +1769682066,869662208,0.0,0.0,0.0,1.0,0.00024472898803651333,0.0026849291753023863,0.010593601502478123,-0.20981252193450928,0.049862079322338104,-0.013182764872908592 +1769682066,901763584,0.0,0.0,0.0,1.0,0.0003560768673196435,0.002628125948831439,0.010732973925769329,-0.07981093227863312,0.12989699840545654,-0.007925959303975105 +1769682066,948372736,0.0,0.0,0.0,1.0,7.106347766239196e-05,0.0026355357840657234,0.0110152093693614,0.2896159589290619,-0.18029393255710602,0.00567264948040247 +1769682066,974065408,0.0,0.0,0.0,1.0,0.00020565908926073462,0.002696871291846037,0.0111248092725873,0.20988298952579498,-0.05044782534241676,-0.004637360572814941 +1769682067,16069120,0.0,0.0,0.0,1.0,0.00016355373372789472,0.002737634116783738,0.011343722231686115,-0.31075528264045715,-0.36896878480911255,0.014667203649878502 +1769682067,50342912,0.0,0.0,0.0,1.0,0.00037348276237025857,0.002794120693579316,0.011601792648434639,4.3986110540572554e-05,-0.00011945288861170411,-0.005959109403192997 +1769682067,81325312,0.0,0.0,0.0,1.0,0.00026108184829354286,0.0028484617359936237,0.011799870058894157,0.13023291528224945,0.07946483790874481,-0.006584228947758675 +1769682067,103924224,0.0,0.0,0.0,1.0,4.869337135460228e-05,0.002565777860581875,0.011914885602891445,-0.2606295943260193,-0.158532977104187,0.029840685427188873 +1769682067,152974336,0.0,0.0,0.0,1.0,-9.55223513301462e-05,0.0008562958682887256,0.012177865952253342,-0.05111146718263626,-0.20883458852767944,0.046729493886232376 +1769682067,181705984,0.0,0.0,0.0,1.0,3.486420609988272e-06,0.0001428250689059496,0.012283663265407085,0.33982783555984497,0.029034079983830452,0.023452138528227806 +1769682067,200770304,0.0,0.0,0.0,1.0,-0.00039515207754448056,-0.00028279179241508245,0.012318342924118042,-0.0003243766550440341,0.0008609220385551453,0.04290550947189331 +1769682067,261800192,0.0,0.0,0.0,1.0,-0.00034600371145643294,-0.0005631503299809992,0.012386997230350971,0.07928131520748138,-0.13024713099002838,0.006785699166357517 +1769682067,275688192,0.0,0.0,0.0,1.0,-0.0002964046725537628,-0.0007094427710399032,0.01239760871976614,-0.2607101500034332,-0.15865930914878845,-0.0035451073199510574 +1769682067,314756352,0.0,0.0,0.0,1.0,-0.0002702584897633642,-0.00069242570316419,0.012481802143156528,-0.20957013964653015,0.051017723977565765,-0.009742018766701221 +1769682067,349707520,0.0,0.0,0.0,1.0,-0.0002603091415949166,-0.0005709006800316274,0.012569938786327839,0.340023398399353,0.02795708179473877,0.005544963758438826 +1769682067,370775296,0.0,0.0,0.0,1.0,-0.00012220811913721263,-0.00044280843576416373,0.012627254240214825,-0.13033053278923035,-0.07950090616941452,-0.0184513870626688 +1769682067,414894080,0.0,0.0,0.0,1.0,0.00023466443235520273,0.00014810150605626404,0.012755370698869228,-0.0001676384563324973,0.0004539853543974459,0.02264479547739029 +1769682067,450336256,0.0,0.0,0.0,1.0,-0.00031421237508766353,0.0013411190593615174,0.01286261435598135,-0.15804778039455414,0.2612757384777069,0.005511234048753977 +1769682067,468816128,0.0,0.0,0.0,1.0,-0.0002499788533896208,0.0017619746504351497,0.012922454625368118,0.20948344469070435,-0.05149152874946594,0.007364492863416672 +1769682067,515846144,0.0,0.0,0.0,1.0,2.6085239369422197e-05,0.0023757629096508026,0.012974749319255352,-0.4191098213195801,0.10372583568096161,0.011454246938228607 +1769682067,545666816,0.0,0.0,0.0,1.0,-0.0002492157509550452,0.0025674595963209867,0.013024115934967995,0.15773500502109528,-0.26143595576286316,-0.0042885951697826385 +1769682067,567542784,0.0,0.0,0.0,1.0,0.00015338763478212059,0.002663980470970273,0.013090396299958229,0.07877526432275772,-0.13064129650592804,0.003225439228117466 +1769682067,617783296,0.0,0.0,0.0,1.0,0.0004015051817987114,0.0025515675079077482,0.013248834758996964,0.00012035468535032123,-0.000310999748762697,-0.015493628568947315 +1769682067,655936000,0.0,0.0,0.0,1.0,0.00029167463071644306,0.0023492956534028053,0.013392114080488682,-0.026400169357657433,0.3398054540157318,-0.021340128034353256 +1769682067,682322176,0.0,0.0,0.0,1.0,6.519233284052461e-05,0.0023105554282665253,0.01350137684494257,0.15714702010154724,-0.2614651024341583,0.008881828747689724 +1769682067,714955520,0.0,0.0,0.0,1.0,0.00021872342040296644,0.0021633224096149206,0.013668731786310673,7.604228449054062e-05,-0.00019167890422977507,-0.009534520097076893 +1769682067,763396608,0.0,0.0,0.0,1.0,0.0002694682916626334,0.0020490079186856747,0.013904284685850143,-0.07859101891517639,0.13116759061813354,0.013421911746263504 +1769682067,772164352,0.0,0.0,0.0,1.0,9.971918188966811e-05,0.0020840163342654705,0.014030246995389462,-0.13080212473869324,-0.07864377647638321,-0.010206179693341255 +1769682067,815911936,0.0,0.0,0.0,1.0,0.00030893899383954704,0.0019968515262007713,0.014289154671132565,-0.41844096779823303,0.10480129718780518,-0.01983029954135418 +1769682067,850230784,0.0,0.0,0.0,1.0,5.9359706938266754e-05,0.0020423445384949446,0.014504645019769669,0.07836765795946121,-0.13118359446525574,-0.008636323735117912 +1769682067,883884800,0.0,0.0,0.0,1.0,-7.440059562213719e-06,0.0019460712792351842,0.014585782773792744,-0.3147825300693512,-0.3656620383262634,0.005963297560811043 +1769682067,905762304,0.0,0.0,0.0,1.0,-7.09261221345514e-05,0.0018502670573070645,0.014728750102221966,-0.15873898565769196,-0.6273812651634216,0.018481703475117683 +1769682067,949771264,0.0,0.0,0.0,1.0,0.00012678744678851217,0.0020213911775499582,0.014831873588263988,-0.20924997329711914,0.05316520109772682,0.006711832247674465 +1769682067,981664768,0.0,0.0,0.0,1.0,-0.00016703670553397387,0.002074298681691289,0.014876087196171284,-5.0293827371206135e-05,0.00012014432286377996,0.005959045607596636 +1769682068,17246976,0.0,0.0,0.0,1.0,-0.00016362802125513554,0.001977363834157586,0.014914721250534058,-0.20894016325473785,0.05272722989320755,-0.024299923330545425 +1769682068,56690688,0.0,0.0,0.0,1.0,-0.00022968667326495051,0.0020197152625769377,0.014995047822594643,-0.07782917469739914,0.1310545802116394,-0.009270302951335907 +1769682068,81898752,0.0,0.0,0.0,1.0,-4.759898001793772e-05,0.0014524429570883512,0.01507942471653223,-0.13154245913028717,-0.07713369280099869,0.03500295430421829 +1769682068,99915264,0.0,0.0,0.0,1.0,-2.144409518223256e-05,0.0008149095810949802,0.0151784997433424,-0.13148438930511475,-0.07728610187768936,0.025465888902544975 +1769682068,158731264,0.0,0.0,0.0,1.0,-2.008488809224218e-05,-1.7875740013550967e-05,0.015383466146886349,-0.20941725373268127,0.05450808256864548,0.04359976202249527 +1769682068,171855616,0.0,0.0,0.0,1.0,-0.0002183036267524585,-0.0003850840439554304,0.015570846386253834,-0.13157784938812256,-0.07712049037218094,0.02665710635483265 +1769682068,215074560,0.0,0.0,0.0,1.0,4.024767258670181e-05,-0.0006159662152640522,0.015890071168541908,-0.26291510462760925,-0.15486843883991241,0.013990936800837517 +1769682068,250471680,0.0,0.0,0.0,1.0,-0.00010612074402160943,-0.0006951011018827558,0.016193464398384094,0.05420234799385071,0.2083686888217926,-0.029976611956954002 +1769682068,279708928,0.0,0.0,0.0,1.0,0.00037871699896641076,-0.0006429371424019337,0.01634243130683899,-0.053905390202999115,-0.20921720564365387,-0.012926789931952953 +1769682068,317196032,0.0,0.0,0.0,1.0,-0.00024149456294253469,-0.0005140329012647271,0.01656121201813221,-0.1313057839870453,-0.0778818428516388,-0.025770345702767372 +1769682068,366028288,0.0,0.0,0.0,1.0,-0.00023411426809616387,-0.0002691856352612376,0.01668844185769558,0.15469148755073547,-0.26352086663246155,-0.014835947193205357 +1769682068,373295872,0.0,0.0,0.0,1.0,-0.0001760628802003339,0.0002910498878918588,0.016778700053691864,-0.20883718132972717,0.05445634573698044,0.0007182038389146328 +1769682068,420034816,0.0,0.0,0.0,1.0,-0.00016931045684032142,0.0009330864995718002,0.016824012622237206,-0.2632434070110321,-0.15443269908428192,-0.0074480511248111725 +1769682068,451804672,0.0,0.0,0.0,1.0,-0.0005630510859191418,0.0016640396788716316,0.01687873713672161,0.0770033523440361,-0.13160139322280884,0.006887876428663731 +1769682068,467650048,0.0,0.0,0.0,1.0,-0.00029544191784225404,0.001882148557342589,0.01691482774913311,-0.1318262666463852,-0.07678210735321045,0.011160219088196754 +1769682068,514882304,0.0,0.0,0.0,1.0,-0.00012106529902666807,0.002184363082051277,0.017008163034915924,0.20860478281974792,-0.05465003103017807,0.012432357296347618 +1769682068,567009024,0.0,0.0,0.0,1.0,0.00033245974918827415,0.0021584765054285526,0.017151596024632454,0.0001237037795362994,-0.0002889566821977496,-0.014301670715212822 +1769682068,581251584,0.0,0.0,0.0,1.0,0.0003237323253415525,0.0021832664497196674,0.017330633476376534,0.2638525664806366,0.15328501164913177,-0.011533601209521294 +1769682068,599630080,0.0,0.0,0.0,1.0,-8.437735959887505e-05,0.0021227786783128977,0.017407391220331192,0.07665286958217621,-0.13177447021007538,0.008103086613118649 +1769682068,648901376,0.0,0.0,0.0,1.0,1.1733645806089044e-05,0.0019305115565657616,0.017664335668087006,0.18750551342964172,0.2848030626773834,-0.019609369337558746 +1769682068,682166528,0.0,0.0,0.0,1.0,0.00022467912640422583,0.0017521983245387673,0.01776537299156189,0.15318939089775085,-0.2642199695110321,-0.0076061999425292015 +1769682068,715099392,0.0,0.0,0.0,1.0,-6.326241418719292e-06,0.0018322921823710203,0.017910974100232124,-0.05557609722018242,-0.20856449007987976,-0.0010415525175631046 +1769682068,749976832,0.0,0.0,0.0,1.0,0.00035858803312294185,0.0016996337799355388,0.018069814890623093,-0.20844145119190216,0.055697765201330185,-0.004187757149338722 +1769682068,781735424,0.0,0.0,0.0,1.0,-8.439761586487293e-06,0.0017726487712934613,0.01815997064113617,0.02039792574942112,-0.34053799510002136,0.005890482105314732 +1769682068,819792896,0.0,0.0,0.0,1.0,-6.907600618433207e-05,0.001784814172424376,0.01828089728951454,0.2085847705602646,-0.05638398230075836,-0.01843516156077385 +1769682068,853638912,0.0,0.0,0.0,1.0,-0.00022315603564493358,0.0017925059655681252,0.018418727442622185,-0.11241920292377472,-0.4163856506347656,0.02053362876176834 +1769682068,881828608,0.0,0.0,0.0,1.0,-0.00021190414554439485,0.0017215259140357375,0.018488997593522072,0.07600457966327667,-0.13220785558223724,0.005759233608841896 +1769682068,915045888,0.0,0.0,0.0,1.0,-0.0001022920769173652,0.0017345244996249676,0.01854427345097065,0.019560188055038452,-0.34053751826286316,0.008275997824966908 +1769682068,958238720,0.0,0.0,0.0,1.0,6.0530990594998e-05,0.0017501190304756165,0.018602464348077774,-0.26474207639694214,-0.15180625021457672,-0.0005548724438995123 +1769682068,971916800,0.0,0.0,0.0,1.0,6.89798325765878e-05,0.001745398622006178,0.018698157742619514,0.05669187381863594,0.20803098380565643,-0.012040074914693832 +1769682069,15511296,0.0,0.0,0.0,1.0,0.00014965928858146071,0.0017511022742837667,0.018865903839468956,-0.4164167046546936,0.11356663703918457,-0.00021921005100011826 +1769682069,50912000,0.0,0.0,0.0,1.0,2.0296720322221518e-06,0.0010846770601347089,0.01906280778348446,-0.0003121927729807794,0.0006770924665033817,0.03337029367685318 +1769682069,83518720,0.0,0.0,0.0,1.0,-0.00021685013780370355,0.0007326339255087078,0.0191375520080328,-0.00033482781145721674,0.0007254664087668061,0.03575388342142105 +1769682069,115322368,0.0,0.0,0.0,1.0,1.9397761207073927e-05,0.00011233650002395734,0.019275115802884102,0.07519438117742538,-0.13202840089797974,0.03080841340124607 +1769682069,151166208,0.0,0.0,0.0,1.0,-0.0005104900919832289,-0.00011479643580969423,0.019332239404320717,-0.057430364191532135,-0.2077869027853012,0.014410324394702911 +1769682069,167411712,0.0,0.0,0.0,1.0,-0.00024115316045936197,-0.000267887458903715,0.019320810213685036,0.1326856017112732,0.07535864412784576,0.0020944802090525627 +1769682069,217044992,0.0,0.0,0.0,1.0,-0.0002806895354297012,-0.0003733173361979425,0.019272545352578163,-0.05772615596652031,-0.20759981870651245,0.020365260541439056 +1769682069,248285952,0.0,0.0,0.0,1.0,-0.0005234670825302601,-0.0002307238755747676,0.01923811435699463,-0.26545271277427673,-0.150624617934227,-0.017297690734267235 +1769682069,282080000,0.0,0.0,0.0,1.0,-0.0002411113673588261,-0.00010945164831355214,0.019229399040341377,-0.05769626051187515,-0.20819850265979767,-0.013009677641093731 +1769682069,314832384,0.0,0.0,0.0,1.0,-0.00030342041281983256,-6.645602115895599e-05,0.019228676334023476,-0.07480743527412415,0.13258494436740875,-0.017686503008008003 +1769682069,356436480,0.0,0.0,0.0,1.0,-0.00019149278523400426,0.0003448612114880234,0.0192656721919775,-0.05824488773941994,-0.20745553076267242,0.02035820297896862 +1769682069,370805504,0.0,0.0,0.0,1.0,-0.0003145335940644145,0.001109686098061502,0.019303476437926292,-0.1912962645292282,-0.2823653817176819,0.013489596545696259 +1769682069,415119616,0.0,0.0,0.0,1.0,-0.00010044708324130625,0.0018280366202816367,0.019348815083503723,-0.20784839987754822,0.05856488272547722,0.008803565055131912 +1769682069,449536256,0.0,0.0,0.0,1.0,0.0002854249032679945,0.0022899117320775986,0.01949915662407875,-0.1332133412361145,-0.07437481731176376,0.010990908369421959 +1769682069,483289600,0.0,0.0,0.0,1.0,1.2192234862595797e-05,0.002366112545132637,0.01966487057507038,0.14901237189769745,-0.2662660479545593,0.005613888148218393 +1769682069,516258304,0.0,0.0,0.0,1.0,0.00022159900981932878,0.00236326502636075,0.01983039826154709,-7.916464528534561e-05,0.00016931371646933258,0.0083425622433424 +1769682069,550697472,0.0,0.0,0.0,1.0,0.0001199569960590452,0.0021906783804297447,0.020016970112919807,-0.26669132709503174,-0.14829444885253906,0.018347326666116714 +1769682069,581647872,0.0,0.0,0.0,1.0,-0.00026514637283980846,0.0022328817285597324,0.02011575922369957,0.0743718221783638,-0.1335597187280655,-0.010879854671657085 +1769682069,618499328,0.0,0.0,0.0,1.0,-2.54438491538167e-05,0.0019720366690307856,0.020197555422782898,-3.4552514989627525e-05,7.268035551533103e-05,0.003575375536456704 +1769682069,658823936,0.0,0.0,0.0,1.0,-0.0002477155067026615,0.0019794628024101257,0.020309023559093475,0.22219306230545044,-0.4002434313297272,0.004337185528129339 +1769682069,667823616,0.0,0.0,0.0,1.0,0.00010581867536529899,0.0018880777060985565,0.020372362807393074,-8.13804508652538e-05,0.0001696850813459605,0.008342533372342587 +1769682069,715285760,0.0,0.0,0.0,1.0,9.427254553884268e-06,0.0018409661715850234,0.020551670342683792,-0.19315555691719055,-0.28118395805358887,0.007402559742331505 +1769682069,759261696,0.0,0.0,0.0,1.0,0.00013679644325748086,0.001778950565494597,0.020691631361842155,0.07389214634895325,-0.13370457291603088,-0.006090033799409866 +1769682069,769373184,0.0,0.0,0.0,1.0,0.00012294994667172432,0.0017385224346071482,0.020810484886169434,-0.13350991904735565,-0.07389982044696808,-0.00816384144127369 +1769682069,815605760,0.0,0.0,0.0,1.0,-0.00031706091249361634,0.0017724710050970316,0.02091771736741066,0.07357918471097946,-0.13356953859329224,0.005836290307343006 +1769682069,850731008,0.0,0.0,0.0,1.0,-0.0005032708868384361,0.0019509359262883663,0.02090919390320778,0.13369174301624298,0.07355504482984543,0.002225183881819248 +1769682069,882062848,0.0,0.0,0.0,1.0,-0.0003031677333638072,0.0017917322693392634,0.020845185965299606,-0.06030678004026413,-0.20724546909332275,-0.0011569233611226082 +1769682069,907837696,0.0,0.0,0.0,1.0,-0.0004703064914792776,0.0019438223680481315,0.020756114274263382,0.1338314414024353,0.0732908621430397,-0.0025255600921809673 +1769682069,950323712,0.0,0.0,0.0,1.0,-0.00040473369881510735,0.0018288897117599845,0.020679449662566185,0.13392853736877441,0.07310733199119568,-0.006089736707508564 +1769682069,982201344,0.0,0.0,0.0,1.0,-0.0004590359458234161,0.0017763831419870257,0.020665204152464867,0.20733395218849182,-0.06131354719400406,-0.025258934125304222 +1769682070,15707904,0.0,0.0,0.0,1.0,-0.0002812831080518663,0.0013927941909059882,0.020748037844896317,-0.12220396101474762,-0.4132193922996521,0.04411753639578819 +1769682070,48500480,0.0,0.0,0.0,1.0,-6.708572618663311e-05,0.0006262535462155938,0.020817521959543228,0.14559485018253326,-0.2672826647758484,0.039121367037296295 +1769682070,83404288,0.0,0.0,0.0,1.0,-0.0003145442751701921,-8.854816405801103e-05,0.020904559642076492,0.13378503918647766,0.0734243094921112,0.027299914509058 +1769682070,115424512,0.0,0.0,0.0,1.0,-0.0002542813599575311,-0.0003790632472373545,0.021003196015954018,0.2067553848028183,-0.06105047091841698,0.015275771729648113 +1769682070,150355456,0.0,0.0,0.0,1.0,-0.00012255337787792087,-0.000635036441963166,0.021133631467819214,-0.011169426143169403,0.3410153090953827,-0.0034740061964839697 +1769682070,173350912,0.0,0.0,0.0,1.0,-6.867447518743575e-05,-0.0006118458695709705,0.02123490907251835,0.13407033681869507,0.07287907600402832,0.01299369428306818 +1769682070,201046528,0.0,0.0,0.0,1.0,-9.712341125123203e-05,-0.0005352023290470243,0.02138141728937626,-0.4026649296283722,-0.2177489846944809,-0.007987765595316887 +1769682070,246270464,0.0,0.0,0.0,1.0,-0.00012182688806205988,-0.00039604277117177844,0.021547598764300346,0.00012014015374006703,-0.00024267734261229634,-0.011917861178517342 +1769682070,267038208,0.0,0.0,0.0,1.0,-0.00021790309983771294,-0.0002185635967180133,0.021626299247145653,-0.13425108790397644,-0.07254227995872498,-0.01060497760772705 +1769682070,302091776,0.0,0.0,0.0,1.0,3.7298595998436213e-06,-0.00010702356667025015,0.021666666492819786,1.1968886610702612e-05,-2.4268712877528742e-05,-0.001191786490380764 +1769682070,350552576,0.0,0.0,0.0,1.0,-0.00040796835673972964,0.0012891310034319758,0.02163884975016117,0.20641499757766724,-0.062065958976745605,0.017649322748184204 +1769682070,369484544,0.0,0.0,0.0,1.0,7.080170325934887e-05,0.0017242805333808064,0.021610768511891365,0.06257083266973495,0.2063666135072708,-0.01072704792022705 +1769682070,400067584,0.0,0.0,0.0,1.0,-2.1420419216156006e-06,0.0021200075279921293,0.021577445790171623,0.1343686729669571,0.07233411818742752,0.01896647736430168 +1769682070,467053056,0.0,0.0,0.0,1.0,-6.936091813258827e-05,0.002654517535120249,0.021568777039647102,0.07188128679990768,-0.13479770720005035,-0.00605837581679225 +1769682070,468894720,0.0,0.0,0.0,1.0,0.0001843854843173176,0.0025758659467101097,0.02162003703415394,-0.07138251513242722,0.13395479321479797,-0.03684937581419945 +1769682070,515633920,0.0,0.0,0.0,1.0,-8.555053500458598e-05,0.0025805423501878977,0.021829677745699883,0.0717560276389122,-0.13498836755752563,-0.010814364068210125 +1769682070,556925696,0.0,0.0,0.0,1.0,-1.6878620954230428e-05,0.0024502489250153303,0.022022180259227753,6.209110870258883e-05,-0.00012151764531154186,-0.005958906374871731 +1769682070,569918464,0.0,0.0,0.0,1.0,3.168545663356781e-05,0.002394536742940545,0.022199396044015884,-0.06326090544462204,-0.2065059393644333,-0.009565859101712704 +1769682070,615976960,0.0,0.0,0.0,1.0,-0.000199883637833409,0.002185962861403823,0.02239980734884739,-0.13489115238189697,-0.07132651656866074,3.329617902636528e-05 +1769682070,649969152,0.0,0.0,0.0,1.0,0.00010981503874063492,0.0020866766571998596,0.02255861833691597,0.00017711552209220827,-0.00034083795617334545,-0.016684891656041145 +1769682070,684355840,0.0,0.0,0.0,1.0,-9.152229176834226e-05,0.0021306811831891537,0.02266700379550457,0.20631447434425354,-0.06426817178726196,-0.016757782548666 +1769682070,716235008,0.0,0.0,0.0,1.0,-0.00018430214549880475,0.002021404914557934,0.0227803997695446,0.06398577988147736,0.20615921914577484,0.002433438552543521 +1769682070,747448320,0.0,0.0,0.0,1.0,-2.974551171064377e-05,0.0020063400734215975,0.022899983450770378,0.20599764585494995,-0.06411175429821014,0.004718845244497061 +1769682070,766844672,0.0,0.0,0.0,1.0,-0.000360095058567822,0.0019814500119537115,0.022985147312283516,0.14163289964199066,-0.27022722363471985,0.007055156864225864 +1769682070,819246848,0.0,0.0,0.0,1.0,-0.0002339650527574122,0.0020200491417199373,0.023049095645546913,-0.06454894691705704,-0.20584116876125336,0.005893074441701174 +1769682070,851350528,0.0,0.0,0.0,1.0,-0.00040274180355481803,0.0019496034365147352,0.023092366755008698,0.20600275695323944,-0.06495014578104019,-0.010731486603617668 +1769682070,870626816,0.0,0.0,0.0,1.0,-0.00015344198618549854,0.0019843413028866053,0.023128226399421692,0.0706605464220047,-0.13556909561157227,-0.010763030499219894 +1769682070,900159232,0.0,0.0,0.0,1.0,-0.0001852639834396541,0.0019234736682847142,0.023183567449450493,-0.20027408003807068,-0.27625811100006104,-0.00013083592057228088 +1769682070,961434624,0.0,0.0,0.0,1.0,-0.0002617126447148621,0.00206181057728827,0.023314720019698143,0.0,-0.0,0.0 +1769682070,968610816,0.0,0.0,0.0,1.0,6.203886005096138e-05,0.0017238677246496081,0.02341262623667717,-0.06542001664638519,-0.20540547370910645,0.015398537740111351 +1769682071,16912640,0.0,0.0,0.0,1.0,-8.181427256204188e-05,0.0008197007700800896,0.023545291274785995,0.1352105587720871,0.07069116085767746,0.029868759214878082 +1769682071,50582784,0.0,0.0,0.0,1.0,-0.00023733280249871314,-0.00011794545571319759,0.02362070605158806,0.20517021417617798,-0.0649358406662941,0.03699802979826927 +1769682071,79723008,0.0,0.0,0.0,1.0,-0.0002269726974191144,-0.0003052129177376628,0.023651648312807083,0.27081945538520813,0.14063245058059692,0.04186349734663963 +1769682071,116632576,0.0,0.0,0.0,1.0,-0.00023567728931084275,-0.000543793139513582,0.02365114726126194,-0.20567220449447632,0.06632498651742935,0.016638267785310745 +1769682071,151895040,0.0,0.0,0.0,1.0,-0.0004997934447601438,-0.0005423640250228345,0.023600710555911064,-0.13911980390548706,0.27127981185913086,-0.016621708869934082 +1769682071,182310912,0.0,0.0,0.0,1.0,-0.0003999049949925393,-0.0006284741684794426,0.023558789864182472,-0.1357308328151703,-0.06970720738172531,-0.008412878029048443 +1769682071,217046784,0.0,0.0,0.0,1.0,-0.0006573258433490992,-0.0005145515315234661,0.023489784449338913,-0.47400006651878357,-0.4137206971645355,-0.0026975772343575954 +1769682071,252994816,0.0,0.0,0.0,1.0,-0.0002902947016991675,-0.0004524261166807264,0.023389730602502823,0.06675129383802414,0.20493759214878082,-0.017767269164323807 +1769682071,282529536,0.0,0.0,0.0,1.0,-0.00015074448310770094,0.00012427241017576307,0.023272261023521423,0.20497551560401917,-0.06634114682674408,0.022668981924653053 +1769682071,303728128,0.0,0.0,0.0,1.0,-0.0002778037451207638,0.001370321260765195,0.02318674325942993,-0.00027326797135174274,0.0005113463848829269,0.025027252733707428 +1769682071,361313792,0.0,0.0,0.0,1.0,-0.0003013791283592582,0.0025303997099399567,0.023093849420547485,-0.27246883511543274,-0.13748443126678467,0.02485673502087593 +1769682071,371862528,0.0,0.0,0.0,1.0,-1.7971615307033062e-05,0.0029028947465121746,0.023054048418998718,-0.06741135567426682,-0.20466284453868866,0.021325187757611275 +1769682071,414990336,0.0,0.0,0.0,1.0,8.885675924830139e-05,0.003362087532877922,0.02299816533923149,-0.13474024832248688,-0.4100542962551117,0.0009195598540827632 +1769682071,450112768,0.0,0.0,0.0,1.0,-0.00016740098362788558,0.003485216060653329,0.02294343151152134,0.3422181010246277,-0.3399255871772766,0.0131902564316988 +1769682071,479511552,0.0,0.0,0.0,1.0,-0.00019369371875654906,0.0035167608875781298,0.022914106026291847,-1.3498348380380776e-05,2.4370241590077057e-05,0.0011917680967599154 +1769682071,516103424,0.0,0.0,0.0,1.0,-0.0003373927029315382,0.003277535317465663,0.02284351922571659,0.20442809164524078,0.2729431092739105,-0.021129194647073746 +1769682071,551506944,0.0,0.0,0.0,1.0,7.215177174657583e-05,0.0031547562684863806,0.022795692086219788,-1.3770069926977158e-05,2.4380664399359375e-05,0.0011917647207155824 +1769682071,566821376,0.0,0.0,0.0,1.0,-0.00013830020907334983,0.003129548393189907,0.022797485813498497,0.13655368983745575,0.0681157335639,-0.009347986429929733 +1769682071,621639424,0.0,0.0,0.0,1.0,-0.0001379815803375095,0.0029222466982901096,0.022880826145410538,-0.00019341360894031823,-0.3411012887954712,0.00817284919321537 +1769682071,654332672,0.0,0.0,0.0,1.0,-9.723505354486406e-05,0.002900502411648631,0.022947845980525017,-0.00012661085929721594,0.0002196975110564381,0.010725846514105797 +1769682071,669191680,0.0,0.0,0.0,1.0,-7.817399455234408e-05,0.002840840257704258,0.02295420505106449,0.13668377697467804,0.06785167753696442,-0.0069246962666511536 +1769682071,716161024,0.0,0.0,0.0,1.0,-0.0004168091109022498,0.002730973996222019,0.022811496630311012,0.1368034929037094,0.06762906908988953,-0.011675708927214146 +1769682071,760567552,0.0,0.0,0.0,1.0,-0.0005237438017502427,0.0027769010048359632,0.02259092964231968,-0.2733735740184784,-0.1356203407049179,-0.006475983187556267 +1769682071,769743360,0.0,0.0,0.0,1.0,-0.0007314134854823351,0.002858769381418824,0.022476401180028915,0.06910447776317596,0.20438094437122345,-0.0045404862612485886 +1769682071,800771328,0.0,0.0,0.0,1.0,-0.0007507326081395149,0.002788617042824626,0.022332264110445976,0.3394967317581177,-0.34266945719718933,0.012329703196883202 +1769682071,843371264,0.0,0.0,0.0,1.0,-0.0005320004420354962,0.002837777603417635,0.022254712879657745,-0.1367710679769516,-0.06762009859085083,-0.007446612231433392 +1769682071,878524928,0.0,0.0,0.0,1.0,-8.108816109597683e-05,0.0028764682356268167,0.022275283932685852,-0.2061420977115631,-0.27214521169662476,-0.02201325073838234 +1769682071,900224512,0.0,0.0,0.0,1.0,-0.00010979345825035125,0.002910090610384941,0.022318312898278236,-0.13447095453739166,0.27372944355010986,-0.012036647647619247 +1769682071,950403840,0.0,0.0,0.0,1.0,0.000516714877448976,0.00235451920889318,0.022452542558312416,-0.06745383888483047,0.13755013048648834,0.02376542240381241 +1769682071,968138240,0.0,0.0,0.0,1.0,0.00010779115837067366,0.001568633015267551,0.02244599536061287,0.13606850802898407,0.06868745386600494,0.07899849116802216 +1769682072,10996736,0.0,0.0,0.0,1.0,-0.00027160809258930385,0.0005984714953228831,0.02240172028541565,-0.0005829556612297893,0.000952528091147542,0.046478237956762314 +1769682072,55296768,0.0,0.0,0.0,1.0,-0.0002215688582509756,-0.0005142397712916136,0.0223526768386364,0.13338401913642883,-0.27391108870506287,0.02517024800181389 +1769682072,66903040,0.0,0.0,0.0,1.0,-0.00013993900211062282,-0.0006837554392404854,0.022369667887687683,0.407520592212677,-0.1401887983083725,0.03777577728033066 +1769682072,115173376,0.0,0.0,0.0,1.0,-9.87612729659304e-05,-0.0009686154080554843,0.022476481273770332,0.06663443148136139,-0.13725292682647705,0.0024505737237632275 +1769682072,157634304,0.0,0.0,0.0,1.0,-0.00010388159716967493,-0.0008339000050909817,0.022574063390493393,-0.07061932981014252,-0.20409530401229858,-0.009806548245251179 +1769682072,171496704,0.0,0.0,0.0,1.0,-1.7025507986545563e-05,-0.0007247977191582322,0.0226461049169302,-0.2745899558067322,-0.1331149786710739,-0.010203398764133453 +1769682072,217202944,0.0,0.0,0.0,1.0,-0.00013316910190042108,-0.0005673834821209311,0.022649582475423813,0.27001816034317017,-0.20839804410934448,0.00879465788602829 +1769682072,249401344,0.0,0.0,0.0,1.0,4.5236345613375306e-05,-0.00017892944742925465,0.022644290700554848,-0.20907072722911835,-0.26934677362442017,0.027998827397823334 +1769682072,284000512,0.0,0.0,0.0,1.0,5.658384179696441e-05,0.0011765861418098211,0.02261592261493206,-0.06658980250358582,0.13831569254398346,0.03688422217965126 +1769682072,299708672,0.0,0.0,0.0,1.0,-0.0001689037017058581,0.002109980210661888,0.022584866732358932,-0.27528074383735657,-0.13185162842273712,0.012431973591446877 +1769682072,345761280,0.0,0.0,0.0,1.0,0.00025060202460736036,0.0034333679359406233,0.022568579763174057,0.05992826446890831,-0.47835657000541687,0.02488326095044613 +1769682072,367950080,0.0,0.0,0.0,1.0,0.00010684767039492726,0.004034109879285097,0.022573411464691162,0.2032998949289322,-0.07151030749082565,0.017133841291069984 +1769682072,416855296,0.0,0.0,0.0,1.0,4.154173075221479e-05,0.0044142561964690685,0.022639138624072075,-0.06574654579162598,0.1377752274274826,0.0011026500724256039 +1769682072,451330304,0.0,0.0,0.0,1.0,-0.00016400970343966037,0.004376767668873072,0.022733300924301147,0.2756967544555664,0.13093139231204987,-0.011079784482717514 +1769682072,469274368,0.0,0.0,0.0,1.0,-9.865645552054048e-05,0.004256530664861202,0.022787852212786674,-0.07218122482299805,-0.20348840951919556,-0.00628334516659379 +1769682072,516491008,0.0,0.0,0.0,1.0,-3.6729295970872045e-05,0.003998447675257921,0.022967113181948662,0.07266228646039963,0.20295579731464386,-0.01634886860847473 +1769682072,553114880,0.0,0.0,0.0,1.0,0.00027140675229020417,0.003773878561332822,0.023212216794490814,0.13801628351211548,0.06512441486120224,-0.006676136516034603 +1769682072,566524416,0.0,0.0,0.0,1.0,6.0794263845309615e-05,0.003706613089889288,0.023350218310952187,-0.2030354142189026,0.07256227731704712,-0.011344020254909992 +1769682072,615275008,0.0,0.0,0.0,1.0,0.00017248789663426578,0.003487205132842064,0.023662909865379333,0.008094113320112228,0.3407641351222992,-0.02004339173436165 +1769682072,656239360,0.0,0.0,0.0,1.0,0.0001278150884900242,0.003497409401461482,0.02385355718433857,0.13809208571910858,0.0649297833442688,-0.0018650798592716455 +1769682072,671572736,0.0,0.0,0.0,1.0,9.161059278994799e-05,0.003492848016321659,0.02398686483502388,-0.3408357501029968,0.00796714797616005,-0.021482961252331734 +1769682072,701652736,0.0,0.0,0.0,1.0,-0.0002617243444547057,0.0034869827795773745,0.02405403181910515,-0.13805557787418365,-0.06492803990840912,-0.007698079105466604 +1769682072,748213248,0.0,0.0,0.0,1.0,-0.00024068247876130044,0.003540933597832918,0.02414930798113346,8.209826046368107e-05,-0.0001231776550412178,-0.005958630237728357 +1769682072,782064896,0.0,0.0,0.0,1.0,3.863044548779726e-05,0.0036158859729766846,0.024269113317131996,0.0,-0.0,0.0 +1769682072,799064576,0.0,0.0,0.0,1.0,-0.00025320990243926644,0.003635970875620842,0.024417854845523834,-0.21217279136180878,-0.26721495389938354,0.00017896783538162708 +1769682072,847961856,0.0,0.0,0.0,1.0,-4.4097891077399254e-05,0.0037386417388916016,0.024586716666817665,0.1284862458705902,-0.27657732367515564,0.012303500436246395 +1769682072,867475200,0.0,0.0,0.0,1.0,-0.0005879938253201544,0.0037778697442263365,0.024645816534757614,-0.20244184136390686,0.07395615428686142,-0.015135339461266994 +1769682072,912663552,0.0,0.0,0.0,1.0,-0.0005695691215805709,0.003776365891098976,0.02462044730782509,-0.13841629028320312,-0.06417902559041977,-0.00422705989331007 +1769682072,954352896,0.0,0.0,0.0,1.0,-0.00049653893802315,0.002101405058056116,0.02455967850983143,-0.0010130386799573898,0.0014565340243279934,0.07031120359897614 +1769682072,982140672,0.0,0.0,0.0,1.0,-0.00032955611823126674,0.0010143122635781765,0.024477139115333557,-0.27794280648231506,-0.12657898664474487,0.05108014494180679 +1769682073,120576,0.0,0.0,0.0,1.0,-0.0003098139713983983,0.00030170686659403145,0.024440987035632133,-0.13939808309078217,-0.06265385448932648,0.05294780433177948 +1769682073,68014848,0.0,0.0,0.0,1.0,-0.0001630592450965196,-0.00037413323298096657,0.024501454085111618,-0.07551845908164978,-0.20171982049942017,0.029327113181352615 +1769682073,71040512,0.0,0.0,0.0,1.0,-7.174460915848613e-05,-0.0006627100519835949,0.024598656222224236,0.06333878636360168,-0.1384766399860382,0.014512795954942703 +1769682073,115492608,0.0,0.0,0.0,1.0,-0.00022047196398489177,-0.0005623269244097173,0.02483639121055603,0.051407694816589355,-0.4798727035522461,0.001148937619291246 +1769682073,146671616,0.0,0.0,0.0,1.0,-5.0437694881111383e-05,-0.0004359338490758091,0.025027764961123466,-0.07533616572618484,-0.2024659365415573,-0.014762735925614834 +1769682073,182164992,0.0,0.0,0.0,1.0,-4.979464574716985e-05,-0.0002637170546222478,0.02524581365287304,-0.012394066900014877,-0.3413122892379761,-0.013360945507884026 +1769682073,201795328,0.0,0.0,0.0,1.0,-8.701370097696781e-05,-0.00018195666780229658,0.025336740538477898,-0.27753886580467224,-0.1266465038061142,-0.025172879919409752 +1769682073,252159232,0.0,0.0,0.0,1.0,0.0001757536083459854,0.0006015487597323954,0.025554783642292023,-0.06311921775341034,0.13935646414756775,0.01409175619482994 +1769682073,267197696,0.0,0.0,0.0,1.0,7.9082150477916e-05,0.0013656184310093522,0.025633152574300766,-0.12567192316055298,0.2781580090522766,-0.001612980617210269 +1769682073,315620352,0.0,0.0,0.0,1.0,0.00014612686936743557,0.002233773237094283,0.025769473984837532,-0.15310229361057281,-0.4032839834690094,0.018127748742699623 +1769682073,347081216,0.0,0.0,0.0,1.0,-0.0003828298067674041,0.002783769741654396,0.025821160525083542,0.0001540249359095469,-0.0002232094411738217,-0.010725416243076324 +1769682073,367266304,0.0,0.0,0.0,1.0,-0.0004029894480481744,0.00309526058845222,0.025786958634853363,0.12481663376092911,-0.2782825827598572,0.011170913465321064 +1769682073,415492864,0.0,0.0,0.0,1.0,-0.0006571656558662653,0.0031311754137277603,0.025629471987485886,-0.3411216139793396,0.014987794682383537,0.013808242976665497 +1769682073,465690112,0.0,0.0,0.0,1.0,-0.0005642818287014961,0.003061865223571658,0.02546514943242073,0.06221769377589226,-0.13940541446208954,-0.0009600224439054728 +1769682073,479762688,0.0,0.0,0.0,1.0,-0.0006326687289401889,0.003021807176992297,0.025382250547409058,0.07738255709409714,0.20132675766944885,-0.009011252783238888 +1769682073,498666752,0.0,0.0,0.0,1.0,-0.00031728646717965603,0.00296952435746789,0.025303484871983528,-0.20144732296466827,0.07746346294879913,-0.0010075131431221962 +1769682073,544422144,0.0,0.0,0.0,1.0,-0.0005148376221768558,0.0029302844777703285,0.025260018184781075,0.061811573803424835,-0.1394229531288147,0.00500896293669939 +1769682073,582112256,0.0,0.0,0.0,1.0,-0.0001084387768059969,0.0028097894974052906,0.02533719316124916,-0.00023177363618742675,0.0003220049839001149,0.0154921505600214 +1769682073,621497856,0.0,0.0,0.0,1.0,-0.00025941929197870195,0.00276654283516109,0.02541816234588623,0.13957296311855316,0.061643097549676895,0.0020082416012883186 +1769682073,648935424,0.0,0.0,0.0,1.0,-8.067276212386787e-05,0.0027292061131447554,0.025518590584397316,-0.016959620639681816,-0.34034833312034607,0.024710513651371002 +1769682073,669148672,0.0,0.0,0.0,1.0,0.00019003479974344373,0.00280101434327662,0.025769807398319244,0.00025293807266280055,-0.00034716882510110736,-0.01668379455804825 +1769682073,698979584,0.0,0.0,0.0,1.0,0.00012307302677072585,0.0030090026557445526,0.02624760940670967,3.6304689274402335e-05,-4.963021638104692e-05,-0.0023833971936255693 +1769682073,764568064,0.0,0.0,0.0,1.0,-0.0003653172170743346,0.0030898975674062967,0.026608237996697426,0.12223336100578308,-0.27968528866767883,0.0017420898657292128 +1769682073,771654912,0.0,0.0,0.0,1.0,-0.000932973634917289,0.0031637821812182665,0.026620617136359215,0.12197408825159073,-0.27960148453712463,0.008894742466509342 +1769682073,799819264,0.0,0.0,0.0,1.0,-0.0011240108869969845,0.0030975351110100746,0.026529867202043533,0.06077367439866066,-0.1397130936384201,0.011003055609762669 +1769682073,842647552,0.0,0.0,0.0,1.0,-0.001296430011279881,0.003114276099950075,0.026262840256094933,0.07912982255220413,0.20082589983940125,0.003024778328835964 +1769682073,878208512,0.0,0.0,0.0,1.0,-0.0017082847189158201,0.0030677099712193012,0.02598634362220764,-0.14006249606609344,-0.060592200607061386,0.0026400568895041943 +1769682073,899599104,0.0,0.0,0.0,1.0,-0.0010693263029679656,0.0027243555523455143,0.025753676891326904,0.200289785861969,-0.07909297198057175,0.022676950320601463 +1769682073,952709888,0.0,0.0,0.0,1.0,-0.00148509640712291,0.0016890008701011539,0.0253740306943655,-0.0006972039118409157,0.0009110845858231187,0.04409259185194969 +1769682073,966647296,0.0,0.0,0.0,1.0,-0.001210184651426971,0.0013785178307443857,0.025281697511672974,0.2602623403072357,-0.21938380599021912,0.03607643023133278 +1769682074,13666560,0.0,0.0,0.0,1.0,-0.0010994335170835257,0.000908274669200182,0.02519160881638527,0.1395266205072403,0.06108669191598892,0.04388130083680153 +1769682074,49081344,0.0,0.0,0.0,1.0,-0.0011017824290320277,0.0007012065034359694,0.025101855397224426,0.3401573598384857,-0.019597934558987617,0.030839232727885246 +1769682074,68237312,0.0,0.0,0.0,1.0,-0.001272432622499764,0.0007037890027277172,0.025008095428347588,0.319905549287796,-0.36068952083587646,0.022031936794519424 +1769682074,98925824,0.0,0.0,0.0,1.0,-0.0012533178087323904,0.0008169685024768114,0.02481701970100403,0.25978779792785645,-0.22055493295192719,0.020577387884259224 +1769682074,166398464,0.0,0.0,0.0,1.0,-0.0015183226205408573,0.0007426892407238483,0.024445096030831337,-0.02123105712234974,-0.3403782546520233,0.011406227014958858 +1769682074,174823168,0.0,0.0,0.0,1.0,-0.001226472551934421,0.000894107564818114,0.02425764873623848,-0.34023573994636536,0.020974542945623398,-0.02133878879249096 +1769682074,199748864,0.0,0.0,0.0,1.0,-0.0014087804593145847,0.0009323781123384833,0.024164527654647827,0.28134581446647644,0.11857666820287704,-0.01941468007862568 +1769682074,244656896,0.0,0.0,0.0,1.0,-0.001043221214786172,0.001261784927919507,0.024082832038402557,-0.08113352954387665,-0.20002251863479614,-0.0031732013449072838 +1769682074,278633984,0.0,0.0,0.0,1.0,-0.000615868775639683,0.001192646101117134,0.024105576798319817,0.14075450599193573,0.059075914323329926,-0.008499972522258759 +1769682074,299702784,0.0,0.0,0.0,1.0,0.0001047379628289491,0.0010397362057119608,0.023621276021003723,-0.05901487171649933,0.14046809077262878,-0.010964259505271912 +1769682074,345906432,0.0,0.0,0.0,1.0,-0.000573597033508122,0.0009938010480254889,0.023169120773673058,0.2583710849285126,-0.2218857705593109,0.028935633599758148 +1769682074,366366976,0.0,0.0,0.0,1.0,-0.0008132135262712836,0.0008263374911621213,0.022895965725183487,-7.628774619661272e-05,9.731786121847108e-05,0.004766771104186773 +1769682074,412994816,0.0,0.0,0.0,1.0,-0.0011502394918352365,0.0008344062371179461,0.022636566311120987,0.1994132697582245,-0.08168565481901169,0.015591992065310478 +1769682074,448562432,0.0,0.0,0.0,1.0,-0.0015403395518660545,0.000812141690403223,0.022381747141480446,-0.08223190158605576,-0.19942526519298553,0.0075109126046299934 +1769682074,466808320,0.0,0.0,0.0,1.0,-0.0015707493294030428,0.0009235424804501235,0.022321917116642,0.11731972545385361,-0.28187888860702515,-0.0019308286719024181 +1769682074,499130880,0.0,0.0,0.0,1.0,-0.0014143830630928278,0.0007808464579284191,0.022340411320328712,0.3403891324996948,-0.02391808107495308,0.0011783493682742119 +1769682074,557254400,0.0,0.0,0.0,1.0,-0.0015899097779765725,0.0009325317805632949,0.02240702509880066,-0.08290785551071167,-0.19895268976688385,0.021774161607027054 +1769682074,573992704,0.0,0.0,0.0,1.0,-0.0015897373668849468,0.0009791821939870715,0.022404231131076813,0.11631888896226883,-0.2817816138267517,0.017098985612392426 +1769682074,599676160,0.0,0.0,0.0,1.0,-0.0018202763749286532,0.000983719015493989,0.022370170801877975,-0.08271601051092148,-0.1994197964668274,-0.0068521648645401 +1769682074,645679616,0.0,0.0,0.0,1.0,-0.0021292439196258783,0.0010839622700586915,0.022258007898926735,0.03318110853433609,-0.481452077627182,0.0018601457122713327 +1769682074,678196224,0.0,0.0,0.0,1.0,-0.001853720168583095,0.0008278336026705801,0.022166918963193893,0.48106318712234497,0.03323750197887421,0.02498341165482998 +1769682074,699724800,0.0,0.0,0.0,1.0,-0.0019240695983171463,0.0008781458018347621,0.022044885903596878,0.31488388776779175,-0.3656942546367645,0.0040517570450901985 +1769682074,749010688,0.0,0.0,0.0,1.0,-0.0019979283679276705,0.000784633681178093,0.021837778389453888,0.31437039375305176,-0.36573296785354614,0.015950076282024384 +1769682074,765869568,0.0,0.0,0.0,1.0,-0.0018939089495688677,0.0006877006962895393,0.021679988130927086,0.19896064698696136,-0.08361785113811493,0.0013033535797148943 +1769682074,814642432,0.0,0.0,0.0,1.0,-0.0019267213065177202,0.0007639511022716761,0.02149074152112007,0.14137394726276398,0.05749882012605667,-0.003622993128374219 +1769682074,853520896,0.0,0.0,0.0,1.0,-0.0016684754518792033,0.0008748789550736547,0.021244624629616737,0.19887353479862213,-0.08396352082490921,-0.0010790927335619926 +1769682074,870573056,0.0,0.0,0.0,1.0,-0.0016217067604884505,0.0009109860402531922,0.02107691578567028,0.19883960485458374,-0.08411307632923126,-0.002270190045237541 +1769682074,899298304,0.0,0.0,0.0,1.0,-0.0014453122857958078,0.0008166852057911456,0.020922591909766197,-0.027010297402739525,-0.33995893597602844,0.01222236454486847 +1769682074,958349312,0.0,0.0,0.0,1.0,-0.0011006887070834637,0.0007809314411133528,0.02074987068772316,0.19881334900856018,-0.08452057838439941,-0.00822589173913002 +1769682074,969755904,0.0,0.0,0.0,1.0,-0.0012012154329568148,0.0008110600174404681,0.020610276609659195,0.19870300590991974,-0.08457326889038086,-0.0046492209658026695 +1769682075,230912,0.0,0.0,0.0,1.0,-0.0009231120930053294,0.0007819855818524957,0.020463600754737854,0.05709529295563698,-0.14167329668998718,-0.004640632774680853 +1769682075,43188736,0.0,0.0,0.0,1.0,-0.001318962313234806,0.0008666483336128294,0.020232995972037315,0.14164084196090698,0.05681619793176651,-0.0023823105730116367 +1769682075,66142720,0.0,0.0,0.0,1.0,-0.001166289672255516,0.0009548286907374859,0.02004648931324482,0.5954770445823669,-0.25478893518447876,-0.006774100475013256 +1769682075,106228224,0.0,0.0,0.0,1.0,-0.0013538222992792726,0.0011213512625545263,0.01976865530014038,-0.14199282228946686,-0.056292612105607986,0.019051898270845413 +1769682075,144318464,0.0,0.0,0.0,1.0,-0.0010589922312647104,0.000934671435970813,0.019549552351236343,0.2547035813331604,-0.22659456729888916,0.015736322849988937 +1769682075,170809344,0.0,0.0,0.0,1.0,-0.0013184399576857686,0.001010526088066399,0.01936500146985054,0.05667500197887421,-0.141934335231781,-0.008233592845499516 +1769682075,199264768,0.0,0.0,0.0,1.0,-0.0009822758147493005,0.0008802663069218397,0.0192321315407753,0.396239310503006,-0.17049753665924072,0.014578267931938171 +1769682075,261477376,0.0,0.0,0.0,1.0,-0.0007623626152053475,0.000907899287994951,0.019141357392072678,0.3398970663547516,-0.029116041958332062,0.006141048856079578 +1769682075,269707776,0.0,0.0,0.0,1.0,-0.0005685710930265486,0.0005692379781976342,0.019138827919960022,0.4818338453769684,0.026799684390425682,0.0002336832694709301 +1769682075,299593984,0.0,0.0,0.0,1.0,-0.0005225275526754558,0.00017465197015553713,0.01914665848016739,0.4817708730697632,0.02661551535129547,0.0050061289221048355 +1769682075,344856832,0.0,0.0,0.0,1.0,-0.0008045813883654773,-8.978241385193542e-05,0.019131576642394066,0.395975261926651,-0.17179159820079803,0.0026707041542977095 +1769682075,370312192,0.0,0.0,0.0,1.0,-0.0005646984209306538,-0.00012443010928109288,0.019077423959970474,0.00011714725405909121,-0.0001386095827911049,-0.007150270510464907 +1769682075,402289920,0.0,0.0,0.0,1.0,-0.0006703985272906721,-0.0003152095596306026,0.019030854105949402,0.1116713359951973,-0.28385424613952637,0.009712752886116505 +1769682075,447666432,0.0,0.0,0.0,1.0,-0.0008072069613263011,-0.0003359561087563634,0.018975714221596718,0.4816456437110901,0.02555968426167965,0.016914792358875275 +1769682075,466610176,0.0,0.0,0.0,1.0,-0.0003941390896216035,-0.0004086057306267321,0.018986361101269722,0.2840023338794708,0.11153203994035721,0.008437403477728367 +1769682075,503380224,0.0,0.0,0.0,1.0,-0.0005503330612555146,-0.00016541543300263584,0.01904202438890934,0.339651495218277,-0.030686544254422188,0.012091872282326221 +1769682075,548681984,0.0,0.0,0.0,1.0,-0.0008497008820995688,-0.0001255939423572272,0.019089045003056526,0.14222097396850586,0.05540354177355766,-0.004718779120594263 +1769682075,567600896,0.0,0.0,0.0,1.0,-0.0008656489662826061,-6.840679270680994e-05,0.01903414912521839,0.33982351422309875,-0.03139379620552063,-0.0010209972970187664 +1769682075,599390464,0.0,0.0,0.0,1.0,-0.0009478655410930514,6.4904845203273e-05,0.018876928836107254,0.00011621445446508005,-0.00013806890638079494,-0.007150284945964813 +1769682075,649558784,0.0,0.0,0.0,1.0,-0.0012013575760647655,2.040235631284304e-05,0.018577231094241142,0.39500999450683594,-0.174067422747612,0.0014231097884476185 +1769682075,667882752,0.0,0.0,0.0,1.0,-0.001404438866302371,-3.7930272810626775e-05,0.018321285024285316,-0.14200760424137115,-0.05546996742486954,-0.016738638281822205 +1769682075,698997760,0.0,0.0,0.0,1.0,-0.0011276159202679992,-2.4252109142253175e-05,0.018082447350025177,0.17437605559825897,0.39483141899108887,0.0011996317189186811 +1769682075,743160064,0.0,0.0,0.0,1.0,-0.0011529281036928296,-0.00012638518819585443,0.01784961298108101,0.5920886397361755,-0.26223301887512207,-0.000877751037478447 +1769682075,768974592,0.0,0.0,0.0,1.0,-0.001012096763588488,-6.184682570165023e-05,0.01773224025964737,0.3946389853954315,-0.17504002153873444,-0.0009889616630971432 +1769682075,799744256,0.0,0.0,0.0,1.0,-0.000534266117028892,-0.0001099166547646746,0.01766481064260006,0.42704522609710693,0.1646585613489151,0.010907281190156937 +1769682075,845285888,0.0,0.0,0.0,1.0,-0.0009755751816555858,-0.00022019642347004265,0.017589794471859932,0.591489315032959,-0.2631199061870575,0.007432318292558193 +1769682075,866714112,0.0,0.0,0.0,1.0,-0.0006946398643776774,-0.0001531348389107734,0.0175116378813982,0.4271707236766815,0.16422323882579803,0.01568065956234932 +1769682075,901907456,0.0,0.0,0.0,1.0,-0.0011428090510889888,-3.082754119532183e-05,0.01740938611328602,0.1092144325375557,-0.28505396842956543,4.8394082114100456e-05 +1769682075,942686464,0.0,0.0,0.0,1.0,-0.0008934861980378628,-7.62721465434879e-05,0.017326191067695618,0.08801253139972687,0.19705642759799957,0.0012390388874337077 +1769682075,967694336,0.0,0.0,0.0,1.0,-0.00102468382101506,-3.808375186054036e-05,0.017337262630462646,0.2513982653617859,-0.23074612021446228,0.0024808640591800213 +1769682075,999599104,0.0,0.0,0.0,1.0,-0.0005844674305990338,0.0003863849851768464,0.017431950196623802,0.1972634196281433,-0.0886642187833786,-0.018985044211149216 +1769682076,62849536,0.0,0.0,0.0,1.0,-0.00012283265823498368,0.0009907289640977979,0.01757647655904293,0.33979812264442444,-0.034536462277173996,-0.016521988436579704 +1769682076,69712384,0.0,0.0,0.0,1.0,-0.0003789816692005843,0.0012938629370182753,0.01760670728981495,0.19690541923046112,-0.08861129730939865,-0.0034815918188542128 +1769682076,99459328,0.0,0.0,0.0,1.0,-0.0008966856403276324,0.00137196178548038,0.01752633973956108,0.2509101927280426,-0.23136374354362488,0.00011243694461882114 +1769682076,145954560,0.0,0.0,0.0,1.0,-0.0006876027910038829,0.0013186406577005982,0.01728462241590023,0.2855554223060608,0.1078278198838234,-0.005767577327787876 +1769682076,174153472,0.0,0.0,0.0,1.0,-0.0008449595188722014,0.001189790666103363,0.016892144456505775,0.6245899200439453,0.07315410673618317,0.02426326833665371 +1769682076,199449600,0.0,0.0,0.0,1.0,-0.0010926405666396022,0.0011351227294653654,0.016676055267453194,0.44710442423820496,-0.3207090198993683,0.003815904026851058 +1769682076,244525312,0.0,0.0,0.0,1.0,-0.0008635183330625296,0.0011305701918900013,0.01629355363547802,0.2501670718193054,-0.23173195123672485,0.01204222347587347 +1769682076,266600960,0.0,0.0,0.0,1.0,-0.0007868572138249874,0.000946391373872757,0.016101054847240448,0.589155375957489,-0.2670612037181854,0.03016854077577591 +1769682076,301907968,0.0,0.0,0.0,1.0,-0.00048756084288470447,0.0010059332707896829,0.015981370583176613,0.19619277119636536,-0.08894220739603043,0.01919676549732685 +1769682076,346052096,0.0,0.0,0.0,1.0,-0.00048568123020231724,0.0008681489853188396,0.015834733843803406,0.4824141561985016,0.017397956922650337,-0.009129979647696018 +1769682076,369266176,0.0,0.0,0.0,1.0,-0.00046479905722662807,0.00014597469998989254,0.015705497935414314,0.5357800722122192,-0.12565061450004578,-0.001976165920495987 +1769682076,399237888,0.0,0.0,0.0,1.0,-0.0005848481669090688,-0.0003254185139667243,0.015526625327765942,0.6254444122314453,0.07024568319320679,-0.012565219774842262 +1769682076,448070912,0.0,0.0,0.0,1.0,-0.0004663998552132398,-0.0009835698874667287,0.015311218798160553,0.196580171585083,-0.09004799276590347,-0.016559597104787827 +1769682076,467144448,0.0,0.0,0.0,1.0,-0.00038785976357758045,-0.0010921566281467676,0.015187571756541729,0.19628648459911346,-0.08984530717134476,-0.0010742286685854197 +1769682076,500030976,0.0,0.0,0.0,1.0,-0.0003561092307791114,-0.0010182686382904649,0.01509361807256937,0.4823000729084015,0.01638861931860447,0.0003619985654950142 +1769682076,544713472,0.0,0.0,0.0,1.0,-0.0003065104247070849,-0.0010438540484756231,0.01497985515743494,0.39217111468315125,-0.1798572838306427,0.010926324874162674 +1769682076,573702912,0.0,0.0,0.0,1.0,-0.0005275827134028077,-0.0009683641255833209,0.014855800196528435,0.5722739696502686,0.21211357414722443,0.006424735300242901 +1769682076,600652288,0.0,0.0,0.0,1.0,-0.0004036952741444111,-0.000936912139877677,0.01469553355127573,0.5721378326416016,0.21212968230247498,0.02071242406964302 +1769682076,644968448,0.0,0.0,0.0,1.0,-0.0008455722709186375,-0.0007694184314459562,0.014349643141031265,0.6253458261489868,0.0684010460972786,0.008749344386160374 +1769682076,666765568,0.0,0.0,0.0,1.0,-0.001104425871744752,-0.0007743535097688437,0.01398965623229742,0.3392086923122406,-0.03765247017145157,-0.0022047124803066254 +1769682076,701735936,0.0,0.0,0.0,1.0,-0.0009533506236039102,-0.0007248991169035435,0.013588435016572475,0.3919285535812378,-0.18096330761909485,0.00012700771912932396 +1769682076,747885568,0.0,0.0,0.0,1.0,-0.0008275902946479619,-0.0005882768309675157,0.01314721442759037,0.2863234579563141,0.10545066744089127,0.00735903438180685 +1769682076,766772736,0.0,0.0,0.0,1.0,-0.0004170734900981188,-0.0006530486862175167,0.012980500236153603,0.39155271649360657,-0.1810789704322815,0.013207999989390373 +1769682076,800073472,0.0,0.0,0.0,1.0,-0.00021646425011567771,-0.0006856226245872676,0.012933362275362015,0.5347045660018921,-0.12863974273204803,0.015681244432926178 +1769682076,858154240,0.0,0.0,0.0,1.0,-0.00011183766036992893,-0.0007221404230222106,0.013025503605604172,0.39140766859054565,-0.18145690858364105,0.01199499424546957 +1769682076,871242240,0.0,0.0,0.0,1.0,-0.000265177950495854,-0.0005966940079815686,0.013097708113491535,0.43011149764060974,0.1570245772600174,-0.011635911650955677 +1769682076,899393536,0.0,0.0,0.0,1.0,-0.0003216706681996584,-0.0007531510200351477,0.013107534497976303,0.43007880449295044,0.1569671630859375,-0.005685687065124512 +1769682076,947039744,0.0,0.0,0.0,1.0,-0.00037225993582978845,-0.0006950176903046668,0.013040805235505104,0.33916643261909485,-0.03896801546216011,-0.008231541141867638 +1769682076,969317376,0.0,0.0,0.0,1.0,-0.0006104839849285781,-0.0008374900207854807,0.012882283888757229,0.33920732140541077,-0.039166636765003204,-0.01181558333337307 +1769682077,653568,0.0,0.0,0.0,1.0,-0.0009495170670561492,-0.0007464858354069293,0.01266070269048214,0.24797199666500092,-0.2348468154668808,-0.009596457704901695 +1769682077,48444928,0.0,0.0,0.0,1.0,-0.0007645137375220656,-0.000721067248377949,0.012397939339280128,0.33870530128479004,-0.0389079749584198,0.017957612872123718 +1769682077,66733568,0.0,0.0,0.0,1.0,-0.00044871235149912536,-0.0007154523627832532,0.01229555532336235,0.72984379529953,-0.22197894752025604,0.011981233954429626 +1769682077,105638912,0.0,0.0,0.0,1.0,-0.0003171825665049255,-0.0008320311899296939,0.012288859114050865,0.7296421527862549,-0.22222639620304108,0.017912304028868675 +1769682077,146056448,0.0,0.0,0.0,1.0,-0.0003576828457880765,-0.0008087579626590014,0.012314747087657452,0.677984893321991,-0.07945193350315094,-0.0070458268746733665 +1769682077,167197440,0.0,0.0,0.0,1.0,-0.0001839067117543891,-0.00019419705495238304,0.012357328087091446,0.5344130992889404,-0.13153143227100372,-0.004740271717309952 +1769682077,199474688,0.0,0.0,0.0,1.0,1.5952929970808327e-05,0.0003018488350789994,0.012333402410149574,0.5345680713653564,-0.13197410106658936,-0.017848167568445206 +1769682077,250156800,0.0,0.0,0.0,1.0,-0.0001776290882844478,0.0006645926041528583,0.012199338525533676,0.5342442393302917,-0.13192446529865265,-0.0011540921404957771 +1769682077,266427648,0.0,0.0,0.0,1.0,-0.0004201923729851842,0.0009165095980279148,0.012024530209600925,0.6261770129203796,0.06299532949924469,-0.010504523292183876 +1769682077,300988160,0.0,0.0,0.0,1.0,-0.0005358530906960368,0.0011249654926359653,0.01184906717389822,0.3908783197402954,-0.18433277308940887,-0.02147095277905464 +1769682077,343119360,0.0,0.0,0.0,1.0,-0.0004936481127515435,0.0011069669853895903,0.011663423851132393,0.4825999438762665,0.010921761393547058,-0.009354749694466591 +1769682077,370148864,0.0,0.0,0.0,1.0,0.00010422727791592479,0.0009634782327339053,0.011624238453805447,0.23569060862064362,0.24671189486980438,0.0002842170652002096 +1769682077,400395776,0.0,0.0,0.0,1.0,-7.556637865491211e-05,0.0008560735150240362,0.01164259947836399,0.43077296018600464,0.15463539958000183,0.011025948449969292 +1769682077,444122368,0.0,0.0,0.0,1.0,1.6443271306343377e-05,0.0008748366381041706,0.01167340762913227,0.5230278372764587,0.3495870530605316,0.013620635494589806 +1769682077,466388224,0.0,0.0,0.0,1.0,-0.0001716835831757635,0.0006472925888374448,0.011632938869297504,0.5849302411079407,-0.27666014432907104,0.0215085968375206 +1769682077,502403072,0.0,0.0,0.0,1.0,-0.0004352114046923816,0.0005566970212385058,0.011527789756655693,0.6261213421821594,0.06157972663640976,0.003931542858481407 +1769682077,549288448,0.0,0.0,0.0,1.0,-0.0006716413190588355,0.0005189825315028429,0.011288176290690899,0.4826066195964813,0.009826431050896645,-0.008087316527962685 +1769682077,566206208,0.0,0.0,0.0,1.0,-0.0004953978932462633,0.0003221806837245822,0.011062098667025566,0.4314107894897461,0.1533937156200409,-0.010371647775173187 +1769682077,599908864,0.0,0.0,0.0,1.0,-0.00037143786903470755,-8.167414489435032e-05,0.010809074155986309,0.5334651470184326,-0.13388285040855408,0.01327701099216938 +1769682077,655584000,0.0,0.0,0.0,1.0,-0.0006487664068117738,-0.00023667447385378182,0.01051917765289545,0.49176737666130066,-0.4726893901824951,0.020106416195631027 +1769682077,672938752,0.0,0.0,0.0,1.0,4.643383726943284e-05,-0.0004430669650901109,0.010435511358082294,0.48250752687454224,0.00928446650505066,-0.0009370483458042145 +1769682077,699330048,0.0,0.0,0.0,1.0,-3.132244455628097e-05,-0.00036522519076243043,0.010468507185578346,0.33871135115623474,-0.041888631880283356,-0.0022504646331071854 +1769682077,747691520,0.0,0.0,0.0,1.0,0.0004756845301017165,-0.0005648101214319468,0.010641765780746937,0.28737980127334595,0.10223276168107986,0.01929331198334694 +1769682077,771655680,0.0,0.0,0.0,1.0,0.00039233718416653574,-0.0004603884881362319,0.010755798779428005,0.676949679851532,-0.08379283547401428,0.02169663831591606 +1769682077,800315648,0.0,0.0,0.0,1.0,0.0001031998690450564,-0.0004293883393984288,0.010835499502718449,0.338573157787323,-0.04213958978652954,0.0036934721283614635 +1769682077,844195584,0.0,0.0,0.0,1.0,8.413373143412173e-05,-0.0002008613955695182,0.01081265602260828,0.5838332772254944,-0.279031366109848,0.020284686237573624 +1769682077,867036672,0.0,0.0,0.0,1.0,-0.00018885153986047953,-0.00018219985940959305,0.01068294420838356,0.71958988904953,0.2536414861679077,-0.0018544625490903854 +1769682077,902261760,0.0,0.0,0.0,1.0,-0.00020039209630340338,-0.00017316435696557164,0.010503564029932022,0.38899821043014526,-0.18614372611045837,0.020268836989998817 +1769682077,945521152,0.0,0.0,0.0,1.0,-0.0008206355851143599,-0.00010224661673419178,0.010276501066982746,0.6768348813056946,-0.08506341278553009,0.019282447174191475 +1769682077,967819776,0.0,0.0,0.0,1.0,-0.00015189066471066326,-0.00022209101007319987,0.010224996134638786,0.5834723114967346,-0.2798480689525604,0.01906740665435791 +1769682077,999665920,0.0,0.0,0.0,1.0,0.0003960473113693297,-0.00026561113190837204,0.010312860831618309,0.48231446743011475,0.007870139554142952,0.013315549120306969 +1769682078,58462976,0.0,0.0,0.0,1.0,0.0002920546685345471,-0.00033187371445819736,0.010530225932598114,0.6765990853309631,-0.0855846181511879,0.028800498694181442 +1769682078,75539712,0.0,0.0,0.0,1.0,2.944041625596583e-05,-0.00011821754014817998,0.010750682093203068,0.4321935176849365,0.1511095017194748,-0.008040307089686394 +1769682078,101531648,0.0,0.0,0.0,1.0,0.00014772573194932193,-0.00011617562267929316,0.01081234309822321,0.4823782742023468,0.007291875779628754,0.009729751385748386 +1769682078,143899904,0.0,0.0,0.0,1.0,-0.0001862034696387127,-0.00013921853678766638,0.010827491991221905,0.8710018992424011,-0.18015378713607788,0.024015061557292938 +1769682078,169916672,0.0,0.0,0.0,1.0,-0.00011697631271090358,-0.00015765560965519398,0.010726402513682842,0.6264910697937012,0.05716390162706375,0.007440934889018536 +1769682078,200510720,0.0,0.0,0.0,1.0,-0.0005941936979070306,-0.000217277993215248,0.010521352291107178,0.2880434989929199,0.10062742978334427,0.008541392162442207 +1769682078,244829696,0.0,0.0,0.0,1.0,-0.0008020380628295243,-0.0001524005929240957,0.010153613053262234,0.5827456116676331,-0.281602680683136,0.014256476424634457 +1769682078,267003648,0.0,0.0,0.0,1.0,-0.001066768541932106,-0.00035306307836435735,0.009859479032456875,0.6765745878219604,-0.08745133131742477,0.016845710575580597 +1769682078,301872896,0.0,0.0,0.0,1.0,-0.0009308748412877321,-0.0003076574648730457,0.00960426963865757,0.8208513259887695,-0.037756409496068954,0.006209898740053177 +1769682078,346119680,0.0,0.0,0.0,1.0,-0.00032497092615813017,-0.00022319721756502986,0.009436670690774918,0.48234012722969055,0.006172763183712959,0.013280453160405159 +1769682078,366557440,0.0,0.0,0.0,1.0,2.667587250471115e-05,-0.0001660340785747394,0.009478012099862099,0.5325601696968079,-0.13838133215904236,0.001233480405062437 +1769682078,400947200,0.0,0.0,0.0,1.0,0.00017626106273382902,-0.0002861686807591468,0.00967630185186863,0.6269862651824951,0.05529733747243881,-0.016423644497990608 +1769682078,458158848,0.0,0.0,0.0,1.0,0.00041853508446365595,-0.00045250364928506315,0.01006089523434639,1.0647108554840088,-0.277225524187088,0.016747308894991875 +1769682078,476181248,0.0,0.0,0.0,1.0,0.0003619181225076318,-0.00038475554902106524,0.0103832446038723,0.4824585020542145,0.005374673753976822,0.006107209715992212 +1769682078,499763200,0.0,0.0,0.0,1.0,0.00020484269771259278,-0.0003255042538512498,0.010469666682183743,0.7263875007629395,-0.23344001173973083,0.005947137717157602 +1769682078,545159168,0.0,0.0,0.0,1.0,-0.0005327180260792375,-0.00032076891511678696,0.010475733317434788,0.676576554775238,-0.08955196291208267,0.001293489709496498 +1769682078,573505280,0.0,0.0,0.0,1.0,-0.0006127493688836694,-0.0001534674083814025,0.01037556305527687,0.6271357536315918,0.054134078323841095,-0.020037228241562843 +1769682078,601125376,0.0,0.0,0.0,1.0,-0.00038550252793356776,0.00026568854809738696,0.010216602124273777,0.8207709789276123,-0.040269698947668076,0.0037600556388497353 +1769682078,650863104,0.0,0.0,0.0,1.0,-0.000683677033521235,0.000602202897425741,0.009949544444680214,0.6267915368080139,0.05415508151054382,0.005005474202334881 +1769682078,666732288,0.0,0.0,0.0,1.0,-0.0002921122941188514,0.0007063240627758205,0.009759497828781605,0.626697838306427,0.05410339683294296,0.012170098721981049 +1769682078,705923840,0.0,0.0,0.0,1.0,-0.00040274375351145864,0.0006534588756039739,0.00956804770976305,0.5817874670028687,-0.2847713530063629,-0.009631020948290825 +1769682078,746508288,0.0,0.0,0.0,1.0,9.074443369172513e-05,0.000679744640365243,0.009511809796094894,0.6267333626747131,0.053682684898376465,0.01220107451081276 +1769682078,769578240,0.0,0.0,0.0,1.0,0.0002625169581733644,0.0005879834061488509,0.009682536125183105,0.5812763571739197,-0.2846840023994446,0.01303289458155632 +1769682078,799727616,0.0,0.0,0.0,1.0,0.0006286345887929201,0.00043336552334949374,0.010012137703597546,0.4825458824634552,0.0037405285984277725,0.0013855635188519955 +1769682078,843753216,0.0,0.0,0.0,1.0,0.0009634782327339053,0.00035448139533400536,0.01054071169346571,0.5279483199119568,0.3420725464820862,0.02081792987883091 +1769682078,867414016,0.0,0.0,0.0,1.0,0.0004993350594304502,0.0002319652121514082,0.0108822425827384,0.6762394905090332,-0.09174655377864838,0.0037698112428188324 +1769682078,900413952,0.0,0.0,0.0,1.0,0.00013695341476704925,0.0002819993533194065,0.01110046822577715,0.8207184076309204,-0.0428377203643322,-0.0008814465254545212 +1769682078,944239360,0.0,0.0,0.0,1.0,-5.462983972392976e-05,0.0002550676872488111,0.011177643202245235,0.7714483737945557,0.10134673118591309,0.002819526009261608 +1769682078,969913088,0.0,0.0,0.0,1.0,-0.0006287859287112951,0.0002527687465772033,0.011061511933803558,0.4824235439300537,0.00300506129860878,0.009751041419804096 +1769682079,40960,0.0,0.0,0.0,1.0,-0.0007881829515099525,0.0002981574216391891,0.01083054393529892,0.43326911330223083,0.14743025600910187,0.013453724794089794 +1769682079,45426432,0.0,0.0,0.0,1.0,-0.0010425852378830314,0.00035718412254936993,0.010421394370496273,0.5804488062858582,-0.28636544942855835,0.013079961761832237 +1769682079,67083008,0.0,0.0,0.0,1.0,-0.0008740638731978834,0.00022012768022250384,0.010096607729792595,0.6271653771400452,0.051210738718509674,-0.0032235169783234596 +1769682079,105412096,0.0,0.0,0.0,1.0,-0.0005305579397827387,0.0002998279524035752,0.009742803871631622,0.6757634878158569,-0.09319108724594116,0.01929343119263649 +1769682079,146401792,0.0,0.0,0.0,1.0,-0.000506956537719816,0.0003174794837832451,0.009626267477869987,0.4822440445423126,0.002385515719652176,0.021693013608455658 +1769682079,166629888,0.0,0.0,0.0,1.0,6.738137744832784e-05,0.00029308433295227587,0.009764187969267368,0.33816656470298767,-0.04716850817203522,-0.010607872158288956 +1769682079,200773120,0.0,0.0,0.0,1.0,0.0006391499191522598,4.982815153198317e-05,0.010099155828356743,0.7226661443710327,0.24419359862804413,0.018511082977056503 +1769682079,257304064,0.0,0.0,0.0,1.0,0.0006845423486083746,-6.793624925194308e-05,0.010671919211745262,0.7228782773017883,0.24375861883163452,0.011353484354913235 +1769682079,277591808,0.0,0.0,0.0,1.0,0.0008126820903271437,-0.0001266615727217868,0.01118503138422966,0.9649519324302673,0.002820238471031189,0.013599170371890068 +1769682079,299540224,0.0,0.0,0.0,1.0,0.0003088002558797598,-9.085515921469778e-05,0.01134248822927475,0.7244707942008972,-0.23947423696517944,0.003693732898682356 +1769682079,345458432,0.0,0.0,0.0,1.0,-6.317230872809887e-05,-1.798018638510257e-05,0.011473236605525017,0.8203819394111633,-0.04650018736720085,0.007514765951782465 +1769682079,372029184,0.0,0.0,0.0,1.0,-0.00031321041751652956,-6.418275734176859e-05,0.01138350460678339,0.9647348523139954,0.002097219228744507,0.02789430320262909 +1769682079,399777536,0.0,0.0,0.0,1.0,-0.0007898238254711032,0.00010162244871025905,0.011134270578622818,0.6754708886146545,-0.09528571367263794,0.019307032227516174 +1769682079,445514752,0.0,0.0,0.0,1.0,-0.0011056740768253803,0.00012155895819887519,0.010704358108341694,0.6754658818244934,-0.09562485665082932,0.01692291721701622 +1769682079,466813440,0.0,0.0,0.0,1.0,-0.0008814922766759992,0.00014601914153899997,0.010348259471356869,0.5790311098098755,-0.2888777554035187,0.02023443579673767 +1769682079,501824256,0.0,0.0,0.0,1.0,-0.0008615183760412037,0.0001266963081434369,0.009987923316657543,0.8686919808387756,-0.19276157021522522,0.0038024811074137688 +1769682079,545820416,0.0,0.0,0.0,1.0,-0.0007303312886506319,0.00021194845612626523,0.009596133604645729,0.723558247089386,-0.24098767340183258,0.02273714728653431 +1769682079,566662912,0.0,0.0,0.0,1.0,-0.0006028742645867169,0.0001758239377522841,0.009412257000803947,0.5791369676589966,0.19278211891651154,-0.0006571691483259201 +1769682079,599666944,0.0,0.0,0.0,1.0,-0.0002991599903907627,-1.5536534192506224e-05,0.009349729865789413,0.43417853116989136,0.14472468197345734,0.01351169217377901 +1769682079,648483072,0.0,0.0,0.0,1.0,0.000640754762571305,-0.00025287785683758557,0.009656129404902458,0.6273349523544312,0.0476500429213047,0.003959582187235355 +1769682079,668722176,0.0,0.0,0.0,1.0,0.000866516144014895,-0.0001889530394691974,0.010175786912441254,0.33760616183280945,-0.04855089634656906,0.00965217687189579 +1769682079,700720384,0.0,0.0,0.0,1.0,0.0013308535562828183,-0.0001528993743704632,0.010868865996599197,0.43426838517189026,0.14435873925685883,0.017068542540073395 +1769682079,741837824,0.0,0.0,0.0,1.0,0.0013113160384818912,-0.0001448168040951714,0.01173884142190218,0.7723219990730286,0.09483594447374344,-0.0006970874965190887 +1769682079,773693696,0.0,0.0,0.0,1.0,0.0006036516861058772,-0.00013105911784805357,0.012239872477948666,0.7229822874069214,-0.24270831048488617,0.022756190970540047 +1769682079,800300544,0.0,0.0,0.0,1.0,0.00019255871302448213,-3.154399018967524e-05,0.012544565834105015,0.4823762774467468,-0.0011500492691993713,0.013350934721529484 +1769682079,848369152,0.0,0.0,0.0,1.0,-0.000657367636449635,-0.00020031466556247324,0.012625844217836857,0.5300020575523376,-0.14611920714378357,0.02513820305466652 +1769682079,866862336,0.0,0.0,0.0,1.0,-0.0009509763331152499,-0.00016267559840343893,0.012432185932993889,0.4823571443557739,-0.0015528574585914612,0.014536322094500065 +1769682079,903360768,0.0,0.0,0.0,1.0,-0.0012938342988491058,-0.00014739720791112632,0.011936536990106106,0.3850942850112915,-0.19444522261619568,0.013078073039650917 +1769682079,944939264,0.0,0.0,0.0,1.0,-0.0013001641491428018,-9.03481850400567e-06,0.011528471484780312,0.3872539699077606,0.28785648941993713,0.00409602839499712 +1769682079,967220480,0.0,0.0,0.0,1.0,-0.0015269034774973989,3.455545083852485e-06,0.011126851662993431,0.6276052594184875,0.04511380195617676,-0.002027123235166073 +1769682079,999644160,0.0,0.0,0.0,1.0,-0.001308596576564014,-0.00017099827527999878,0.010779331438243389,0.7248240113258362,0.23777775466442108,0.016132956370711327 +1769682080,49384192,0.0,0.0,0.0,1.0,-0.0008962875581346452,-0.0001647497119847685,0.010402169078588486,0.5800190567970276,0.18987998366355896,0.007665595971047878 +1769682080,68831744,0.0,0.0,0.0,1.0,-0.0007004353683441877,-0.00014855287736281753,0.010199607349932194,0.43510329723358154,0.14222069084644318,0.0027712611481547356 +1769682080,99782144,0.0,0.0,0.0,1.0,-0.0006305724382400513,-5.336725735105574e-05,0.01005448866635561,0.6747271418571472,-0.1004287451505661,0.019246507436037064 +1769682080,146134272,0.0,0.0,0.0,1.0,-0.0002551187644712627,0.00010761959129013121,0.009960582479834557,0.7250555157661438,0.23687084019184113,0.023295272141695023 +1769682080,170734848,0.0,0.0,0.0,1.0,-4.2788960854522884e-05,-1.5100327800610103e-05,0.009929078631103039,0.5330901145935059,0.3341085612773895,0.000692238099873066 +1769682080,201095168,0.0,0.0,0.0,1.0,0.000291220290819183,-6.676682824036106e-05,0.010045812465250492,0.7725651264190674,0.09114809334278107,0.014778923243284225 +1769682080,247782912,0.0,0.0,0.0,1.0,0.0008817162015475333,-1.7586024114280008e-05,0.010559584945440292,0.7728011608123779,0.0905856341123581,0.0016656061634421349 +1769682080,266414336,0.0,0.0,0.0,1.0,0.0013427307130768895,-5.993647937430069e-05,0.011220126412808895,0.5804819464683533,0.18849387764930725,0.006463656201958656 +1769682080,305361152,0.0,0.0,0.0,1.0,0.0011343464720994234,-9.885164035949856e-05,0.012257675640285015,0.7259528040885925,0.2349783331155777,-0.007726514711976051 +1769682080,347603456,0.0,0.0,0.0,1.0,0.000984351267106831,-0.00013672311615664512,0.012934167869389057,0.7216178774833679,-0.2475660741329193,0.0095681706443429 +1769682080,369229824,0.0,0.0,0.0,1.0,0.00046745705185458064,-0.000261222681729123,0.013436093926429749,0.7215911149978638,-0.2479427605867386,0.0048007541336119175 +1769682080,399466752,0.0,0.0,0.0,1.0,-0.00017018005019053817,-0.0003175678139086813,0.013687311671674252,0.6230713725090027,-0.4402279555797577,0.010487432591617107 +1769682080,449623296,0.0,0.0,0.0,1.0,-0.000792799866758287,-0.00042345005203969777,0.013649373315274715,0.6274952292442322,0.0422048419713974,0.020573880523443222 +1769682080,467485440,0.0,0.0,0.0,1.0,-0.0014182196464389563,-0.00034165926626883447,0.013352750800549984,0.4304177761077881,-0.34197744727134705,0.024785086512565613 +1769682080,500086016,0.0,0.0,0.0,1.0,-0.001616229536011815,-0.0003465242334641516,0.012895611114799976,0.8195639252662659,-0.05701449513435364,0.016938693821430206 +1769682080,542259200,0.0,0.0,0.0,1.0,-0.002114530187100172,-0.00013534263416659087,0.012226602993905544,0.6742282509803772,-0.10401159524917603,0.016806919127702713 +1769682080,571776768,0.0,0.0,0.0,1.0,-0.0018227564869448543,-0.00016132986638695002,0.011752724647521973,0.43597158789634705,0.13960407674312592,0.00036434968933463097 +1769682080,600462080,0.0,0.0,0.0,1.0,-0.0010803211480379105,-0.00012030922516714782,0.011355212889611721,0.6802658438682556,0.37767964601516724,-0.005152742378413677 +1769682080,648828416,0.0,0.0,0.0,1.0,-0.001142743043601513,-0.00019624900596681982,0.010898643173277378,0.7732071280479431,0.08678038418292999,0.003994646016508341 +1769682080,667529472,0.0,0.0,0.0,1.0,-0.0007605114369653165,-0.0002861006651073694,0.010636942461133003,0.6279308795928955,0.040070220828056335,-0.0008996827527880669 +1769682080,704863232,0.0,0.0,0.0,1.0,-0.0002460729447193444,-0.0001734898833092302,0.01040270272642374,0.5288323760032654,-0.1518395096063614,0.003531391266733408 +1769682080,744992000,0.0,0.0,0.0,1.0,-0.0003838847333099693,-0.00010132676834473386,0.010270711034536362,0.6276400089263916,0.04000760614871979,0.020546551793813705 +1769682080,767188736,0.0,0.0,0.0,1.0,-0.00018418865511193871,-8.473891648463905e-05,0.01016713585704565,0.48249542713165283,-0.006736744195222855,0.002543963957577944 +1769682080,799608064,0.0,0.0,0.0,1.0,-7.102925155777484e-05,-0.0001125623457483016,0.010089832358062267,0.7271153330802917,0.2309829592704773,0.005384648684412241 +1769682080,851192832,0.0,0.0,0.0,1.0,-4.109177825739607e-05,-0.00020655446860473603,0.009995968081057072,0.6279640793800354,0.03902209550142288,0.0014696596190333366 +1769682080,867097088,0.0,0.0,0.0,1.0,-6.968715024413541e-05,-0.0004060364153701812,0.009902638383209705,0.7197291254997253,-0.2515680491924286,0.0332174077630043 +1769682080,900081920,0.0,0.0,0.0,1.0,-3.4573167795315385e-06,-0.00030465712188743055,0.00985100120306015,0.3830401301383972,-0.19886372983455658,0.0045808954164385796 +1769682080,948035840,0.0,0.0,0.0,1.0,0.0002755494206212461,-0.0007638134993612766,0.009913954883813858,0.33668196201324463,-0.05315699428319931,0.022662809118628502 +1769682080,969871104,0.0,0.0,0.0,1.0,0.0008390722214244306,-0.0009244236280210316,0.010211905464529991,0.2372630536556244,-0.24490958452224731,0.012796838767826557 +1769682081,18500352,0.0,0.0,0.0,1.0,0.0009725176496431231,-0.0006830177153460681,0.01085669081658125,0.5821211934089661,0.18350665271282196,0.0016139950603246689 +1769682081,44119296,0.0,0.0,0.0,1.0,0.0011697569862008095,-0.0004157954244874418,0.011541812680661678,0.23699654638767242,-0.24505001306533813,0.016378451138734818 +1769682081,68686848,0.0,0.0,0.0,1.0,0.0005900544347241521,-0.00014735849981661886,0.011817403137683868,0.4367159605026245,0.1372915506362915,-0.0008928440511226654 +1769682081,101387264,0.0,0.0,0.0,1.0,0.00033797419746406376,-0.00029255542904138565,0.01216653361916542,0.6738086938858032,-0.10830091685056686,0.002375164069235325 +1769682081,146633984,0.0,0.0,0.0,1.0,-0.0003629831480793655,-0.0004346199566498399,0.012393167242407799,0.43655338883399963,0.13727237284183502,0.01816394180059433 +1769682081,166793472,0.0,0.0,0.0,1.0,-0.0008744372753426433,-0.0007422952330671251,0.012365761213004589,0.19130505621433258,-0.10012304037809372,-0.003685764968395233 +1769682081,213166848,0.0,0.0,0.0,1.0,-0.00091666413936764,-0.0007249877671711147,0.012194410897791386,0.8193138241767883,-0.06359253823757172,0.002422885037958622 +1769682081,246841856,0.0,0.0,0.0,1.0,-0.0013825123896822333,-0.0008297630120068789,0.011796364560723305,0.4368952512741089,0.13651838898658752,0.006228774320334196 +1769682081,268187904,0.0,0.0,0.0,1.0,-0.001453330391086638,-0.0006567795062437654,0.011441183276474476,0.6734111905097961,-0.10946771502494812,0.014202740974724293 +1769682081,299646208,0.0,0.0,0.0,1.0,-0.0014965217560529709,-0.00041294822585769,0.011050703004002571,0.6732708811759949,-0.109562449157238,0.02133850008249283 +1769682081,359890176,0.0,0.0,0.0,1.0,-0.0014484330313280225,-0.00032461516093462706,0.01050026435405016,0.5275822281837463,-0.15524713695049286,0.016464857384562492 +1769682081,368420864,0.0,0.0,0.0,1.0,-0.0014028864679858088,-0.0005430658929981291,0.010090481489896774,0.38203418254852295,-0.2009565830230713,0.0008701090700924397 +1769682081,401242368,0.0,0.0,0.0,1.0,-0.001157496590167284,-0.0006766972946934402,0.0096996845677495,0.5827122330665588,0.18118490278720856,0.017032623291015625 +1769682081,443579904,0.0,0.0,0.0,1.0,-0.0007832266855984926,-0.0006385519518516958,0.009176257066428661,0.5275173187255859,-0.15587295591831207,0.010457870550453663 +1769682081,468076288,0.0,0.0,0.0,1.0,-0.0007625081343576312,-0.000999479671008885,0.008782956749200821,0.5274930596351624,-0.15603597462177277,0.009248210117220879 +1769682081,500944640,0.0,0.0,0.0,1.0,-0.0006991542177274823,-0.0011583497980609536,0.008394011296331882,0.5828076004981995,0.18074724078178406,0.021767083555459976 +1769682081,545471488,0.0,0.0,0.0,1.0,-0.0003216397890355438,-0.0014087274903431535,0.007906789891421795,0.6729070544242859,-0.11093087494373322,0.02953101508319378 +1769682081,566448896,0.0,0.0,0.0,1.0,-0.0005157441482879221,-0.001521228812634945,0.007546834647655487,0.48233866691589355,-0.010654028505086899,0.008261030539870262 +1769682081,610672896,0.0,0.0,0.0,1.0,-0.00022954223095439374,-0.0013656325172632933,0.007183136884123087,0.7291871309280396,0.22472995519638062,-0.008040618151426315 +1769682081,648259840,0.0,0.0,0.0,1.0,-0.00010954577737720683,-0.0010709413327276707,0.0067368499003350735,0.4375487267971039,0.13472239673137665,-0.004606491886079311 +1769682081,667057152,0.0,0.0,0.0,1.0,-0.00047172344056889415,-0.0007837942102923989,0.006379150319844484,0.5832722187042236,0.17971740663051605,0.004967766348272562 +1769682081,700596992,0.0,0.0,0.0,1.0,-0.0002849023730959743,-0.0005506675806827843,0.006035267375409603,0.437193363904953,0.13507583737373352,0.02397962659597397 +1769682081,757301504,0.0,0.0,0.0,1.0,-0.00028501194901764393,-0.0007444003713317215,0.0056008086539804935,0.48212650418281555,-0.010927261784672737,0.022488882765173912 +1769682081,771046400,0.0,0.0,0.0,1.0,0.00028968308470211923,-0.0028286059387028217,0.005316086113452911,0.6278532147407532,0.03399144858121872,0.032031476497650146 +1769682081,802579712,0.0,0.0,0.0,1.0,-7.297081174328923e-05,-0.005284679587930441,0.005051161628216505,0.04424285516142845,-0.14511430263519287,0.04260364919900894 +1769682081,846728704,0.0,0.0,0.0,1.0,-7.270067726494744e-05,-0.005172290373593569,0.004718833602964878,0.3818286061286926,-0.2028682827949524,-0.03402724862098694 +1769682081,879350784,0.0,0.0,0.0,1.0,-6.80199300404638e-05,-0.00133746606297791,0.004455273505300283,0.5277615785598755,-0.1582755744457245,-0.04004528746008873 +1769682081,900073216,0.0,0.0,0.0,1.0,0.000523173832334578,0.00044558412628248334,0.004204919096082449,0.39311936497688293,0.279814213514328,-0.016451191157102585 +1769682081,947145472,0.0,0.0,0.0,1.0,8.433569018961862e-05,0.002842313377186656,0.0038659567944705486,0.6849561929702759,0.36917319893836975,-0.016447918489575386 +1769682081,967244032,0.0,0.0,0.0,1.0,-0.00012765788414981216,0.0025466817896813154,0.00361430156044662,0.6726729869842529,-0.11255587637424469,0.027976438403129578 +1769682082,13926656,0.0,0.0,0.0,1.0,0.0003701512177940458,0.001554106012918055,0.003388596000149846,0.6727418899536133,-0.1127338781952858,0.022056665271520615 +1769682082,49657856,0.0,0.0,0.0,1.0,-8.028979209484532e-06,-0.00010779633885249496,0.0030998766887933016,0.4379784166812897,0.13365714251995087,-0.017859887331724167 +1769682082,69134848,0.0,0.0,0.0,1.0,-8.022117253858596e-05,0.00019233868806622922,0.00291331484913826,0.29182931780815125,0.0892956405878067,1.4104880392551422e-05 +1769682082,100992000,0.0,0.0,0.0,1.0,0.0002515448140911758,-5.261308251647279e-05,0.002723891055211425,0.7740515470504761,0.07751473784446716,0.015223697759211063 +1769682082,159826688,0.0,0.0,0.0,1.0,-9.485602640779689e-05,-0.000990071683190763,0.00249188463203609,0.48278728127479553,-0.012565825134515762,-0.02652551792562008 +1769682082,171554816,0.0,0.0,0.0,1.0,-2.6220104700769298e-05,0.00018705490219872445,0.0023213112726807594,0.4823445975780487,-0.012015104293823242,0.005652530584484339 +1769682082,201535232,0.0,0.0,0.0,1.0,2.1822386770509183e-05,-0.0004004767688456923,0.0021471811924129725,0.5834219455718994,0.1787925660610199,0.021450813859701157 +1769682082,244322048,0.0,0.0,0.0,1.0,0.00016995528130792081,0.001099083572626114,0.0019370841328054667,0.4257280230522156,-0.34868124127388,0.0002763774245977402 +1769682082,278693632,0.0,0.0,0.0,1.0,-5.3275660320650786e-05,0.0010938704945147038,0.0017705238424241543,0.6281453967094421,0.03264289349317551,0.015214706771075726 +1769682082,302338816,0.0,0.0,0.0,1.0,0.00015477357374038547,-0.0007502599619328976,0.0016113142482936382,0.4820290505886078,-0.011723028495907784,0.0283184964209795 +1769682082,344004096,0.0,0.0,0.0,1.0,-0.0002702127967495471,-0.004195645451545715,0.0014069078024476767,0.5264714360237122,-0.1575017124414444,0.039867572486400604 +1769682082,366952448,0.0,0.0,0.0,1.0,-9.231572767021134e-05,-0.005381203722208738,0.0012591587146744132,0.6279146075248718,0.03287571668624878,0.03291871398687363 +1769682082,411063808,0.0,0.0,0.0,1.0,-0.00018550165987107903,-0.005396594759076834,0.0011284103384241462,0.33623984456062317,-0.05653775855898857,0.017437569797039032 +1769682082,449259520,0.0,0.0,0.0,1.0,-7.538766658399254e-05,-0.004533232189714909,0.0009627108811400831,0.4825631082057953,-0.012523209676146507,-0.01131821796298027 +1769682082,470454272,0.0,0.0,0.0,1.0,-0.00011187609197804704,-0.0034375402610749006,0.0008475693757645786,0.628242552280426,0.03237645700573921,0.008784950710833073 +1769682082,499718912,0.0,0.0,0.0,1.0,0.00019981565128546208,-0.002300666179507971,0.0007413997664116323,0.1908029466867447,-0.10182441025972366,-0.021909447386860847 +1769682082,556731648,0.0,0.0,0.0,1.0,2.5071851268876344e-05,-0.0010708679910749197,0.0006046958733350039,0.336563378572464,-0.057032451033592224,-0.00774246035143733 +1769682082,573547264,0.0,0.0,0.0,1.0,8.012641774257645e-05,-5.5613807489862666e-05,0.00047908732085488737,0.3364546298980713,-0.05688723921775818,0.0005948557518422604 +1769682082,601403648,0.0,0.0,0.0,1.0,0.00020756440062541515,0.00020683216280303895,0.00042269896948710084,0.2920990288257599,0.0887831300497055,-0.015743307769298553 +1769682082,646631680,0.0,0.0,0.0,1.0,3.027138336619828e-05,0.0005835126503370702,0.00030967796919867396,0.3807445764541626,-0.20248189568519592,0.021710822358727455 +1769682082,682195968,0.0,0.0,0.0,1.0,5.6245789892273024e-05,0.0006572404527105391,0.00023842713562771678,0.6282013654708862,0.03237808123230934,0.012288527563214302 +1769682082,700030720,0.0,0.0,0.0,1.0,-9.340788528788835e-05,0.0006247521378099918,0.00017466254939790815,0.19053295254707336,-0.10147126764059067,-0.0016502400394529104 +1769682082,744256512,0.0,0.0,0.0,1.0,9.439286077395082e-05,0.0005705072544515133,8.679472375661135e-05,0.24710676074028015,0.23536014556884766,0.017988871783018112 +1769682082,766758400,0.0,0.0,0.0,1.0,-3.196996112819761e-05,0.00043950119288638234,2.5266834200010635e-05,0.4377002716064453,0.13380016386508942,0.01158234104514122 +1769682082,811920896,0.0,0.0,0.0,1.0,-3.59791265509557e-05,0.00022019748575985432,-2.28739736485295e-05,0.29184120893478394,0.08914221078157425,0.0045453570783138275 +1769682082,847386624,0.0,0.0,0.0,1.0,0.0002851698955055326,-1.6557411072426476e-05,-7.934903260320425e-05,0.4820946455001831,-0.011938367038965225,0.024358199909329414 +1769682082,868546816,0.0,0.0,0.0,1.0,0.00018995351274497807,9.092182881431654e-05,-0.00012692251766566187,0.3363136947154999,-0.05670413002371788,0.011359259486198425 +1769682082,899733248,0.0,0.0,0.0,1.0,0.0007636380614712834,0.026446867734193802,0.00013412036059889942,0.38680705428123474,-0.21077407896518707,-0.4321650266647339 +1769682082,959776256,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682082,968217600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682083,1189120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5947694919304922e-05,-2.1751979147666134e-05,-0.0011917894007638097 +1769682083,45297664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682083,67079424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.594779132574331e-05,2.175199733756017e-05,0.0011917894007638097 +1769682083,100843776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682083,145018112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682083,166908416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.594792956893798e-05,-2.175202280341182e-05,-0.0011917894007638097 +1769682083,210521344,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682083,252890368,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682083,269690112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.594806781213265e-05,2.1752051907242276e-05,0.0011917894007638097 +1769682083,299925760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5948107829899527e-05,-2.175205918319989e-05,-0.0011917894007638097 +1769682083,356153600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682083,371346688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5948204236337915e-05,-2.175207919208333e-05,-0.0011917894007638097 +1769682083,401261824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5948246073094197e-05,-2.1752086468040943e-05,-0.0011917894007638097 +1769682083,445146624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,3.189660492353141e-05,-4.350419476395473e-05,-0.0023835788015276194 +1769682083,484638720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-0.1459352672100067,-0.044550247490406036,-0.0011397688649594784 +1769682083,500248832,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682083,553031936,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5948438885970972e-05,2.175212102883961e-05,0.0011917894007638097 +1769682083,568423168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682083,610156544,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5948522559483536e-05,2.1752139218733646e-05,0.0011917894007638097 +1769682083,650585600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5948577129165642e-05,2.1752150132670067e-05,0.0011917894007638097 +1769682083,669925120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5948618965921924e-05,-2.175215740862768e-05,-0.0011917894007638097 +1769682083,700141312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682083,749115136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.594871537236031e-05,2.175217741751112e-05,0.0011917894007638097 +1769682083,767376384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5948757209116593e-05,-2.1752184693468735e-05,-0.0011917894007638097 +1769682083,800025600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682083,846175232,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.594885361555498e-05,-2.1752204702352174e-05,-0.0011917892843484879 +1769682083,874117120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5948908185237087e-05,-2.175221379729919e-05,-0.0011917892843484879 +1769682083,901275136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.594893547007814e-05,2.1752217435278e-05,0.0011917892843484879 +1769682083,945452032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682083,967096832,0.0,0.0,0.0,1.0,1.8781616972773918e-07,1.1900870049430523e-06,2.9381942567852093e-06,0.0,-0.0,0.0 +1769682084,1591040,0.0,0.0,0.0,1.0,3.8577195482503157e-07,1.1254639957769541e-06,2.9401082883850904e-06,3.189814378856681e-05,-4.350450399215333e-05,-0.0023835785686969757 +1769682084,53830400,0.0,0.0,0.0,1.0,3.8577195482503157e-07,1.1254641094637918e-06,2.9401082883850904e-06,-1.594912464497611e-05,2.1752266547991894e-05,0.0011917892843484879 +1769682084,69840384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.594916648173239e-05,2.1752277461928315e-05,0.0011917892843484879 +1769682084,99989760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682084,147319040,0.0,0.0,0.0,1.0,1.8781625499286747e-07,1.1900870049430523e-06,2.9381944841588847e-06,0.0,-0.0,0.0 +1769682084,167347456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682084,199950080,0.0,0.0,0.0,1.0,-1.2564315454710595e-07,7.666914143555914e-07,2.939960268122377e-06,-1.5949317457852885e-05,2.1752302927779965e-05,0.0011917892843484879 +1769682084,245154048,0.0,0.0,0.0,1.0,-5.078126719126885e-07,8.038302894419758e-07,2.9370648917392828e-06,0.044517915695905685,-0.14591319859027863,0.0032589472830295563 +1769682084,269090816,0.0,0.0,0.0,1.0,-1.2564315454710595e-07,7.666914711990103e-07,2.9399604954960523e-06,0.08900391310453415,-0.2917828857898712,0.008901476860046387 +1769682084,302657024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949393855407834e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682084,344418048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682084,377261312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682084,401446656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682084,445255168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682084,467307008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682084,515792896,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682084,550869760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682084,568656896,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682084,600370688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682084,657609728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682084,671206912,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682084,702611200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682084,745089792,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682084,778501120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682084,800088576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682084,850441472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682084,869529088,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682084,910708224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682084,949907456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682084,968005888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682085,309248,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,56625408,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,70534400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682085,101980416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,145369600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,178552832,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682085,201444352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,242617344,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,268505600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682085,308949504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,344801536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,368370176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682085,400276480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,457104640,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,470277632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682085,501427456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,543836672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,578663168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682085,601424384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,653579776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,668230656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682085,715586816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,753086208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,767601664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682085,800599296,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,854455040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,868394496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682085,902194176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,945838336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682085,977769472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682086,4374784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,46510592,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,67021056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682086,114012160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,150988800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,169460224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682086,200225536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,263780864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,271913472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682086,301250816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,345116928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,367672320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682086,406958848,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682086,453281024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,468862720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682086,500257280,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,560218880,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,576051200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,600630016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,642856704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,671268096,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682086,702610944,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,747206144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,767444480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682086,800580608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,848278784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,867320320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682086,900621312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,962771968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682086,968716288,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682087,2586112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,46226688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,70904576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682087,102161408,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,144808704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,167735552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682087,201449984,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,243593728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,268052736,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682087,300843776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,350578176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,370375424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682087,400790784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,461197312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,467825920,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682087,501841664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,542622464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,567191296,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682087,601043200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,647229952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,667252224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682087,711976704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,748259584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,769778688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682087,800303104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,861694464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,869394176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682087,901801216,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,943182592,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682087,967414528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682088,1566720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682088,57739008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682088,66552832,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682088,116413952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682088,144082432,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682088,167690240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682088,200344320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682088,253566464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682088,267112192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682088,301330944,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682088,346173952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682088,380875264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682088,401437696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682088,445327104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682088,467452416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682088,510909440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682088,550889984,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682088,570718464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682088,600809984,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682088,656332288,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682088,671085056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682088,701696512,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682088,745242112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682088,778148352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682088,801236736,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682088,846893568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682088,867847680,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682088,915020800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682088,947500800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682088,968869632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682089,974592,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,60551168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,71622144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682089,102294272,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,143278080,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,168619520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682089,201644800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,245386240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,268064000,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682089,300414720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,360175360,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,373010176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682089,401531904,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,444015616,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,469026304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682089,502698752,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,544877824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,578245888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682089,602183424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,647107072,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,667830016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682089,713103104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,748694272,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,768646144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682089,801313536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,858898688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,869523968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682089,901785856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,945173504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682089,968343808,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682090,937728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,43367680,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,68318464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682090,110804736,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,149252864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,168895232,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682090,201241600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,262012416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,270625024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682090,302916096,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,346373376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,367480064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682090,402911232,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,448682752,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,469311744,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682090,501424128,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,550449152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,568290816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682090,601570304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,655679488,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,668326912,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682090,700977152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,747012608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,779870720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682090,801827072,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,845739264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,868306944,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682090,913390080,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,950379520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682090,969762560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682091,1190400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,60015360,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,71372032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682091,102918144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,147604480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,179352576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682091,200877568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,248184064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,268024576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682091,315819264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,349074176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,368170496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682091,403470592,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,464043264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,471492352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682091,501661440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,543589376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,568183296,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682091,602468096,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,645394176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,668560128,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682091,700762624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,747931648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,768348928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682091,800759296,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,842963200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,873432320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682091,902818304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,946960384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682091,967916544,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682092,2733568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,49252608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,70161664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682092,101263872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,150342656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,168711168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682092,201744128,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,245451520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,269645312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682092,302489088,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,346228736,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,380333312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682092,400846336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,446180096,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,467685120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682092,512944384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,550346496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,568842752,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682092,601004032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,655400448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,668307712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682092,701967872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,747995648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,784634880,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,801406720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,847246080,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,867593984,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682092,900833536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,950657024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682092,969387264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682093,1694720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,46229504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,69094144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682093,101796608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,147415040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,171635968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682093,201969408,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,244904448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,282383104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682093,301704704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,346708224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,367779840,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682093,416419584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,448824320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,468235520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682093,502560256,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,554246400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,568986112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682093,602163200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,649902336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,679266048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682093,701974784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,749291520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,767998720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682093,812592640,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,848216064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,869088256,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682093,902040064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,963467776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682093,973167872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682094,2236672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,47957504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,68667136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682094,104891392,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682094,147595520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,168186112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682094,202307584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,251640576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,269573376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682094,301573376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,350397440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,375817728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,402716416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,445457408,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,468429312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682094,502643456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,548631552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,569327360,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682094,601094400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,647091200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,668291584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682094,704028928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,744999424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,771682816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682094,803543552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,846203392,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,883618304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682094,902047232,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,945339136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682094,968221696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682095,12246016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,49461248,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,70133248,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682095,101155840,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,158017280,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,173765376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,202547200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,246927616,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,278849536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682095,302323200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,350221824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,368677376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682095,414601472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,449997568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,470258688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682095,501335808,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,562229760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,571393536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682095,602961408,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,643320320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,668193792,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682095,706045696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682095,746213632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,768340480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682095,801990144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,849941760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,869876736,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682095,901302784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,943642624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682095,969823488,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682096,2885888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682096,45609216,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682096,68712448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682096,105926912,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682096,145586176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682096,169277696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682096,201285120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682096,248489728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682096,268139008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682096,302189312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682096,347063040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682096,369359872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682096,401248000,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682096,448882688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682096,483486208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682096,501614336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682096,552724480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682096,568273664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682096,612008192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682096,649933056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682096,669118464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682096,701845504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682096,755952384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682096,770249728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682096,804998912,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682096,847458048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682096,884714496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682096,901889280,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682096,947325440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682096,968619520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682097,4386048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682097,49726976,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682097,69617152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682097,101513728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682097,161211136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682097,171282432,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682097,205092864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682097,243603200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 +1769682097,268856576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682097,353511680,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682097,377361664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 +1769682097,403884288,0.0,0.0,0.0,1.0,-0.0035942692775279284,-0.009212064556777477,-9.924649202730507e-05,0.33446431159973145,-0.05416807532310486,0.15088599920272827 +1769682097,407940864,0.0,0.0,0.0,1.0,-0.004390263464301825,-0.01550078485161066,-0.000194189342437312,0.24580679833889008,0.2371724247932434,0.11813031136989594 +1769682097,445907456,0.0,0.0,0.0,1.0,-0.0030720618087798357,-0.023568470031023026,-0.0004202936834190041,-0.19129860401153564,0.1026206836104393,0.06623376905918121 +1769682097,468826624,0.0,0.0,0.0,1.0,-0.002148950472474098,-0.02424110472202301,-0.0004901762586086988,-0.0004899436025880277,0.000766909564845264,0.04290572181344032 +1769682097,501429504,0.0,0.0,0.0,1.0,-0.0012180343037471175,-0.02311142534017563,-0.0006064481567591429,-0.6725927591323853,0.11323709040880203,-0.029489953070878983 +1769682097,550935040,0.0,0.0,0.0,1.0,-0.00031764627783559263,-0.018819911405444145,-0.0007425482617691159,-0.6278324723243713,-0.03313760831952095,-0.0509251169860363 +1769682097,568925440,0.0,0.0,0.0,1.0,0.0001839823235059157,-0.014646115712821484,-0.0008361560176126659,-0.33587536215782166,0.055763281881809235,-0.06138288974761963 +1769682097,601410304,0.0,0.0,0.0,1.0,0.0009612255962565541,-0.010252624750137329,-0.0009052776731550694,-0.5707262754440308,0.30259937047958374,-0.09044621139764786 +1769682097,645191680,0.0,0.0,0.0,1.0,0.0012493893736973405,-0.005491847172379494,-0.0010041891364380717,-0.7166538238525391,0.25791454315185547,-0.0955447107553482 +1769682097,670521856,0.0,0.0,0.0,1.0,0.0013091729488223791,-0.0028898646123707294,-0.0010454467264935374,-0.42493635416030884,0.34730109572410583,-0.0802428126335144 +1769682097,702001664,0.0,0.0,0.0,1.0,0.0012595225125551224,-0.0008128851186484098,-0.0010907927062362432,-0.6725398302078247,0.11283449083566666,-0.043585922569036484 +1769682097,755006464,0.0,0.0,0.0,1.0,0.0011998306727036834,0.00039907809696160257,-0.001136689679697156,-0.8185750246047974,0.06842678040266037,-0.032128818333148956 +1769682097,770576384,0.0,0.0,0.0,1.0,0.001376171363517642,0.0009022353915497661,-0.0011475383071228862,-0.3361400067806244,0.05610959604382515,-0.03730052709579468 +1769682097,803006208,0.0,0.0,0.0,1.0,0.000923873798456043,0.0008108473266474903,-0.0011510413605719805,-0.482230007648468,0.011841455474495888,-0.01870040036737919 +1769682097,847173376,0.0,0.0,0.0,1.0,0.0010836757719516754,0.00040210873703472316,-0.0011531247291713953,-0.48229217529296875,0.01194760575890541,-0.011559967882931232 +1769682097,869215488,0.0,0.0,0.0,1.0,0.0004567274881992489,0.00010311765799997374,-0.0011407763231545687,-0.39313533902168274,-0.2797938585281372,-0.001928416546434164 +1769682097,913400064,0.0,0.0,0.0,1.0,0.0005293840076774359,-0.0002157453418476507,-0.0011110439663752913,-0.3364778459072113,0.05674684792757034,0.0008164402097463608 +1769682097,952013056,0.0,0.0,0.0,1.0,0.00012583320494741201,-0.001178049948066473,-0.0011111559579148889,-0.8634936213493347,0.21475431323051453,-0.0006400486454367638 +1769682097,971014656,0.0,0.0,0.0,1.0,0.00012787045852746814,-0.002143397694453597,-0.0010982590029016137,-0.6729643940925598,0.11344149708747864,0.001689014956355095 +1769682098,1625088,0.0,0.0,0.0,1.0,-0.00017273909179493785,-0.002586553106084466,-0.0010955261532217264,-0.48247912526130676,0.012250160798430443,0.00997002050280571 +1769682098,63450368,0.0,0.0,0.0,1.0,-0.0001889695122372359,-0.003471693489700556,-0.0010993435280397534,-0.33649638295173645,0.0567166730761528,0.002104027196764946 +1769682098,71071744,0.0,0.0,0.0,1.0,-2.6127401724806987e-05,-0.003886898048222065,-0.0010948959970846772,-0.23523470759391785,0.2472773790359497,0.0019097139593213797 +1769682098,103282432,0.0,0.0,0.0,1.0,-0.000331885035848245,-0.0037757502868771553,-0.0010906908428296447,-0.5837534070014954,-0.17833438515663147,0.012766038067638874 +1769682098,145004800,0.0,0.0,0.0,1.0,-5.193257675273344e-05,-0.003606291487812996,-0.001105829724110663,-0.6283544301986694,-0.03254355490207672,0.0062704067677259445 +1769682098,169245952,0.0,0.0,0.0,1.0,-0.0002216405118815601,-0.003887301543727517,-0.0011086781742051244,-0.6283526420593262,-0.03256448358297348,0.006340145133435726 +1769682098,205999872,0.0,0.0,0.0,1.0,-9.424093150300905e-05,-0.0037102338392287493,-0.001133360667154193,-0.6282482743263245,-0.032830312848091125,-0.00667549530044198 +1769682098,245369600,0.0,0.0,0.0,1.0,-5.401237649493851e-05,-0.0037787719629704952,-0.0011591230286285281,-0.48233652114868164,0.011797768995165825,-0.0074867671355605125 +1769682098,269176064,0.0,0.0,0.0,1.0,-4.4299747969489545e-05,-0.003996185027062893,-0.0011913120979443192,-0.42577168345451355,0.3482299745082855,-0.011900736019015312 +1769682098,301660672,0.0,0.0,0.0,1.0,-2.5839412046479993e-05,-0.004180410876870155,-0.0012320384848862886,-0.8634474873542786,0.214081272482872,-0.017438767477869987 +1769682098,357875712,0.0,0.0,0.0,1.0,-0.0004452480934560299,-0.0038632263895124197,-0.001300695352256298,-0.4822543263435364,0.011523161083459854,-0.019212618470191956 +1769682098,373480960,0.0,0.0,0.0,1.0,-0.00022963744413573295,-0.0028140905778855085,-0.0013412267435342073,-0.538774847984314,-0.32495826482772827,-0.01466422714293003 +1769682098,401848576,0.0,0.0,0.0,1.0,-0.0002898047387134284,-0.002444206504151225,-0.0013872144045308232,-0.6846684217453003,-0.3696524202823639,-0.01367250643670559 +1769682098,447592448,0.0,0.0,0.0,1.0,-0.0002926813904196024,-0.0023072464391589165,-0.0014515307266265154,-0.818881630897522,0.06826967000961304,-0.002191992476582527 +1769682098,473146368,0.0,0.0,0.0,1.0,-5.589490319835022e-05,-0.0024905919563025236,-0.0015085857594385743,-0.875407338142395,-0.26810091733932495,0.009511998854577541 +1769682098,504124416,0.0,0.0,0.0,1.0,-0.00016419112216681242,-0.002443824429064989,-0.0015624344814568758,-0.7740467190742493,-0.07801008969545364,-0.018200542777776718 +1769682098,546977024,0.0,0.0,0.0,1.0,-0.00012952768884133548,-0.002428098116070032,-0.001669149729423225,-0.717608630657196,0.25840914249420166,-0.02262512966990471 +1769682098,568444160,0.0,0.0,0.0,1.0,-1.5270108633558266e-05,-0.0020664806943386793,-0.0017463038675487041,-0.6729509830474854,0.11266706138849258,-0.011299953795969486 +1769682098,605028608,0.0,0.0,0.0,1.0,-4.802025796379894e-05,-0.0009664896642789245,-0.0018429955234751105,-0.7294076085090637,-0.22370754182338715,0.0015878574922680855 +1769682098,651876864,0.0,0.0,0.0,1.0,0.0001426935486961156,-0.000559210660867393,-0.0019273879006505013,-0.7741557955741882,-0.07787953317165375,-0.0001347418874502182 +1769682098,669231360,0.0,0.0,0.0,1.0,0.00010706937609938905,0.0010840255999937654,-0.001981232548132539,-0.8634762763977051,0.2132778763771057,-0.03341173380613327 +1769682098,702919680,0.0,0.0,0.0,1.0,0.00022024173813406378,0.0030768888536840677,-0.00201651593670249,-0.8187615871429443,0.06748738884925842,-0.024584822356700897 +1769682098,749486080,0.0,0.0,0.0,1.0,0.0002000001259148121,0.0035721284803003073,-0.0020646711345762014,-1.0658433437347412,-0.16767330467700958,-0.004269249737262726 +1769682098,769249024,0.0,0.0,0.0,1.0,-0.00010547427518758923,0.0018835890805348754,-0.0022302705328911543,-0.7293415069580078,-0.223944753408432,0.0013754572719335556 +1769682098,801976064,0.0,0.0,0.0,1.0,-0.0007053626468405128,0.0001254828239325434,-0.0024228033144026995,-0.7626826763153076,0.40425968170166016,-0.004241228569298983 +1769682098,850634752,0.0,0.0,0.0,1.0,-0.0011561919236555696,-0.0017369827255606651,-0.0026251019444316626,-0.437642365694046,-0.13427427411079407,0.010125670582056046 +1769682098,883041792,0.0,0.0,0.0,1.0,-0.0011896262876689434,-0.003045374993234873,-0.002803270472213626,-0.9199260473251343,-0.12322605401277542,-0.005236342549324036 +1769682098,902987264,0.0,0.0,0.0,1.0,-0.0011527196038514376,-0.003286972176283598,-0.0028717154636979103,-1.0657519102096558,-0.1681678295135498,-0.007741933688521385 +1769682098,946468608,0.0,0.0,0.0,1.0,-0.0013209335738793015,-0.003210346680134535,-0.003007367718964815,-0.7179243564605713,0.2579769194126129,-0.010548912920057774 +1769682098,969476096,0.0,0.0,0.0,1.0,-0.0017389331478625536,-0.00295790727250278,-0.0031023581977933645,-0.8749501705169678,-0.26949799060821533,-0.014014897868037224 +1769682099,8695040,0.0,0.0,0.0,1.0,-0.0014922141563147306,-0.0017518012318760157,-0.0031942285131663084,-0.9646123051643372,0.02180035412311554,-0.0316249281167984 +1769682099,50125568,0.0,0.0,0.0,1.0,-0.0014122892171144485,-0.0010527921840548515,-0.003240263322368264,-1.200433611869812,0.2689321041107178,-0.007667265832424164 +1769682099,69210880,0.0,0.0,0.0,1.0,-0.0013172563631087542,0.00038947875145822763,-0.00326451170258224,-1.2002086639404297,0.2681197226047516,-0.04698093980550766 +1769682099,101679104,0.0,0.0,0.0,1.0,-0.0014343212824314833,0.0016549568390473723,-0.003276060102507472,-0.8188644647598267,0.06662409007549286,-0.021936960518360138 +1769682099,158445056,0.0,0.0,0.0,1.0,-0.0011765029048547149,0.0029795279260724783,-0.003251519985496998,-0.6620452404022217,0.5937214493751526,-0.035027433186769485 +1769682099,171483904,0.0,0.0,0.0,1.0,-0.001424269750714302,0.0020163501612842083,-0.0032704004552215338,-0.6283668279647827,-0.03366255760192871,0.021476127207279205 +1769682099,201738496,0.0,0.0,0.0,1.0,-0.0015336412470787764,0.0007443242939189076,-0.0032873153686523438,-0.5275970101356506,0.15720880031585693,0.02832215093076229 +1769682099,249019648,0.0,0.0,0.0,1.0,-0.0016569863073527813,-0.001478137681260705,-0.0033154713455587626,-0.7184033393859863,0.25788673758506775,0.024136770516633987 +1769682099,270501120,0.0,0.0,0.0,1.0,-0.0016569672152400017,-0.002399055752903223,-0.0033210234250873327,-0.7183728218078613,0.25766903162002563,0.015850752592086792 +1769682099,301893888,0.0,0.0,0.0,1.0,-0.001674933242611587,-0.0029385818634182215,-0.0033234606962651014,-0.7632899284362793,0.40301257371902466,-0.0071557327173650265 +1769682099,345995008,0.0,0.0,0.0,1.0,-0.0016402594046667218,-0.003417858388274908,-0.0033103683963418007,-0.773967981338501,-0.07950787991285324,-0.0035440754145383835 +1769682099,369658624,0.0,0.0,0.0,1.0,-0.0015401772689074278,-0.0032554026693105698,-0.0032985075376927853,-0.8189442753791809,0.06596746295690536,-0.018178025260567665 +1769682099,405369088,0.0,0.0,0.0,1.0,-0.0015800312394276261,-0.002347138710319996,-0.0032386579550802708,-0.6732242703437805,0.1110716313123703,-0.010809764266014099 +1769682099,451331328,0.0,0.0,0.0,1.0,-0.0018288110150024295,-0.0017397969495505095,-0.0031844470649957657,-0.9647760391235352,0.020804911851882935,-0.011001694947481155 +1769682099,469133568,0.0,0.0,0.0,1.0,-0.0016935245366767049,-0.0014321833150461316,-0.003134234109893441,-0.6733042597770691,0.11110666394233704,-0.0011950256302952766 +1769682099,502968832,0.0,0.0,0.0,1.0,-0.002084069885313511,-0.0015585612272843719,-0.003085402073338628,-0.6731142401695251,0.11047784984111786,-0.03453020006418228 +1769682099,558326016,0.0,0.0,0.0,1.0,-0.001839080941863358,-0.0013808204093948007,-0.003007769351825118,-1.0655419826507568,-0.17001208662986755,0.01322808489203453 +1769682099,576232704,0.0,0.0,0.0,1.0,-0.0020370748825371265,-0.001352333347313106,-0.0029349213000386953,-0.7738392949104309,-0.08028984069824219,-0.015131523832678795 +1769682099,601661952,0.0,0.0,0.0,1.0,-0.0021679799538105726,-0.0012965186033397913,-0.002915146993473172,-0.6280866265296936,-0.035162344574928284,-0.01501695066690445 +1769682099,649403136,0.0,0.0,0.0,1.0,-0.002067259745672345,-0.0014127708273008466,-0.0028613728936761618,-0.7637221217155457,0.4022105634212494,-0.006385795772075653 +1769682099,672446720,0.0,0.0,0.0,1.0,-0.0020605057943612337,-0.0014444964472204447,-0.0028033133130520582,-0.864219605922699,0.2109868824481964,-0.01803489401936531 +1769682099,702805760,0.0,0.0,0.0,1.0,-0.0021036872640252113,-0.0013994124019518495,-0.002757288748398423,-0.9648299217224121,0.020166931673884392,-0.004668766632676125 +1769682099,745502976,0.0,0.0,0.0,1.0,-0.002188032027333975,-0.0013548695715144277,-0.0026228793431073427,-1.2110258340835571,-0.21624025702476501,-0.010459324344992638 +1769682099,768786944,0.0,0.0,0.0,1.0,-0.002338727004826069,-0.0012216848554089665,-0.0025076919700950384,-0.8743366003036499,-0.2715185880661011,-0.005237503442913294 +1769682099,805918976,0.0,0.0,0.0,1.0,-0.0021143555641174316,-0.0012328255688771605,-0.002295335754752159,-0.7738606333732605,-0.08056780695915222,-0.0030075320973992348 +1769682099,848960768,0.0,0.0,0.0,1.0,-0.0021676025353372097,-0.0013684419682249427,-0.0021328406874090433,-0.7186797857284546,0.2561396658420563,-0.002198224887251854 +1769682099,869601792,0.0,0.0,0.0,1.0,-0.0019692531786859035,-0.0013779448345303535,-0.0019388969521969557,-0.6734898686408997,0.11057434976100922,0.01118707936257124 +1769682099,969692160,0.0,0.0,0.0,1.0,-0.0022702058777213097,-0.001054425141774118,-0.0016871477710083127,-0.819172203540802,0.0651274248957634,0.004009981639683247 +1769682099,984181248,0.0,0.0,0.0,1.0,-0.002447035163640976,-0.0008972973446361721,-0.0014442182146012783,-1.2010241746902466,0.2654547691345215,-0.027468308806419373 +1769682099,998592256,0.0,0.0,0.0,1.0,-0.002371728653088212,-0.0009890375658869743,-0.0013336226111277938,-1.1558148860931396,0.1199435219168663,-0.011745497584342957 +1769682100,5492224,0.0,0.0,0.0,1.0,-0.0024045919999480247,-0.0005317731993272901,-0.0011168890632689,-0.6733190417289734,0.1098623126745224,-0.02444421499967575 +1769682100,47747328,0.0,0.0,0.0,1.0,-0.0011970348423346877,-0.00045803480315953493,-0.000573114026337862,-1.100770115852356,0.45668187737464905,-0.007163830101490021 +1769682100,68109056,0.0,0.0,0.0,1.0,-0.0007197527447715402,-0.00036745425313711166,-0.00020001971279270947,-0.9649210572242737,0.01976802572607994,0.010024460032582283 +1769682100,102001152,0.0,0.0,0.0,1.0,-0.0001601549593033269,-0.0003353188803885132,0.00028930322150699794,-0.6735402345657349,0.1104811429977417,0.016117241233587265 +1769682100,151415808,0.0,0.0,0.0,1.0,0.00019495657761581242,-3.110950274276547e-05,0.000843699905090034,-0.9649967551231384,0.020022498443722725,0.024339640513062477 +1769682100,170777600,0.0,0.0,0.0,1.0,0.0003013648383785039,0.00021466650650836527,0.0012045784387737513,-0.7738362550735474,-0.08080659061670303,-0.0028553111478686333 +1769682100,202674688,0.0,0.0,0.0,1.0,0.0001511279260739684,0.0005936937523074448,0.0015188864199444652,-0.6280969381332397,-0.0355750173330307,-0.008762684650719166 +1769682100,245246208,0.0,0.0,0.0,1.0,0.000505977775901556,0.0008223271579481661,0.001907716621644795,-0.9194823503494263,-0.12622816860675812,-0.01726021245121956 +1769682100,272992768,0.0,0.0,0.0,1.0,0.00029365773661993444,0.0008796540787443519,0.0021559910383075476,-0.81905198097229,0.06483703851699829,-0.017379125580191612 +1769682100,303249408,0.0,0.0,0.0,1.0,0.0005372323794290423,0.0007481602369807661,0.0024170971009880304,-0.7186928391456604,0.2561786472797394,0.0003805598244071007 +1769682100,347840000,0.0,0.0,0.0,1.0,0.0005313189467415214,0.0007398420129902661,0.002767267869785428,-0.6281004548072815,-0.0354008674621582,-0.010021451860666275 +1769682100,368942848,0.0,0.0,0.0,1.0,0.0003993733262177557,0.0009110952960327268,0.0030378964729607105,-0.9647752046585083,0.019855046644806862,-0.015145853161811829 +1769682100,405505024,0.0,0.0,0.0,1.0,0.0004436213057488203,0.0006996787269599736,0.0034287525340914726,-0.8743801116943359,-0.27141332626342773,-0.007660040631890297 +1769682100,445064192,0.0,0.0,0.0,1.0,0.0005566959735006094,0.0006334299687296152,0.003723727772012353,-0.8190498352050781,0.06534306704998016,-0.011534763500094414 +1769682100,470792448,0.0,0.0,0.0,1.0,0.00032312137773260474,0.0007897873874753714,0.004016596358269453,-0.9648065567016602,0.020313024520874023,-0.008068209514021873 +1769682100,502073344,0.0,0.0,0.0,1.0,0.00016966172552201897,0.0007879825425334275,0.004298531450331211,-0.6281858086585999,-0.03485238552093506,0.0018204869702458382 +1769682100,564418048,0.0,0.0,0.0,1.0,0.00021975382696837187,0.000871744763571769,0.004685272928327322,-0.9647262096405029,0.020400691777467728,-0.02123577706515789 +1769682100,572893952,0.0,0.0,0.0,1.0,0.0003412430523894727,0.0009352345950901508,0.004961565136909485,-0.6732792258262634,0.11102256178855896,-0.005564630497246981 +1769682100,603097856,0.0,0.0,0.0,1.0,-0.0005590067012235522,0.0014774248702451587,0.005119172856211662,-0.6278581619262695,-0.03552059829235077,-0.059027768671512604 +1769682100,647624960,0.0,0.0,0.0,1.0,-0.0018127014627680182,0.0025662812404334545,0.0052802423015236855,-0.7737653851509094,-0.08010927587747574,-0.03775344416499138 +1769682100,673396736,0.0,0.0,0.0,1.0,-0.0021972847171127796,0.0030629655811935663,0.005443782079964876,-0.33645686507225037,0.055272381752729416,-0.02906951680779457 +1769682100,701988096,0.0,0.0,0.0,1.0,-0.002605080371722579,0.0036075233947485685,0.0056363437324762344,-0.7738834619522095,-0.079586461186409,-0.0212264247238636 +1769682100,748855808,0.0,0.0,0.0,1.0,-0.0032478782813996077,0.0037543370854109526,0.005908552091568708,-0.6730867624282837,0.11142183840274811,-0.020146150141954422 +1769682100,770003200,0.0,0.0,0.0,1.0,-0.003439569380134344,0.0036398712545633316,0.006114580202847719,-0.9757440090179443,-0.4605241119861603,-0.0012684185057878494 +1769682100,804223488,0.0,0.0,0.0,1.0,-0.003461763495579362,0.0036658993922173977,0.006368372589349747,-1.1104971170425415,-0.023076757788658142,-0.023370476439595222 +1769682100,845643520,0.0,0.0,0.0,1.0,-0.0034970019478350878,0.003457664279267192,0.006575589068233967,-1.0097135305404663,0.1682509481906891,0.000463167205452919 +1769682100,870217984,0.0,0.0,0.0,1.0,-0.0035185408778488636,0.0032306259963661432,0.0068065631203353405,-0.5273043513298035,0.15723076462745667,0.004895927384495735 +1769682100,901863168,0.0,0.0,0.0,1.0,-0.003690251847729087,0.003083164105191827,0.007058833260089159,-0.4824594259262085,0.011522944085299969,0.00855272077023983 +1769682100,960941056,0.0,0.0,0.0,1.0,-0.0033440240658819675,0.0030381917022168636,0.007449386175721884,-0.8187745809555054,0.06750783324241638,-0.02321886457502842 +1769682100,976186624,0.0,0.0,0.0,1.0,-0.003420490538701415,0.0031455415301024914,0.007871574722230434,-0.7741495370864868,-0.07781711220741272,-0.0017740949988365173 +1769682101,5136128,0.0,0.0,0.0,1.0,-0.0034104730002582073,0.0032226296607404947,0.008197613060474396,-0.7741434574127197,-0.07768157124519348,-0.005430570803582668 +1769682101,45176832,0.0,0.0,0.0,1.0,-0.0033456087112426758,0.00316733680665493,0.008515976369380951,-0.8635166883468628,0.21436114609241486,-0.005632852204144001 +1769682101,76346112,0.0,0.0,0.0,1.0,-0.0033584574703127146,0.003009845968335867,0.008920865133404732,-0.6283649206161499,-0.032404009252786636,0.007891627959907055 +1769682101,102096384,0.0,0.0,0.0,1.0,-0.003385270480066538,0.0030016088858246803,0.009117134846746922,-0.2918347120285034,-0.08922041207551956,-0.0032064788974821568 +1769682101,145825792,0.0,0.0,0.0,1.0,-0.004932026378810406,0.0026386985555291176,0.009311552159488201,-0.2470783144235611,-0.2355477511882782,-0.03660920634865761 +1769682101,169196032,0.0,0.0,0.0,1.0,-0.006011568941175938,0.0020076886285096407,0.009419317357242107,-0.875579833984375,-0.26727157831192017,-0.0229780413210392 +1769682101,205315072,0.0,0.0,0.0,1.0,-0.006522688549011946,0.0013735821703448892,0.0095869405195117,-0.8185506463050842,0.06939176470041275,-0.029706252738833427 +1769682101,251753216,0.0,0.0,0.0,1.0,-0.006917068734765053,0.0011250256793573499,0.009739842265844345,-0.6726782917976379,0.11427871137857437,-0.01135382428765297 +1769682101,269931776,0.0,0.0,0.0,1.0,-0.0058903140015900135,0.00039032549830153584,0.009891903959214687,-0.38100600242614746,0.2038314938545227,0.0373314693570137 +1769682101,356883968,0.0,0.0,0.0,1.0,-0.004613176919519901,-0.0009918306022882462,0.01017887145280838,-0.8189345598220825,0.0710221454501152,0.031096823513507843 +1769682101,370817792,0.0,0.0,0.0,1.0,-0.004543237388134003,-0.001899887342005968,0.01048864796757698,-1.0092946290969849,0.1733735203742981,0.04630642011761665 +1769682101,392927232,0.0,0.0,0.0,1.0,-0.004431547597050667,-0.0022020009346306324,0.010710932314395905,-0.4824720025062561,0.013726795092225075,0.016553107649087906 +1769682101,402841856,0.0,0.0,0.0,1.0,-0.0039495183154940605,-0.002139451215043664,0.010873784311115742,-0.5706585049629211,0.3057378828525543,-0.002112730871886015 +1769682101,453012224,0.0,0.0,0.0,1.0,-0.004152173642069101,-0.002185413846746087,0.011299504898488522,-0.5263795852661133,0.15991009771823883,-0.005790151655673981 +1769682101,468650240,0.0,0.0,0.0,1.0,-0.004148347768932581,-0.0021685140673071146,0.011467475444078445,-0.8185792565345764,0.07203326374292374,0.0004198262467980385 +1769682101,514448128,0.0,0.0,0.0,1.0,-0.003816411131992936,-0.0019763547461479902,0.011723292991518974,-0.7304553985595703,-0.22011050581932068,-0.014344786293804646 +1769682101,553115904,0.0,0.0,0.0,1.0,-0.0040869261138141155,-0.0017564737936481833,0.012040476314723492,-0.6282866597175598,-0.029821641743183136,-0.02428661659359932 +1769682101,570317824,0.0,0.0,0.0,1.0,-0.003716899547725916,-0.0015534855192527175,0.012253860011696815,-0.6283482313156128,-0.029502371326088905,-0.017108194530010223 +1769682101,602212608,0.0,0.0,0.0,1.0,-0.0038092101458460093,-0.0013275389792397618,0.012437934055924416,-0.7745703458786011,-0.0729958638548851,-0.01041348185390234 +1769682101,663361536,0.0,0.0,0.0,1.0,-0.0037737982347607613,-0.0013160665985196829,0.012696769088506699,-0.5260047316551208,0.1611081212759018,-0.006695793475955725 +1769682101,671689984,0.0,0.0,0.0,1.0,-0.004007814917713404,-0.0012740634847432375,0.012911999598145485,-0.3360513746738434,0.05877833068370819,-0.006546664983034134 +1769682101,702881280,0.0,0.0,0.0,1.0,-0.0038234535604715347,-0.0013208487071096897,0.013147587887942791,-0.5259039402008057,0.16156025230884552,-0.0030417493544518948 +1769682101,749242624,0.0,0.0,0.0,1.0,-0.001738396822474897,-0.0005180700682103634,0.013884998857975006,-0.6722729206085205,0.11866918951272964,0.028703970834612846 +1769682101,768694784,0.0,0.0,0.0,1.0,-0.000828922085929662,0.0001836232258938253,0.014444083906710148,-0.6287857294082642,-0.02722538821399212,0.036643899977207184 +1769682101,803372032,0.0,0.0,0.0,1.0,-0.000262443907558918,0.0007730423239991069,0.014902404509484768,-0.7315221428871155,-0.21688412129878998,0.01666928082704544 +1769682101,846708480,0.0,0.0,0.0,1.0,2.6748835807666183e-05,0.0013103191740810871,0.015373134054243565,-0.7314700484275818,-0.21675439178943634,-0.010778434574604034 +1769682101,872194048,0.0,0.0,0.0,1.0,9.485958435107023e-05,0.0013411262771114707,0.015626072883605957,-0.5852532982826233,-0.17313611507415771,-0.00912211649119854 +1769682101,903743744,0.0,0.0,0.0,1.0,0.0005072206258773804,0.0013599207159131765,0.015872646123170853,-0.29267287254333496,-0.08639714121818542,-0.005767414346337318 +1769682101,949552128,0.0,0.0,0.0,1.0,0.0006282436661422253,0.0013967333361506462,0.016028394922614098,-0.3357888162136078,0.060079071670770645,-0.010149562731385231 +1769682101,971190016,0.0,0.0,0.0,1.0,0.0007631261833012104,0.0012485100887715816,0.016165412962436676,-0.5251163244247437,0.1634988635778427,-0.021008532494306564 +1769682102,2502912,0.0,0.0,0.0,1.0,0.0005758245242759585,0.0011475509963929653,0.016306139528751373,-0.43923696875572205,-0.12889009714126587,-0.0027364741545170546 +1769682102,63518976,0.0,0.0,0.0,1.0,0.0004921550862491131,0.0010478374315425754,0.016513364389538765,-0.671428382396698,0.12133362889289856,-0.013233417645096779 +1769682102,71917312,0.0,0.0,0.0,1.0,0.00043146172538399696,0.001109844888560474,0.01660255715250969,-0.6712759733200073,0.12151498347520828,-0.026368457823991776 +1769682102,104204032,0.0,0.0,0.0,1.0,-0.0018586262594908476,0.002258189721032977,0.016567640006542206,-0.8785040974617004,-0.256978839635849,-0.061610184609889984 +1769682102,148331776,0.0,0.0,0.0,1.0,-0.0027461617719382048,0.0033192515838891268,0.016596300527453423,-0.6709598302841187,0.12202271819114685,-0.05030708387494087 +1769682102,169152256,0.0,0.0,0.0,1.0,-0.003520695026963949,0.003940333146601915,0.01666373386979103,-0.6283486485481262,-0.024176882579922676,-0.04957948625087738 +1769682102,208229376,0.0,0.0,0.0,1.0,-0.004128080327063799,0.004473335575312376,0.01679966039955616,-0.5861660242080688,-0.16992680728435516,-0.014349039644002914 +1769682102,250356992,0.0,0.0,0.0,1.0,-0.004459606017917395,0.004502578638494015,0.01691334694623947,-0.4820280373096466,0.01932220160961151,-0.015769172459840775 +1769682102,269294592,0.0,0.0,0.0,1.0,-0.0047257812693715096,0.004611368291079998,0.017019646242260933,-0.4397827982902527,-0.12694962322711945,-0.006743879523128271 +1769682102,303016960,0.0,0.0,0.0,1.0,-0.004904582165181637,0.004519055597484112,0.01711057499051094,-0.2931723892688751,-0.08456407487392426,-0.012097876518964767 +1769682102,359331584,0.0,0.0,0.0,1.0,-0.005356566049158573,0.004430835135281086,0.01722050830721855,-0.5663052201271057,0.31358009576797485,-0.007850904949009418 +1769682102,373288704,0.0,0.0,0.0,1.0,-0.005318757612258196,0.00433594174683094,0.017302505671977997,-0.48218679428100586,0.02068137563765049,0.0101873017847538 +1769682102,404253440,0.0,0.0,0.0,1.0,-0.005420604255050421,0.004073420539498329,0.01740380749106407,-0.44022125005722046,-0.12571173906326294,0.009581480175256729 +1769682102,445373696,0.0,0.0,0.0,1.0,-0.00525696063414216,0.004100439604371786,0.017488284036517143,-0.6918811798095703,-0.35595378279685974,0.0085437698289752 +1769682102,475130368,0.0,0.0,0.0,1.0,-0.0039656274020671844,0.00483675254508853,0.017683900892734528,-0.4826706051826477,0.022125329822301865,0.07078738510608673 +1769682102,502497792,0.0,0.0,0.0,1.0,0.00036888851900584996,0.007489815354347229,0.018106993287801743,-0.29426199197769165,-0.08260161429643631,0.08052969723939896 +1769682102,555626752,0.0,0.0,0.0,1.0,0.0026254169642925262,0.009894107468426228,0.01849946193397045,-0.7760849595069885,-0.06069009378552437,0.04604917764663696 +1769682102,569503488,0.0,0.0,0.0,1.0,0.004819161724299192,0.011035059578716755,0.018665803596377373,-0.7762228846549988,-0.06015390157699585,0.05534111708402634 +1769682102,603131136,0.0,0.0,0.0,1.0,0.007917496375739574,0.010325534269213676,0.018738849088549614,-0.6296432018280029,-0.018031643703579903,0.07874439656734467 +1769682102,650306816,0.0,0.0,0.0,1.0,0.009894224815070629,0.009214340709149837,0.018755722790956497,-0.441419392824173,-0.12318559736013412,0.07200156152248383 +1769682102,672034048,0.0,0.0,0.0,1.0,0.010811899788677692,0.008338826708495617,0.018782857805490494,-0.5646480917930603,0.3172163963317871,0.014508607797324657 +1769682102,702425088,0.0,0.0,0.0,1.0,0.011684868484735489,0.00785779394209385,0.01885933242738247,-0.6289790868759155,-0.017600983381271362,0.005496155470609665 +1769682102,751551744,0.0,0.0,0.0,1.0,0.012282132171094418,0.0073890541680157185,0.01909715309739113,-0.25277701020240784,-0.22917057573795319,-0.00954208243638277 +1769682102,769185024,0.0,0.0,0.0,1.0,0.01273933332413435,0.007075359113514423,0.019386621192097664,-0.3345560133457184,0.06463980674743652,-0.036679934710264206 +1769682102,802413824,0.0,0.0,0.0,1.0,0.012893161736428738,0.007162188179790974,0.01970640756189823,-0.6081958413124084,-0.09031985700130463,-0.028344785794615746 +1769682102,846672896,0.0,0.0,0.0,1.0,0.012362807989120483,0.00720034446567297,0.020093193277716637,-0.4409465491771698,-0.12248647958040237,-0.01776808314025402 +1769682102,874913792,0.0,0.0,0.0,1.0,0.012399217113852501,0.0073575410060584545,0.020364586263895035,-0.5678684711456299,-0.23623283207416534,-0.011807632632553577 +1769682102,903152128,0.0,0.0,0.0,1.0,0.011806264519691467,0.007460825145244598,0.02044171281158924,-0.42072033882141113,-0.19559937715530396,-0.023756250739097595 +1769682102,946562560,0.0,0.0,0.0,1.0,0.01003074087202549,0.007613120600581169,0.020290818065404892,-0.7551158666610718,-0.12960919737815857,-0.0646052211523056 +1769682102,969485312,0.0,0.0,0.0,1.0,0.004918613471090794,0.00523643521592021,0.019613422453403473,-0.4203187823295593,-0.19580410420894623,-0.077471524477005 +1769682103,4190464,0.0,0.0,0.0,1.0,0.0022090261336416006,0.002873018616810441,0.01900017261505127,-0.4206371009349823,-0.19527974724769592,-0.06320703774690628 +1769682103,47913216,0.0,0.0,0.0,1.0,0.0005704008508473635,0.0017458177171647549,0.01866713911294937,-0.3809302747249603,-0.3418237864971161,-0.03312988206744194 +1769682103,69614592,0.0,0.0,0.0,1.0,-0.0001623165881028399,0.0011923146666958928,0.01838850788772106,-0.42136070132255554,-0.19421207904815674,-0.02271852269768715 +1769682103,103280128,0.0,0.0,0.0,1.0,-0.0013791467063128948,0.0008313360740430653,0.018062660470604897,-0.3345670998096466,0.06728875637054443,0.0019251564517617226 +1769682103,148385536,0.0,0.0,0.0,1.0,-0.002216181717813015,0.0009848317131400108,0.017720630392432213,-0.46188750863075256,-0.045965999364852905,0.0055497875437140465 +1769682103,169432832,0.0,0.0,0.0,1.0,-0.0021741141099482775,0.0012083427282050252,0.017566820606589317,-0.46194222569465637,-0.045687463134527206,0.007915329188108444 +1769682103,202198016,0.0,0.0,0.0,1.0,-0.0019983085803687572,0.0015226067043840885,0.017563892528414726,-0.27482929825782776,-0.1530865728855133,0.004694952163845301 +1769682103,245295360,0.0,0.0,0.0,1.0,0.0007273193914443254,0.0010727207409217954,0.01818506419658661,-0.10099669545888901,0.3705064058303833,0.1435452252626419 +1769682103,273301760,0.0,0.0,0.0,1.0,0.004905352368950844,-0.001926360186189413,0.019293665885925293,-0.6311506628990173,-0.00845826044678688,0.16138379275798798 +1769682103,303784704,0.0,0.0,0.0,1.0,0.007525433320552111,-0.004466325510293245,0.020473530516028404,-0.06103963032364845,0.22324298322200775,0.14256000518798828 +1769682103,346067200,0.0,0.0,0.0,1.0,0.009353188797831535,-0.006509286817163229,0.021872490644454956,-0.4631645679473877,-0.042847901582717896,0.095070980489254 +1769682103,369864960,0.0,0.0,0.0,1.0,0.009959317743778229,-0.00744278822094202,0.022662702947854996,-0.29550081491470337,-0.07774218171834946,0.04769298806786537 +1769682103,404245760,0.0,0.0,0.0,1.0,0.010463874787092209,-0.007989972829818726,0.023200711235404015,-0.3343040347099304,0.06954052299261093,0.015202241018414497 +1769682103,448546816,0.0,0.0,0.0,1.0,0.010623166337609291,-0.008021874353289604,0.02328028529882431,-0.40347784757614136,-0.2646375596523285,-0.005126723553985357 +1769682103,470040320,0.0,0.0,0.0,1.0,0.010744573548436165,-0.007729546632617712,0.023129167035222054,-0.12783318758010864,-0.11305632442235947,-0.02222215011715889 +1769682103,502690560,0.0,0.0,0.0,1.0,0.010733774863183498,-0.007300133816897869,0.022829707711935043,-0.4425475597381592,-0.11667876690626144,-0.016047628596425056 +1769682103,550712064,0.0,0.0,0.0,1.0,0.0110335573554039,-0.006727446336299181,0.022388609126210213,-0.03855881839990616,0.14741250872612,-0.012522709555923939 +1769682103,570037504,0.0,0.0,0.0,1.0,0.01113564521074295,-0.0063751693814992905,0.02211841195821762,-0.44262373447418213,-0.11618725955486298,-0.026476968079805374 +1769682103,602494720,0.0,0.0,0.0,1.0,0.011212769895792007,-0.005723281297832727,0.021968068554997444,-0.4237302839756012,-0.18931394815444946,-0.0021785348653793335 +1769682103,646029568,0.0,0.0,0.0,1.0,0.011723856441676617,-0.004882699344307184,0.021893462166190147,-0.16667203605175018,0.0351361483335495,-0.020236199721693993 +1769682103,672746496,0.0,0.0,0.0,1.0,0.0097274761646986,-0.003691783407703042,0.02190769463777542,-0.5132792592048645,-0.4504561722278595,-0.10395381599664688 +1769682103,703334656,0.0,0.0,0.0,1.0,0.0049307155422866344,-0.0003660586371552199,0.021875858306884766,-0.4036913514137268,-0.26483020186424255,-0.13609959185123444 +1769682103,750714624,0.0,0.0,0.0,1.0,0.002285922411829233,0.002777294721454382,0.02175411954522133,-0.2755352556705475,-0.15185187757015228,-0.09881477057933807 +1769682103,769071616,0.0,0.0,0.0,1.0,0.0011987609323114157,0.00411579804494977,0.02166476473212242,-0.12797491252422333,-0.11345809698104858,-0.08376914262771606 +1769682103,815612416,0.0,0.0,0.0,1.0,0.00011633598478510976,0.004819322377443314,0.02157706767320633,-0.4240270256996155,-0.1884041279554367,-0.050797320902347565 +1769682103,853587968,0.0,0.0,0.0,1.0,-0.0009192416328005493,0.004861733876168728,0.021382013335824013,-0.36951974034309387,-0.09445206820964813,-0.013979801908135414 +1769682103,868987904,0.0,0.0,0.0,1.0,-0.001366803073324263,0.0045806849375367165,0.02124633640050888,-0.36968472599983215,-0.09406470507383347,-0.0020985063165426254 +1769682103,901986560,0.0,0.0,0.0,1.0,-0.0017049582675099373,0.004159320145845413,0.02104600891470909,-0.1293993443250656,-0.11100905388593674,0.024598881602287292 +1769682103,959380736,0.0,0.0,0.0,1.0,-0.00206468952819705,0.003403525799512863,0.02068905532360077,-0.258719801902771,-0.2222859412431717,0.024115031585097313 +1769682103,967518208,0.0,0.0,0.0,1.0,-0.0021347629372030497,0.002964950632303953,0.02039121277630329,-0.14828966557979584,-0.036725517362356186,0.030085928738117218 +1769682104,5897216,0.0,0.0,0.0,1.0,-0.0018769903108477592,0.0024658297188580036,0.020109040662646294,-0.2403419017791748,-0.2960379421710968,0.020890070125460625 +1769682104,47273216,0.0,0.0,0.0,1.0,-0.0017391778528690338,0.0021170356776565313,0.019798187538981438,-0.24067887663841248,0.018550138920545578,0.00891161896288395 +1769682104,70438912,0.0,0.0,0.0,1.0,-0.0015126066282391548,0.0018698746571317315,0.019665736705064774,-0.07409209758043289,-0.01837579533457756,0.006680241785943508 +1769682104,102817792,0.0,0.0,0.0,1.0,-0.001201594597660005,0.001638309913687408,0.019600186496973038,-0.07405012845993042,-0.018422657623887062,0.0019085827516391873 +1769682104,148600064,0.0,0.0,0.0,1.0,-0.000688503438141197,0.001566152786836028,0.01965697854757309,-0.22206072509288788,-0.05531900376081467,-0.0062082745134830475 +1769682104,168913408,0.0,0.0,0.0,1.0,-0.0006397695979103446,0.0015407323371618986,0.019765468314290047,-0.29606175422668457,-0.0736883357167244,-0.013854654505848885 +1769682104,216841216,0.0,0.0,0.0,1.0,-0.00037117599276825786,0.001589913503266871,0.019896607846021652,-0.2962793707847595,-0.07321928441524506,0.001623830758035183 +1769682104,250597120,0.0,0.0,0.0,1.0,-0.0003005866310559213,0.001669825753197074,0.02002638578414917,-0.11178607493638992,-0.1844239979982376,0.014140786603093147 +1769682104,270796800,0.0,0.0,0.0,1.0,-0.0004071959119755775,0.001786605454981327,0.020043952390551567,-0.16638827323913574,0.037659719586372375,-0.001407105941325426 +1769682104,302384128,0.0,0.0,0.0,1.0,-0.0005333758308552206,0.001468457980081439,0.01996944472193718,-0.05624886602163315,-0.0917402058839798,0.028514938428997993 +1769682104,361143552,0.0,0.0,0.0,1.0,-0.0004229331389069557,0.0008694363059476018,0.0198042094707489,-0.20447620749473572,-0.12803727388381958,0.02154316008090973 +1769682104,377198336,0.0,0.0,0.0,1.0,-0.000360169040504843,0.0005517529207281768,0.019640546292066574,-0.16630548238754272,0.0380229726433754,-0.0014249798841774464 +1769682104,404979968,0.0,0.0,0.0,1.0,-0.0002578370040282607,0.0005062401760369539,0.019583798944950104,-0.05621422082185745,-0.09198947995901108,0.009438134729862213 +1769682104,448938496,0.0,0.0,0.0,1.0,-0.00023457231873180717,0.00034692618646658957,0.01950572431087494,-0.09448103606700897,-0.2582497000694275,0.008557338267564774 +1769682104,481438464,0.0,0.0,0.0,1.0,-0.00014674861449748278,0.0004142950929235667,0.01944788359105587,-0.2045166790485382,-0.1279890388250351,-0.003502398729324341 +1769682104,502799872,0.0,0.0,0.0,1.0,-0.00015974724374245852,0.00034383664024062455,0.019374554976820946,0.01793677732348442,-0.07426704466342926,-0.004356621764600277 +1769682104,545246720,0.0,0.0,0.0,1.0,-0.00022389835794456303,0.0005097222747281194,0.019260386005043983,-0.14833404123783112,-0.035695627331733704,-0.0034081609919667244 +1769682104,569886464,0.0,0.0,0.0,1.0,-0.000258665211731568,0.0006444971659220755,0.01914948597550392,-0.2047494798898697,-0.1276165097951889,-0.004706464242190123 +1769682104,614306048,0.0,0.0,0.0,1.0,-0.0003259771619923413,0.0006676307530142367,0.01901881769299507,-0.22272595763206482,-0.053018394857645035,0.00918014906346798 +1769682104,652516864,0.0,0.0,0.0,1.0,-0.00012732009054161608,0.0011173828970640898,0.018893050029873848,-0.24039527773857117,0.021285122260451317,0.003994396887719631 +1769682104,673559040,0.0,0.0,0.0,1.0,5.94593002460897e-05,0.0014353558653965592,0.018855512142181396,-0.07429296523332596,-0.01752963475883007,0.005437701009213924 +1769682104,702698496,0.0,0.0,0.0,1.0,0.00011233999975956976,0.001731274533085525,0.01886366866528988,-0.03910404443740845,-0.16597706079483032,0.0062569743022322655 +1769682104,759770624,0.0,0.0,0.0,1.0,0.00020801625214517117,0.0019424117635935545,0.018900619819760323,-0.1484675109386444,-0.03513283282518387,-0.003444117261096835 +1769682104,769932288,0.0,0.0,0.0,1.0,7.73539359215647e-05,0.0019514246378093958,0.018911616876721382,-0.13112479448318481,-0.10909143835306168,0.008879927918314934 +1769682104,804606976,0.0,0.0,0.0,1.0,-4.379521124064922e-05,0.0019469254184514284,0.018887368962168694,-0.1484510749578476,-0.03505456820130348,-0.008228526450693607 +1769682104,847590656,0.0,0.0,0.0,1.0,0.0001058397174347192,0.0019412675173953176,0.01887519471347332,-0.14861705899238586,-0.034717101603746414,0.0036780729424208403 +1769682104,870859008,0.0,0.0,0.0,1.0,8.504019933752716e-05,0.0018845419399440289,0.018885862082242966,-0.03946991637349129,-0.16612112522125244,-0.00805449765175581 +1769682104,902948864,0.0,0.0,0.0,1.0,6.008826312609017e-05,0.00174516171682626,0.018921080976724625,0.017304643988609314,-0.07428813725709915,0.0016112643061205745 +1769682104,947758336,0.0,0.0,0.0,1.0,0.0001031727297231555,0.0017324951477348804,0.018954148516058922,-0.017276616767048836,0.07434636354446411,0.000771065300796181 +1769682104,970097408,0.0,0.0,0.0,1.0,-2.5031680706888437e-05,0.0016444058855995536,0.01897321455180645,-0.1142626479268074,-0.1830185502767563,0.004487138241529465 +1769682105,13348864,0.0,0.0,0.0,1.0,-0.00018967059440910816,0.0016609864542260766,0.01896183378994465,-0.05725490301847458,-0.09136384725570679,0.008199363946914673 +1769682105,53391872,0.0,0.0,0.0,1.0,-0.00016142372624017298,0.0016027404926717281,0.01889631897211075,-0.09158188849687576,0.057414788752794266,0.008541413582861423 +1769682105,70637312,0.0,0.0,0.0,1.0,-0.0003316428337711841,0.0016555533511564136,0.018835704773664474,-0.16581878066062927,0.04025082290172577,0.0008128900080919266 +1769682105,106058240,0.0,0.0,0.0,1.0,-0.000234471372095868,0.001555370050482452,0.01879281923174858,0.017124546691775322,-0.07453691959381104,-0.007919689640402794 +1769682105,161062400,0.0,0.0,0.0,1.0,-0.00031930781551636755,0.0015231024008244276,0.01884295605123043,-0.0913156196475029,0.05733851343393326,-0.004580938257277012 +1769682105,169818368,0.0,0.0,0.0,1.0,-0.00014242947509046644,0.0015679672360420227,0.018957631662487984,0.017026353627443314,-0.07453358173370361,-0.006727172993123531 +1769682105,204499968,0.0,0.0,0.0,1.0,-4.92232502438128e-05,0.001577490591444075,0.019119376316666603,-0.11495693773031235,-0.18267831206321716,-0.0039058863185346127 +1769682105,249187584,0.0,0.0,0.0,1.0,-0.00013610991300083697,0.001641461276449263,0.019330017268657684,-0.07442450523376465,-0.01681758090853691,0.0005974335363134742 +1769682105,270365952,0.0,0.0,0.0,1.0,-0.00018844781152438372,0.0015990855172276497,0.019452549517154694,-0.07447835057973862,-0.016706451773643494,0.004169154912233353 +1769682105,303841792,0.0,0.0,0.0,1.0,-0.00020988546020817012,0.0013756301486864686,0.0195331908762455,-0.0579567551612854,-0.09076431393623352,0.022468512877821922 +1769682105,348713216,0.0,0.0,0.0,1.0,-0.00033802964026108384,0.0008267254452221096,0.019595202058553696,-0.04130521044135094,-0.16521775722503662,0.020508240908384323 +1769682105,369217792,0.0,0.0,0.0,1.0,-0.0001571561151649803,0.0005718843312934041,0.019625224173069,-0.0413290411233902,-0.16530653834342957,0.014547677710652351 +1769682105,412862976,0.0,0.0,0.0,1.0,-8.834288746584207e-05,0.000325061846524477,0.01966222934424877,-0.0746539756655693,-0.01631336286664009,0.0148860989138484 +1769682105,449200128,0.0,0.0,0.0,1.0,-0.00014307250967249274,0.00019426006474532187,0.019685527309775352,-0.05794224515557289,-0.09101221710443497,0.0010096416808664799 +1769682105,470651904,0.0,0.0,0.0,1.0,-0.00013729681086260825,0.0001990191376535222,0.019674966111779213,-0.13243664801120758,-0.10755051672458649,-0.0031749363988637924 +1769682105,502749952,0.0,0.0,0.0,1.0,-0.00026390812126919627,0.0002372295130044222,0.019616415724158287,-0.14882704615592957,-0.03317034989595413,-0.014327825978398323 +1769682105,561292032,0.0,0.0,0.0,1.0,-0.00045062621938996017,0.00033912539947777987,0.01947522535920143,0.123815156519413,-0.20731116831302643,-0.006459463387727737 +1769682105,567624960,0.0,0.0,0.0,1.0,-0.00034618371864780784,0.00035353351267986,0.01932777278125286,-0.07445799559354782,-0.016449671238660812,-0.005378331057727337 +1769682105,602821632,0.0,0.0,0.0,1.0,-0.0005491557531058788,0.0004011924029327929,0.019144820049405098,-0.041881125420331955,-0.1654137670993805,-0.0009587829699739814 +1769682105,646236672,0.0,0.0,0.0,1.0,-0.0002630396338645369,0.000826615490950644,0.01891755498945713,-0.13293690979480743,-0.10688836127519608,0.0087272422388196 +1769682105,670216704,0.0,0.0,0.0,1.0,-0.0003111212281510234,0.0011256460566073656,0.018749302253127098,-0.11664796620607376,-0.1815757006406784,-0.0015820303233340383 +1769682105,705506304,0.0,0.0,0.0,1.0,-0.00018229290435556322,0.0012874045642092824,0.018605265766382217,-0.13295386731624603,-0.10689713060855865,0.0003744709538295865 +1769682105,746653952,0.0,0.0,0.0,1.0,-8.938171959016472e-05,0.0014053734485059977,0.01844765804708004,-0.042463518679142,-0.16507722437381744,0.01094815880060196 +1769682105,769599744,0.0,0.0,0.0,1.0,-1.6814592527225614e-05,0.0014575745444744825,0.018360618501901627,0.09058152139186859,-0.05839632824063301,0.007010033819824457 +1769682105,802771712,0.0,0.0,0.0,1.0,0.00014995475066825747,0.0014911963371559978,0.01828005723655224,0.015962660312652588,-0.07448458671569824,0.0063837626948952675 +1769682105,849304320,0.0,0.0,0.0,1.0,-1.3573735486716032e-05,0.001440286636352539,0.0181584432721138,0.03213090822100639,-0.14946778118610382,-0.012257524766027927 +1769682105,869433856,0.0,0.0,0.0,1.0,-0.00011024158447980881,0.0013851557159796357,0.01805211417376995,0.10650672763586044,-0.13331498205661774,0.0002996019320562482 +1769682105,914866944,0.0,0.0,0.0,1.0,-6.533932173624635e-05,0.0013042273931205273,0.017927659675478935,6.0257352743064985e-05,-9.063203469850123e-05,-0.004767132457345724 +1769682105,947247872,0.0,0.0,0.0,1.0,-3.593780274968594e-05,0.0012225210666656494,0.017749298363924026,-0.16498132050037384,0.04275597259402275,-0.011251398362219334 +1769682105,971843840,0.0,0.0,0.0,1.0,-0.00016979048086795956,0.0011652277316898108,0.017609670758247375,-0.14922446012496948,-0.031689587980508804,-0.004869923461228609 +1769682106,2777344,0.0,0.0,0.0,1.0,-0.00020233466057106853,0.0011850164737552404,0.017479322850704193,-0.09039827436208725,0.05886039510369301,-0.00227042892947793 +1769682106,60207360,0.0,0.0,0.0,1.0,-0.00010943086817860603,0.001215631142258644,0.01732645556330681,-0.13352914154529572,-0.10619556903839111,-0.005645117722451687 +1769682106,69422592,0.0,0.0,0.0,1.0,-0.00014843119424767792,0.001185243483632803,0.017231883481144905,-4.572220132104121e-05,6.805097655160353e-05,0.003575341310352087 +1769682106,104868096,0.0,0.0,0.0,1.0,-0.00022946516401134431,0.001262447563931346,0.017173070460557938,-0.04341868683695793,-0.16496063768863678,0.002583990804851055 +1769682106,150258176,0.0,0.0,0.0,1.0,-1.5694822650402784e-06,0.0012988717062398791,0.0171522069722414,-0.05907585844397545,-0.09030640870332718,-0.0014243291225284338 +1769682106,169740800,0.0,0.0,0.0,1.0,-3.0950468499213457e-06,0.0012259959476068616,0.01717931590974331,-0.043554410338401794,-0.16500501334667206,-0.002187400823459029 +1769682106,202873600,0.0,0.0,0.0,1.0,5.616992712020874e-05,0.0011989837512373924,0.017220238223671913,0.04659978672862053,-0.22421640157699585,-0.0034724485594779253 +1769682106,245265408,0.0,0.0,0.0,1.0,-4.195008659735322e-05,0.001223806873895228,0.01727866567671299,0.030922310426831245,-0.14943842589855194,0.0008643744513392448 +1769682106,270486272,0.0,0.0,0.0,1.0,-4.989055742044002e-05,0.0012781053083017468,0.01731071062386036,-0.11857106536626816,-0.18032492697238922,-0.0016765721375122666 +1769682106,311904768,0.0,0.0,0.0,1.0,7.5879215728491545e-06,0.0008951956988312304,0.01733993925154209,0.10532023757696152,-0.13383540511131287,0.014653041958808899 +1769682106,347983616,0.0,0.0,0.0,1.0,-2.2073814761824906e-05,0.0005321514909155667,0.017331348732113838,0.015176648274064064,-0.07451842725276947,0.012351373210549355 +1769682106,369696000,0.0,0.0,0.0,1.0,-3.425701288506389e-05,0.00033041101414710283,0.01729195937514305,-0.22445903718471527,-0.04554183781147003,0.015836266800761223 +1769682106,402778368,0.0,0.0,0.0,1.0,-7.811319665051997e-05,0.00022219862148631364,0.017226271331310272,-7.748889038339257e-05,0.00011380625073798001,0.005958878435194492 +1769682106,448914944,0.0,0.0,0.0,1.0,-8.208284270949662e-05,0.00017670515808276832,0.017131172120571136,0.030281612649559975,-0.14936226606369019,0.01040167361497879 +1769682106,469417216,0.0,0.0,0.0,1.0,3.6607758374884725e-05,3.132905112579465e-05,0.017063351348042488,0.015056062489748001,-0.0746205523610115,0.008776232600212097 +1769682106,502424320,0.0,0.0,0.0,1.0,-5.1083421567454934e-05,0.00010781214223243296,0.016986722126603127,-0.11914481222629547,-0.1800590455532074,-0.01241336204111576 +1769682106,549727232,0.0,0.0,0.0,1.0,5.353655433282256e-05,0.00021389800531324,0.016879037022590637,0.030367793515324593,-0.14991503953933716,-0.015816928818821907 +1769682106,573068032,0.0,0.0,0.0,1.0,8.580973371863365e-07,0.0001594495406607166,0.01678549498319626,0.10494695603847504,-0.13468557596206665,-0.004408428445458412 +1769682106,604084224,0.0,0.0,0.0,1.0,0.003219283651560545,0.0014897756045684218,0.016872840002179146,-0.27102968096733093,0.18183240294456482,0.1217760518193245 +1769682106,645006592,0.0,0.0,0.0,1.0,0.012196238152682781,0.007708865217864513,0.017503727227449417,-0.241018146276474,0.03239717334508896,0.12139157950878143 +1769682106,669896960,0.0,0.0,0.0,1.0,0.015395976603031158,0.011119091883301735,0.01780998706817627,-0.15102049708366394,-0.027771450579166412,0.10106942057609558 +1769682106,703817472,0.0,0.0,0.0,1.0,0.018374664708971977,0.013789528980851173,0.018073871731758118,-0.015671098604798317,0.07605063170194626,0.05782918632030487 +1769682106,748605440,0.0,0.0,0.0,1.0,0.02019135281443596,0.014783648774027824,0.0182258989661932,0.059663478285074234,0.09019958972930908,0.025172647088766098 +1769682106,769529856,0.0,0.0,0.0,1.0,0.021407565101981163,0.014886632561683655,0.018394973129034042,-0.029527166858315468,0.14969328045845032,-0.002531293546780944 +1769682106,803337728,0.0,0.0,0.0,1.0,0.022349007427692413,0.014564194716513157,0.01858539693057537,0.014911952428519726,-0.07513405382633209,-0.011190745048224926 +1769682106,851530496,0.0,0.0,0.0,1.0,0.022807789966464043,0.013831655494868755,0.01885331980884075,-0.04532724246382713,-0.16471616923809052,-0.011151270940899849 +1769682106,869327872,0.0,0.0,0.0,1.0,0.022941483184695244,0.013258185237646103,0.019031284376978874,-0.06004806235432625,-0.08980950713157654,-0.011915627866983414 +1769682106,903960064,0.0,0.0,0.0,1.0,0.022748464718461037,0.012745499610900879,0.019148724153637886,-0.04532996937632561,-0.1649409383535385,-0.021685225889086723 +1769682106,946305280,0.0,0.0,0.0,1.0,0.022026855498552322,0.012246795929968357,0.01919645443558693,-0.045527148991823196,-0.16480228304862976,-0.016794444993138313 +1769682111,449709824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682111,469859328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682111,508509440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682111,551401216,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682111,570179072,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682111,603246080,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682111,654025728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682111,675126784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682111,708136448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682111,749525504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682111,780176896,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682111,804022784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682111,850981120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682111,870001152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682111,905479168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682111,946494464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,2.983749618579168e-05,-2.9077438739477657e-05,-0.0011913662310689688 +1769682111,970120448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682112,3381760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682112,54460672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-2.9837494366802275e-05,2.9077393264742568e-05,0.0011913662310689688 +1769682112,69864960,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682112,103148032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682112,149174528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,2.9837490728823468e-05,-2.9077349608996883e-05,-0.0011913662310689688 +1769682112,174360064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,2.9837490728823468e-05,-2.9077331419102848e-05,-0.0011913662310689688 +1769682112,204487168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,2.9837490728823468e-05,-2.9077318686177023e-05,-0.0011913662310689688 +1769682112,248769536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682112,270050816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682112,306575872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682112,352612608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682112,372456192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,2.983748709084466e-05,-2.9077249564579688e-05,-0.0011913662310689688 +1769682112,405257984,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,2.983748709084466e-05,-2.9077231374685653e-05,-0.0011913662310689688 +1769682112,447825664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.967497418168932e-05,-5.815443000756204e-05,-0.0023827324621379375 +1769682112,473217792,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.967497418168932e-05,5.8154400903731585e-05,0.0023827324621379375 +1769682112,505187584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.9674970543710515e-05,5.8154360885964707e-05,0.0023827324621379375 +1769682112,562941440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-2.9837483452865854e-05,2.907716407207772e-05,0.0011913662310689688 +1769682112,571296256,0.0,0.0,0.0,1.0,-0.008756635710597038,-0.05442739278078079,-0.00033104082103818655,2.2332217693328857,-0.10502099990844727,0.9607414603233337 +1769682112,604107776,0.0,0.0,0.0,1.0,-0.010440201498568058,-0.1138630136847496,-0.0008013287442736328,0.19377656280994415,0.19650958478450775,0.5001848936080933 +1769682112,646923520,0.0,0.0,0.0,1.0,-0.008604364469647408,-0.12436666339635849,-0.0009981729090213776,-0.5765535831451416,0.2281189262866974,0.19729392230510712 +1769682112,670377984,0.0,0.0,0.0,1.0,-0.006303846836090088,-0.11558905243873596,-0.0011187746422365308,-1.2743514776229858,0.2723561227321625,-0.04449739307165146 +1769682112,707104512,0.0,0.0,0.0,1.0,-0.003186236135661602,-0.08750796318054199,-0.0012216190807521343,-1.4764554500579834,0.08262033015489578,-0.25626876950263977 +1769682112,747721984,0.0,0.0,0.0,1.0,-0.0011786373797804117,-0.06250698864459991,-0.0012880105059593916,-1.7894163131713867,0.11087051779031754,-0.35017213225364685 +1769682112,770484480,0.0,0.0,0.0,1.0,0.00043194316094741225,-0.03858155384659767,-0.0013551611918956041,-1.616320013999939,-0.01835893839597702,-0.37711164355278015 +1769682112,804416512,0.0,0.0,0.0,1.0,0.0018632762366905808,-0.013277989812195301,-0.0014509354950860143,-1.261987566947937,0.1893768608570099,-0.34781503677368164 +1769682112,864302848,0.0,0.0,0.0,1.0,0.0026447258424013853,2.2794236429035664e-05,-0.0015078383730724454,-1.1755824089050293,0.12638403475284576,-0.2909657061100006 +1769682112,870610432,0.0,0.0,0.0,1.0,0.003066743491217494,0.008011781610548496,-0.001540872734040022,-1.0025458335876465,2.7354806661605835e-05,-0.1979741007089615 +1769682112,904457216,0.0,0.0,0.0,1.0,0.0030754904728382826,0.012206636369228363,-0.0015265223337337375,-0.7765618562698364,0.03587935492396355,-0.10626551508903503 +1769682112,950263552,0.0,0.0,0.0,1.0,0.0027150746900588274,0.011547456495463848,-0.0014778440818190575,-0.7014042139053345,0.04850265011191368,-0.04680192470550537 +1769682112,982112000,0.0,0.0,0.0,1.0,0.0023725503124296665,0.007500298786908388,-0.0013226439477875829,-0.7772985696792603,0.038992851972579956,0.02902258187532425 +1769682113,6509824,0.0,0.0,0.0,1.0,0.0019825263880193233,0.004497101996093988,-0.0011310992995277047,-0.9170626997947693,-0.05859020724892616,0.04823434725403786 +1769682113,47849216,0.0,0.0,0.0,1.0,0.001525992644019425,0.0014727015513926744,-0.0008951441268436611,-0.7775151133537292,0.03973688557744026,0.06220020353794098 +1769682113,71254016,0.0,0.0,0.0,1.0,0.0014730809489265084,-0.001209791051223874,-0.0005903224227949977,-0.690791666507721,-0.024434087797999382,0.06426986306905746 +1769682113,104519936,0.0,0.0,0.0,1.0,0.0009096930152736604,-0.004018938168883324,-0.0001330378872808069,-0.7887658476829529,0.11509320139884949,0.058050282299518585 +1769682113,152767744,0.0,0.0,0.0,1.0,0.0007562153623439372,-0.005982476752251387,0.0002483410353306681,-0.9622456431388855,0.24358384311199188,0.0612325482070446 +1769682113,170823936,0.0,0.0,0.0,1.0,0.0005552286165766418,-0.007464288733899593,0.0006806137389503419,-1.1546080112457275,-0.017298031598329544,0.03436735272407532 +1769682113,203958272,0.0,0.0,0.0,1.0,0.0003801132261287421,-0.007489364128559828,0.0013304268941283226,-1.1656707525253296,0.05733411759138107,-0.0028973519802093506 +1769682113,248002560,0.0,0.0,0.0,1.0,0.0005082341376692057,-0.006809843238443136,0.0018484118627384305,-1.2298511266708374,-0.029368892312049866,-0.003296228125691414 +1769682113,270798080,0.0,0.0,0.0,1.0,0.00034428268554620445,-0.006349155213683844,0.0023673686664551497,-1.0788484811782837,-0.007217776030302048,-0.021911069750785828 +1769682113,305039360,0.0,0.0,0.0,1.0,0.0003829917695838958,-0.005894998088479042,0.0031103924848139286,-1.2522660493850708,0.12126938998699188,-0.02554337866604328 +1769682113,348742400,0.0,0.0,0.0,1.0,0.0005439626984298229,-0.005180161911994219,0.0036850569304078817,-1.2409887313842773,0.0457899272441864,-0.030635740607976913 +1769682113,373098240,0.0,0.0,0.0,1.0,0.0003279372467659414,-0.003939079120755196,0.00424330634996295,-1.16548752784729,0.05700822174549103,-0.03755638748407364 +1769682113,405221888,0.0,0.0,0.0,1.0,0.00040835875552147627,-0.0022814269177615643,0.004970568232238293,-1.176705241203308,0.1326972246170044,-0.038088180124759674 +1769682113,451331584,0.0,0.0,0.0,1.0,0.00039952911902219057,-0.0016839231830090284,0.00550071382895112,-1.2409805059432983,0.04642953723669052,-0.027880322188138962 +1769682113,488581120,0.0,0.0,0.0,1.0,0.00026849331334233284,-0.000556869141291827,0.006169617176055908,-1.2184419631958008,-0.10502687096595764,-0.05984897166490555 +1769682113,514458624,0.0,0.0,0.0,1.0,0.0005415456253103912,0.0025227246806025505,0.006623353809118271,-1.0899181365966797,0.06874998658895493,-0.05159967020153999 +1769682113,547360000,0.0,0.0,0.0,1.0,0.0004558165674097836,0.005220918916165829,0.007158774882555008,-1.078742504119873,-0.006370164453983307,-0.04872671514749527 +1769682113,570248704,0.0,0.0,0.0,1.0,0.0006507523357868195,0.006605137139558792,0.0074050286784768105,-1.0676385164260864,-0.0814361721277237,-0.037464652210474014 +1769682113,604768768,0.0,0.0,0.0,1.0,0.0006926907226443291,0.008229875937104225,0.00786144845187664,-1.078816294670105,-0.005422867834568024,-0.030126428231596947 +1769682113,652306944,0.0,0.0,0.0,1.0,0.0007068632985465229,0.008696937002241611,0.008176272734999657,-0.8525051474571228,0.028814569115638733,-0.0026431092992424965 +1769682113,672175360,0.0,0.0,0.0,1.0,0.0007244219304993749,0.006125698797404766,0.008462567813694477,-0.8304826021194458,-0.12123395502567291,0.028333522379398346 +1769682113,704716032,0.0,0.0,0.0,1.0,-6.1871025536675e-05,0.0012775277718901634,0.008630020543932915,-0.8951423764228821,-0.20666968822479248,0.06333865970373154 +1769682113,753002496,0.0,0.0,0.0,1.0,-0.00019972931477241218,-0.0015096802962943912,0.008732493966817856,-0.8416506052017212,-0.04500482231378555,0.03709492087364197 +1769682113,777543424,0.0,0.0,0.0,1.0,-0.00026444814284332097,-0.0034488365054130554,0.0090553043410182,-1.003558874130249,0.008279344066977501,0.01598145253956318 +1769682113,803730176,0.0,0.0,0.0,1.0,-0.00020399277855176479,-0.00391129357740283,0.009440524503588676,-0.9389822483062744,0.09474072605371475,0.002427038736641407 +1769682113,851859200,0.0,0.0,0.0,1.0,-0.00018040860595647246,-0.003918955102562904,0.009888929314911366,-1.143473744392395,-0.08911358565092087,-0.004783225245773792 +1769682113,870750976,0.0,0.0,0.0,1.0,-0.00023709688684903085,-0.0038019255734980106,0.01033351756632328,-1.154420018196106,-0.013396922498941422,-0.011290905997157097 +1769682113,906595584,0.0,0.0,0.0,1.0,-0.00018280129006598145,-0.002987178973853588,0.010850469581782818,-1.0788614749908447,-0.0022759325802326202,-0.02295718342065811 +1769682113,953292288,0.0,0.0,0.0,1.0,-0.00043587241088971496,-0.002194735687226057,0.01114463061094284,-1.0033735036849976,0.009087398648262024,-0.018021367490291595 +1769682113,972210688,0.0,0.0,0.0,1.0,-0.0006044640322215855,-0.0016185807762667537,0.011295498348772526,-0.9278221726417542,0.02011951059103012,-0.025030385702848434 +1769682114,4076544,0.0,0.0,0.0,1.0,-0.0008405338739976287,-0.0010068155825138092,0.01130841113626957,-1.1760673522949219,0.13924789428710938,-0.020617926493287086 +1769682114,50973440,0.0,0.0,0.0,1.0,-0.000985883641988039,-0.0008709852118045092,0.011212161742150784,-1.0788898468017578,-0.0005848556756973267,-0.01797247864305973 +1769682114,72513792,0.0,0.0,0.0,1.0,-0.0011895759962499142,-0.0006640600040555,0.01100749708712101,-1.0681260824203491,-0.0756746232509613,-0.013707038946449757 +1769682114,104222976,0.0,0.0,0.0,1.0,-0.00136198615655303,-0.00040551667916588485,0.01056827511638403,-0.9926573038101196,-0.06429621577262878,-0.0064580561593174934 +1769682114,147123456,0.0,0.0,0.0,1.0,-0.0011411829618737102,-0.00021350366296246648,0.010211644694209099,-1.057436227798462,-0.150540292263031,-0.01778961345553398 +1769682114,174780416,0.0,0.0,0.0,1.0,-0.0020826533436775208,0.0004208386526443064,0.009720353409647942,-1.1543623208999634,-0.010060064494609833,-0.03349597752094269 +1769682114,205815552,0.0,0.0,0.0,1.0,-0.002006705617532134,0.0005229084054008126,0.009307158179581165,-1.089573621749878,0.07691709697246552,-0.016205983236432076 +1769682114,247209984,0.0,0.0,0.0,1.0,-0.0021509819198399782,0.0007354918052442372,0.008893653750419617,-0.9277533292770386,0.0226827971637249,-0.027328111231327057 +1769682114,283211264,0.0,0.0,0.0,1.0,-0.001969744451344013,0.0009701162343844771,0.008476347662508488,-1.0682655572891235,-0.07361625134944916,-0.014966216869652271 +1769682114,303800832,0.0,0.0,0.0,1.0,-0.0019314332166686654,0.001498327823355794,0.007952687330543995,-0.9384863972663879,0.09951820969581604,0.0029510613530874252 +1769682114,347444480,0.0,0.0,0.0,1.0,-0.0019033981952816248,0.001619603019207716,0.0075786663219332695,-0.9927505850791931,-0.062485966831445694,-0.017372053116559982 +1769682114,370785280,0.0,0.0,0.0,1.0,-0.0018471749499440193,0.0014517726376652718,0.0072274357080459595,-1.0350875854492188,0.24018870294094086,-0.011592024937272072 +1769682114,404231168,0.0,0.0,0.0,1.0,-0.001843802398070693,0.0013989299768581986,0.006778267677873373,-1.0139189958572388,0.08937019109725952,-0.009195797145366669 +1769682114,447459072,0.0,0.0,0.0,1.0,-0.001653551124036312,0.0013732712250202894,0.006452443078160286,-1.100018858909607,0.15468472242355347,-0.006388690322637558 +1769682114,471385088,0.0,0.0,0.0,1.0,-0.0016005747020244598,0.0013017901219427586,0.006144177634268999,-0.8417230844497681,-0.04025077819824219,-0.004236745648086071 +1769682114,504058112,0.0,0.0,0.0,1.0,-0.0015892600640654564,0.0012287836289033294,0.005833358038216829,-0.9823374152183533,-0.13674797117710114,-0.008669666945934296 +1769682114,572354560,0.0,0.0,0.0,1.0,-0.0014149637427181005,0.0012549509992823005,0.00570776779204607,-0.9383174777030945,0.10086357593536377,-0.0008864719420671463 +1769682114,581586944,0.0,0.0,0.0,1.0,-0.001412504119798541,0.0012982365442439914,0.005668616387993097,-0.9068373441696167,-0.12579606473445892,-0.005069689825177193 +1769682114,604965888,0.0,0.0,0.0,1.0,-0.0013443994102999568,0.0012702369131147861,0.005679359659552574,-0.9487113356590271,0.17667898535728455,-0.007522165309637785 +1769682114,649168128,0.0,0.0,0.0,1.0,-0.0015773444902151823,0.0015223956434056163,0.005670751444995403,-0.9277685284614563,0.025622189044952393,-0.008739357814192772 +1769682114,672048384,0.0,0.0,0.0,1.0,-0.0016471415292471647,0.0013362080790102482,0.005606339778751135,-1.1545230150222778,-0.005452744662761688,-0.005608053877949715 +1769682114,709130496,0.0,0.0,0.0,1.0,-0.0021270758006721735,0.0011951399501413107,0.005378628149628639,-0.9277636408805847,0.026010815054178238,-0.00762971630319953 +1769682114,753484544,0.0,0.0,0.0,1.0,-0.00227620592340827,0.001132627367042005,0.005085268057882786,-0.9929847121238708,-0.059595998376607895,0.003511001355946064 +1769682114,771805184,0.0,0.0,0.0,1.0,-0.0023506819270551205,0.0012589737307280302,0.004702891688793898,-0.938111424446106,0.1016930639743805,-0.016615640372037888 +1769682114,804791296,0.0,0.0,0.0,1.0,-0.0025888497475534678,0.0014526081504300237,0.004131197929382324,-0.917334794998169,-0.04927342012524605,-0.013121351599693298 +1769682114,848450304,0.0,0.0,0.0,1.0,-0.0013390871463343501,0.0019761158619076014,0.003966957796365023,-0.9485538005828857,0.1779928058385849,0.0017973072826862335 +1769682114,871776256,0.0,0.0,0.0,1.0,-0.001082899048924446,0.0023965518921613693,0.0037197135388851166,-1.099680781364441,0.1572587490081787,-0.0033523254096508026 +1769682114,905649920,0.0,0.0,0.0,1.0,-0.0005937471869401634,0.0028576997574418783,0.0033320703078061342,-0.9381141662597656,0.10247665643692017,-0.004938846454024315 +1769682114,947606528,0.0,0.0,0.0,1.0,-0.00021757170907221735,0.0030636233277618885,0.0029982631094753742,-1.0137121677398682,0.09229515492916107,-0.0016235224902629852 +1769682114,978339072,0.0,0.0,0.0,1.0,-0.00011270827963016927,0.0032284960616379976,0.0025764754973351955,-0.8418336510658264,-0.038132354617118835,-0.0014306660741567612 +1769682115,3894016,0.0,0.0,0.0,1.0,0.00034264629357494414,0.0032125527504831553,0.002331797732040286,-1.0239568948745728,0.16778415441513062,-0.015531817451119423 +1769682115,47395584,0.0,0.0,0.0,1.0,0.0005144425085745752,0.003275769529864192,0.002173034939914942,-0.9173955321311951,-0.0484810397028923,-0.007753761950880289 +1769682115,71294976,0.0,0.0,0.0,1.0,0.0005525083979591727,0.0032494403421878815,0.002092345617711544,-0.992954671382904,-0.05888381972908974,-0.014009729959070683 +1769682115,106278656,0.0,0.0,0.0,1.0,0.0008211211534217,0.0031408616341650486,0.00208178604952991,-0.9277058839797974,0.02719932422041893,-0.010920891538262367 +1769682115,145619456,0.0,0.0,0.0,1.0,0.0007929514395073056,0.0031769853085279465,0.00208358746021986,-0.7765746712684631,0.048103440552949905,-0.001026681624352932 +1769682115,173099520,0.0,0.0,0.0,1.0,0.0006998160970397294,0.0030853115022182465,0.0020485329441726208,-0.9380102157592773,0.10291561484336853,-0.011682911776006222 +1769682115,205480448,0.0,0.0,0.0,1.0,0.00041607936145737767,0.0030811119358986616,0.001922936411574483,-0.7662340402603149,-0.027497487142682076,-0.005375559441745281 +1769682115,252967168,0.0,0.0,0.0,1.0,-0.0005291402922011912,0.002839360386133194,0.0014719297178089619,-0.7663494944572449,-0.027039673179388046,0.01241071056574583 +1769682115,270200320,0.0,0.0,0.0,1.0,-0.0009940682211890817,0.0028455976862460375,0.001159628271125257,-0.7766243815422058,0.04850105941295624,0.00820353627204895 +1769682115,305437696,0.0,0.0,0.0,1.0,-0.002091968199238181,0.0027583250775933266,0.0005659890011884272,-0.7868008613586426,0.12372400611639023,-0.01034012995660305 +1769682115,364009472,0.0,0.0,0.0,1.0,-0.0024146626237779856,0.002759586786851287,0.00017592096992302686,-0.8418318033218384,-0.03768625855445862,-0.00593214388936758 +1769682115,372604160,0.0,0.0,0.0,1.0,-0.0027307718992233276,0.002823786111548543,-0.00016268111357931048,-0.8417587876319885,-0.037931010127067566,-0.016731085255742073 +1769682115,405048320,0.0,0.0,0.0,1.0,-0.0029536853544414043,0.0028082840144634247,-0.0005484676803462207,-0.852123498916626,0.03781706094741821,-0.010246271267533302 +1769682115,448686848,0.0,0.0,0.0,1.0,-0.002922074170783162,0.002855188213288784,-0.0007624244317412376,-0.7867842316627502,0.12365099042654037,-0.012965967878699303 +1769682115,470414848,0.0,0.0,0.0,1.0,-0.0031931016128510237,0.002848555101081729,-0.0009313028422184289,-0.8624231219291687,0.11346417665481567,-0.00736471451818943 +1769682115,504791040,0.0,0.0,0.0,1.0,-0.003009331878274679,0.0028509481344372034,-0.001101791043765843,-0.9276948571205139,0.02744523622095585,-0.010788153856992722 +1769682115,550242304,0.0,0.0,0.0,1.0,-0.0030894610099494457,0.002935383003205061,-0.0012077587889507413,-0.6905827522277832,-0.017352156341075897,-0.012943504378199577 +1769682115,572747520,0.0,0.0,0.0,1.0,-0.003090248443186283,0.0030103556346148252,-0.001323872827924788,-0.85210120677948,0.037686873227357864,-0.010618963278830051 +1769682115,605699840,0.0,0.0,0.0,1.0,-0.003033472690731287,0.003130305092781782,-0.0014982471475377679,-0.700863242149353,0.05811136215925217,-0.017196066677570343 +1769682115,654148352,0.0,0.0,0.0,1.0,-0.0030748313292860985,0.0033324547111988068,-0.0016872460255399346,-0.8417872190475464,-0.03801539167761803,-0.010306555777788162 +1769682115,670815488,0.0,0.0,0.0,1.0,-0.0031068562529981136,0.0033851575572043657,-0.0017861940432339907,-0.8623766899108887,0.11302851140499115,-0.017354527488350868 +1769682115,705445888,0.0,0.0,0.0,1.0,-0.002941335318610072,0.0027068976778537035,-0.0018884333549067378,-0.6903862953186035,-0.018042394891381264,-0.037158407270908356 +1769682115,763251456,0.0,0.0,0.0,1.0,-0.002601107582449913,0.0016435673460364342,-0.0019365663174539804,-0.8313288688659668,-0.11408346891403198,-0.025521170347929 +1769682115,772144384,0.0,0.0,0.0,1.0,-0.002558167790994048,0.000949937617406249,-0.001981850480660796,-0.7557687759399414,-0.10369516164064407,-0.02041839063167572 +1769682115,804379904,0.0,0.0,0.0,1.0,-0.0024093491956591606,0.00041727288044057786,-0.0020111631602048874,-0.7662582993507385,-0.027726804837584496,-0.0006750719621777534 +1769682115,846705408,0.0,0.0,0.0,1.0,-0.002476109191775322,0.000259527878370136,-0.0020239471923559904,-0.7009550929069519,0.05801799148321152,-0.007940842770040035 +1769682115,870438400,0.0,0.0,0.0,1.0,-0.0024025554303079844,0.00018233756418339908,-0.0020109510514885187,-0.7009679675102234,0.05800122767686844,-0.006749838590621948 +1769682115,904325376,0.0,0.0,0.0,1.0,-0.0005434898193925619,-0.0004889550036750734,-0.0019922470673918724,-0.7219908237457275,0.209962397813797,0.031637463718652725 +1769682115,948111872,0.0,0.0,0.0,1.0,-4.346996865933761e-05,-0.00107296509668231,-0.0019744245801120996,-0.7871929407119751,0.1238643005490303,0.026988031342625618 +1769682115,970185984,0.0,0.0,0.0,1.0,0.0002791541046462953,-0.0015818156534805894,-0.001990126445889473,-0.604938268661499,-0.08223851770162582,0.02918921783566475 +1769682116,7227648,0.0,0.0,0.0,1.0,0.00036120967706665397,-0.0018846626626327634,-0.0020997643005102873,-0.4743594527244568,0.08926571905612946,0.011145258322358131 +1769682116,49059328,0.0,0.0,0.0,1.0,0.00029874773463234305,-0.0019889934919774532,-0.0022216360084712505,-0.6151407361030579,-0.007159128785133362,0.008535943925380707 +1769682116,71005184,0.0,0.0,0.0,1.0,0.0004899850464425981,-0.0018683529924601316,-0.002365706954151392,-0.787002444267273,0.12304701656103134,-0.0014370987191796303 +1769682116,105738752,0.0,0.0,0.0,1.0,0.0005965591408312321,-0.0017442182870581746,-0.002550962381064892,-0.6905137896537781,-0.018227003514766693,-0.01914738491177559 +1769682116,150385920,0.0,0.0,0.0,1.0,0.000708782288711518,-0.001678762724623084,-0.0026650328654795885,-0.6253783106803894,0.06785337626934052,-0.012088279239833355 +1769682116,171870208,0.0,0.0,0.0,1.0,0.0007713472004979849,-0.0016615730710327625,-0.002725261962041259,-0.5602203607559204,0.15384255349636078,-0.009807365015149117 +1769682116,204529664,0.0,0.0,0.0,1.0,0.0010629052994772792,-0.0015032280934974551,-0.0027094935066998005,-0.7009811997413635,0.05735050141811371,-0.011170633137226105 +1769682116,250508800,0.0,0.0,0.0,1.0,0.0009280357626266778,-0.0014088659081608057,-0.00264408509247005,-0.776468813419342,0.04660261049866676,-0.024589113891124725 +1769682116,277114368,0.0,0.0,0.0,1.0,0.000776846194639802,-0.001442277804017067,-0.00258169905282557,-0.6046416163444519,-0.08332856744527817,-0.0002730637788772583 +1769682116,304531712,0.0,0.0,0.0,1.0,0.00038552930345758796,-0.0016216064104810357,-0.0025566238909959793,-0.5499038696289062,0.07819975912570953,-0.002074982039630413 +1769682116,349139456,0.0,0.0,0.0,1.0,0.00040160774369724095,-0.0016260978300124407,-0.002538006752729416,-0.529035210609436,-0.07303774356842041,-0.002271566540002823 +1769682116,370594816,0.0,0.0,0.0,1.0,0.0002212958934251219,-0.0017215600237250328,-0.0025421075988560915,-0.5602694749832153,0.15344756841659546,-0.014422924257814884 +1769682116,405300736,0.0,0.0,0.0,1.0,-3.791986819123849e-05,-0.0017129727639257908,-0.002571520861238241,-0.5394267439842224,0.0023246798664331436,-0.008649604395031929 +1769682116,453164800,0.0,0.0,0.0,1.0,-5.720688568544574e-05,-0.0018465140601620078,-0.002587196184322238,-0.6905918717384338,-0.018573282286524773,-0.006858828477561474 +1769682116,471867904,0.0,0.0,0.0,1.0,-0.00010314775863662362,-0.0017983413999900222,-0.0025871999096125364,-0.6905908584594727,-0.018626878038048744,-0.006820903159677982 +1769682116,503742976,0.0,0.0,0.0,1.0,-7.979471411090344e-05,-0.0018711083102971315,-0.0025244224816560745,-0.690589427947998,-0.018697429448366165,-0.006768973544239998 +1769682116,553402880,0.0,0.0,0.0,1.0,4.236914173816331e-05,-0.0019289195770397782,-0.00245879590511322,-0.4638255834579468,0.012517303228378296,-0.01298903301358223 +1769682116,573033472,0.0,0.0,0.0,1.0,0.00012735788186546415,-0.0012156128650531173,-0.002407260239124298,-0.44242537021636963,-0.14006301760673523,-0.07755562663078308 +1769682116,605474816,0.0,0.0,0.0,1.0,0.0006084077758714557,0.0002771357831079513,-0.0023436150513589382,-0.7006966471672058,0.0555511899292469,-0.0619940347969532 +1769682116,647301632,0.0,0.0,0.0,1.0,0.0005017513176426291,0.001096357824280858,-0.0022958579938858747,-0.4531354308128357,-0.0638023242354393,-0.04228692874312401 +1769682116,676742400,0.0,0.0,0.0,1.0,0.0003832340007647872,0.0015821295091882348,-0.0022554912138730288,-0.5393231511116028,0.001639610156416893,-0.024026088416576385 +1769682116,705732608,0.0,0.0,0.0,1.0,0.0006488669896498322,0.001746688736602664,-0.0022295599337667227,-0.4533030390739441,-0.06331828236579895,-0.01611408032476902 +1769682116,754630912,0.0,0.0,0.0,1.0,0.0006018636049702764,0.0018532825633883476,-0.0022040936164557934,-0.3882632851600647,0.0228097066283226,-0.012744998559355736 +1769682116,771280640,0.0,0.0,0.0,1.0,0.00043520511826500297,0.0018188116373494267,-0.0021641745697706938,-0.48489484190940857,0.16354703903198242,-0.00809828843921423 +1769682116,804513024,0.0,0.0,0.0,1.0,0.0006099425372667611,0.0015100378077477217,-0.002083628671243787,-0.398902028799057,0.09867984056472778,0.003399989567697048 +1769682116,849638656,0.0,0.0,0.0,1.0,0.0006819505360908806,0.0013566820416599512,-0.0020102178677916527,-0.474420964717865,0.08797968924045563,-0.004087098874151707 +1769682116,871604224,0.0,0.0,0.0,1.0,0.0006829536287114024,0.0012443724554032087,-0.0019467385718598962,-0.3338603675365448,0.18468108773231506,0.0008042226545512676 +1769682116,903796480,0.0,0.0,0.0,1.0,0.00046237086644396186,-0.00022508067195303738,-0.0018031670479103923,-0.24707092344760895,0.11753004044294357,-0.09611620754003525 +1769682116,951067392,0.0,0.0,0.0,1.0,-0.00018095099949277937,-0.0035282550379633904,-0.0016540817450731993,-0.45281729102134705,-0.06487950682640076,-0.07936681807041168 +1769682116,975905024,0.0,0.0,0.0,1.0,-0.0009726008283905685,-0.006043335422873497,-0.001631205785088241,-0.38797247409820557,0.02172008529305458,-0.055650558322668076 +1769682117,4865280,0.0,0.0,0.0,1.0,-0.0013434849679470062,-0.008161336183547974,-0.0015942109748721123,-0.2264271229505539,-0.03244994208216667,-0.038986120373010635 +1769682117,49024256,0.0,0.0,0.0,1.0,-0.0017195872496813536,-0.008947034366428852,-0.0015507542993873358,-0.31264543533325195,0.032890044152736664,-0.024179745465517044 +1769682117,71148032,0.0,0.0,0.0,1.0,-0.0020032764878124,-0.009190277196466923,-0.00148496450856328,-0.45318472385406494,-0.06392347812652588,-0.030063286423683167 +1769682117,105838080,0.0,0.0,0.0,1.0,-0.002326719928532839,-0.008885638788342476,-0.001441742293536663,-0.4638807475566864,0.012098649516701698,-0.0077244797721505165 +1769682117,147550208,0.0,0.0,0.0,1.0,-0.0024006771855056286,-0.008412894792854786,-0.0013911017449572682,-0.29168930649757385,-0.1177651435136795,0.002047126181423664 +1769682117,173863424,0.0,0.0,0.0,1.0,-0.002545691328123212,-0.007869030348956585,-0.0013279865961521864,-0.3128623962402344,0.03355862945318222,0.010772572830319405 +1769682117,205341696,0.0,0.0,0.0,1.0,-0.002584140282124281,-0.007541297934949398,-0.001306902151554823,-0.1618041694164276,0.054929062724113464,0.023082109168171883 +1769682117,252900352,0.0,0.0,0.0,1.0,-0.0026448164135217667,-0.0072285570204257965,-0.0012918091379106045,-0.4639533758163452,0.012292527593672276,0.005865783896297216 +1769682117,270604032,0.0,0.0,0.0,1.0,-0.002620808780193329,-0.007054002024233341,-0.0012914171675220132,-0.38842228055000305,0.022970810532569885,0.01205262541770935 +1769682117,304871424,0.0,0.0,0.0,1.0,-0.0025281019043177366,-0.006949909962713718,-0.0013003809144720435,-0.36726444959640503,-0.12818151712417603,0.012983407825231552 +1769682117,347797248,0.0,0.0,0.0,1.0,-0.002478760899975896,-0.007007749285548925,-0.0013049835106357932,-0.31282758712768555,0.03333800286054611,0.004018514417111874 +1769682117,370545664,0.0,0.0,0.0,1.0,-0.0025318884290754795,-0.006948282942175865,-0.0012990955729037523,-0.3883287012577057,0.02245411090552807,-0.010315566323697567 +1769682117,405909760,0.0,0.0,0.0,1.0,-0.0013818674487993121,-0.006754438858479261,-0.001110763754695654,-0.37779664993286133,-0.052836619317531586,0.00448073074221611 +1769682117,460466176,0.0,0.0,0.0,1.0,-0.0007840268663130701,-0.006459795404225588,-0.0009587568929418921,-0.30223044753074646,-0.04230763018131256,0.0022124960087239742 +1769682117,470945280,0.0,0.0,0.0,1.0,-0.0005038247327320278,-0.00615433044731617,-0.000851383781991899,-0.4533703029155731,-0.06330396234989166,0.011745920404791832 +1769682117,504361984,0.0,0.0,0.0,1.0,-0.00030323484679684043,-0.00601803045719862,-0.0007654062937945127,-0.312803715467453,0.03311695158481598,-0.003991927485913038 +1769682117,546299904,0.0,0.0,0.0,1.0,-0.0002231268590549007,-0.006028907373547554,-0.0007369288941845298,-0.3883465528488159,0.022418081760406494,-0.008699297904968262 +1769682117,585372416,0.0,0.0,0.0,1.0,-0.00014575249224435538,-0.006135288625955582,-0.0007321082521229982,-0.3339901864528656,0.18413200974464417,-0.00938364490866661 +1769682117,605332224,0.0,0.0,0.0,1.0,6.698224024148658e-05,-0.006299575325101614,-0.0007465161615982652,-0.3022252321243286,-0.042323462665081024,0.0037179943174123764 +1769682117,653357312,0.0,0.0,0.0,1.0,0.00026356737362220883,-0.0054419687949121,-0.0008138053817674518,-0.3231268525123596,0.10601102560758591,-0.13402009010314941 +1769682117,672647936,0.0,0.0,0.0,1.0,-0.00044142166734673083,-0.00182644696906209,-0.0009649053099565208,-0.3018125593662262,-0.0462820827960968,-0.19047163426876068 +1769682117,703911168,0.0,0.0,0.0,1.0,-0.0009852191433310509,0.001789896166883409,-0.0011019345838576555,-0.37744593620300293,-0.05607380345463753,-0.1499030590057373 +1769682117,754540288,0.0,0.0,0.0,1.0,-0.0012872955994680524,0.003581927390769124,-0.0011643536854535341,-0.3881066143512726,0.02008233591914177,-0.1205030232667923 +1769682117,771166208,0.0,0.0,0.0,1.0,-0.0015093769179657102,0.0045459214597940445,-0.001201766892336309,-0.3882095515727997,0.02108425833284855,-0.07049437612295151 +1769682117,805211648,0.0,0.0,0.0,1.0,-0.001996649894863367,0.004902360029518604,-0.00123058061581105,-0.29155802726745605,-0.11828428506851196,-0.012670871801674366 +1769682117,867138816,0.0,0.0,0.0,1.0,-0.001994702499359846,0.00469209486618638,-0.0012386988382786512,-0.12990987300872803,-0.172020822763443,0.017409615218639374 +1769682117,878182400,0.0,0.0,0.0,1.0,-0.0023034107871353626,0.00412358995527029,-0.0012476397678256035,-0.30227237939834595,-0.04201030358672142,0.02381923794746399 +1769682117,906778368,0.0,0.0,0.0,1.0,-0.0023557497188448906,0.0036316232290118933,-0.0012404926819726825,-0.39907875657081604,0.0984942615032196,0.024273648858070374 +1769682117,951342336,0.0,0.0,0.0,1.0,-0.002022751374170184,0.003926364704966545,-0.0012295246124267578,-0.32379594445228577,0.11078383773565292,0.10888255387544632 +1769682117,974122240,0.0,0.0,0.0,1.0,-0.0020832631271332502,0.012083443813025951,-0.00122813880443573,-0.5507749915122986,0.08048976957798004,0.1908564269542694 +1769682118,8905728,0.0,0.0,0.0,1.0,-0.001903104828670621,0.016595618799328804,-0.0012277180794626474,-0.47515711188316345,0.0902937799692154,0.15017332136631012 +1769682118,50814208,0.0,0.0,0.0,1.0,-0.0017270473763346672,0.01945185475051403,-0.0012174609582871199,-0.539969265460968,0.0032553542405366898,0.10840814560651779 +1769682118,75290368,0.0,0.0,0.0,1.0,-0.0014623923925682902,0.02107425220310688,-0.0011987461475655437,-0.23751525580883026,0.04452673718333244,0.04441944509744644 +1769682118,104094720,0.0,0.0,0.0,1.0,-0.0005678021116182208,0.021310675889253616,-0.0011571079958230257,-0.3024246096611023,-0.04180223494768143,0.038364849984645844 +1769682118,169719552,0.0,0.0,0.0,1.0,0.00011540550622157753,0.02048550173640251,-0.0010860126931220293,-0.23731009662151337,0.04369035363197327,0.0023555487859994173 +1769682118,177595392,0.0,0.0,0.0,1.0,0.0005656019202433527,0.019304554909467697,-0.0009674211032688618,-0.14032204449176788,-0.09717892855405807,-0.017017412930727005 +1769682118,204016896,0.0,0.0,0.0,1.0,0.0008152688387781382,0.01836673729121685,-0.0008814825559966266,-0.22642064094543457,-0.032488059252500534,-0.02858210913836956 +1769682118,247042048,0.0,0.0,0.0,1.0,0.0009923537727445364,0.017556894570589066,-0.0007991570746526122,-0.3126015365123749,0.032408494502305984,-0.029511861503124237 +1769682118,274503680,0.0,0.0,0.0,1.0,0.0010784328915178776,0.016981864348053932,-0.0007321656448766589,-0.3338716924190521,0.18346378207206726,-0.032831549644470215 +1769682118,306781952,0.0,0.0,0.0,1.0,0.0010274645173922181,0.016665372997522354,-0.0006787328748032451,-0.29135021567344666,-0.11853107810020447,-0.019555408507585526 +1769682118,348482048,0.0,0.0,0.0,1.0,0.001066908473148942,0.016638806089758873,-0.0006582965725101531,-0.22646239399909973,-0.0323018878698349,-0.018353963270783424 +1769682118,370758912,0.0,0.0,0.0,1.0,0.000972979876678437,0.016711631789803505,-0.0006571453996002674,-0.22656671702861786,-0.032095134258270264,-0.0077402545139193535 +1769682118,406373376,0.0,0.0,0.0,1.0,0.0008484629215672612,0.016929632052779198,-0.0006614639423787594,-0.06481607258319855,-0.08633296191692352,-0.006180891301482916 +1769682118,449083136,0.0,0.0,0.0,1.0,0.0009871628135442734,0.017160896211862564,-0.0006682395469397306,-0.24796144664287567,0.11914288997650146,-0.0017153043299913406 +1769682118,471622912,0.0,0.0,0.0,1.0,0.0007701034191995859,0.01721573993563652,-0.0006730457535013556,-0.1511419713497162,-0.021234016865491867,0.0033244933001697063 +1769682118,504370688,0.0,0.0,0.0,1.0,0.0007464080699719489,0.017481058835983276,-0.0006826191092841327,-0.17236192524433136,0.12970271706581116,-0.006015872582793236 +1769682118,553529856,0.0,0.0,0.0,1.0,0.000734726432710886,0.017447156831622124,-0.0006831996142864227,-0.22676585614681244,-0.03179052099585533,0.008287266828119755 +1769682118,571609344,0.0,0.0,0.0,1.0,0.0006727600703015924,0.017556799575686455,-0.0006736678187735379,-0.08618880063295364,0.06485956162214279,-0.002505357377231121 +1769682118,604399872,0.0,0.0,0.0,1.0,0.0008032267214730382,0.017528381198644638,-0.0006427296902984381,-0.0755561962723732,-0.010647718794643879,0.0002868747105821967 +1769682118,640574464,0.0,0.0,0.0,1.0,0.0006562083726748824,0.013229474425315857,-0.0006007928168401122,0.08013299852609634,-0.056937217712402344,0.39945167303085327 +1769682118,672621312,0.0,0.0,0.0,1.0,0.00019054088625125587,0.007832986302673817,-0.0005314784939400852,0.005519022699445486,-0.06893883645534515,0.33177781105041504 +1769682118,705362432,0.0,0.0,0.0,1.0,4.869904660154134e-05,0.0035115911159664392,-0.0004200562834739685,0.07168885320425034,0.015552985481917858,0.24527709186077118 +1769682118,750159616,0.0,0.0,0.0,1.0,5.7027376897167414e-05,0.0019797738641500473,-0.00033566777710802853,0.0731801763176918,0.013650608249008656,0.14994537830352783 +1769682118,781697792,0.0,0.0,0.0,1.0,4.0133672882802784e-05,-0.0008297843160107732,-0.0003001397126354277,-0.15313014388084412,-0.018760327249765396,0.12793071568012238 +1769682118,805010432,0.0,0.0,0.0,1.0,-0.00011349190754117444,-0.004853064194321632,-0.0003090412064921111,-0.06577906757593155,-0.08506359159946442,0.057905394583940506 +1769682118,851333888,0.0,0.0,0.0,1.0,-8.553273801226169e-05,-0.005997384898364544,-0.0003301073156762868,-0.15090732276439667,-0.021571563556790352,-0.012643172405660152 +1769682118,871002368,0.0,0.0,0.0,1.0,-5.8533249102765694e-05,-0.005819777958095074,-0.0003548101813066751,-0.301599383354187,-0.04343158006668091,-0.03953338414430618 +1769682118,905012992,0.0,0.0,0.0,1.0,0.00018702216038946062,-0.004501326009631157,-0.0003994579310528934,-0.38745975494384766,0.02095858007669449,-0.0647134780883789 +1769682118,954781952,0.0,0.0,0.0,1.0,2.754834531515371e-05,-0.001447221264243126,-0.00047824278590269387,-0.32293057441711426,0.1076127141714096,-0.04277627170085907 +1769682118,970632192,0.0,0.0,0.0,1.0,-3.852925874525681e-05,-9.958157170331106e-05,-0.0005363165982998908,-0.3983614146709442,0.09678388386964798,-0.050845321267843246 +1769682119,5620992,0.0,0.0,0.0,1.0,-3.992030906374566e-05,0.002074547577649355,-0.0006448879721574485,-0.32287850975990295,0.10753032565116882,-0.046365268528461456 +1769682119,63173632,0.0,0.0,0.0,1.0,0.00015119524323381484,0.0032663666643202305,-0.0006979822646826506,-0.21547436714172363,-0.10820350050926208,-0.03211216628551483 +1769682119,71416576,0.0,0.0,0.0,1.0,0.00024543574545532465,0.004777013789862394,-0.0007029575062915683,-0.31213465332984924,0.03189489245414734,-0.0495307557284832 +1769682119,104860416,0.0,0.0,0.0,1.0,0.00026915865601040423,0.007296807132661343,-0.000646169064566493,-0.2258836179971695,-0.03299785405397415,-0.04935761168599129 +1769682119,149005056,0.0,0.0,0.0,1.0,0.0003946376091334969,0.007622517645359039,-0.0006112802075222135,-0.07598616927862167,-0.010119606740772724,0.027622796595096588 +1769682119,170608128,0.0,0.0,0.0,1.0,0.0004282654554117471,0.005588551051914692,-0.0005632757092826068,-0.00026640130090527236,0.0003336310328450054,0.016683897003531456 +1769682119,204672512,0.0,0.0,0.0,1.0,0.0006176606984809041,0.0035541641991585493,-0.00036543127498589456,-0.0864928811788559,0.06518923491239548,0.01518680527806282 +1769682119,250166528,0.0,0.0,0.0,1.0,0.00042908225441351533,0.0025698011741042137,-0.00020760482584591955,-0.00046400484279729426,0.0005727516836486757,0.028600750491023064 +1769682119,270542080,0.0,0.0,0.0,1.0,0.0003549572138581425,0.0021713741589337587,-7.850959082134068e-05,-0.07572797685861588,-0.010456034913659096,0.010900754481554031 +1769682119,306578176,0.0,0.0,0.0,1.0,0.00018883154552895576,0.0018370718462392688,9.05707656784216e-06,-0.14057224988937378,-0.09669995307922363,0.010369982570409775 +1769682119,354455296,0.0,0.0,0.0,1.0,0.00016638838860671967,0.0019196404609829187,1.9289576812298037e-05,0.01059239637106657,-0.07542962580919266,0.006456262432038784 +1769682119,373160704,0.0,0.0,0.0,1.0,-2.075288830383215e-05,0.0020889986772090197,-7.079653187247459e-06,-0.07543543726205826,-0.010814289562404156,-0.006989104673266411 +1769682119,404863232,0.0,0.0,0.0,1.0,-9.13077310542576e-05,0.0025144927203655243,-7.008959073573351e-05,0.02116328291594982,-0.15083537995815277,0.01410695817321539 +1769682119,454989568,0.0,0.0,0.0,1.0,5.046407750342041e-05,0.0027514782268553972,-0.00011588294000830501,-0.06500175595283508,-0.08605314791202545,0.008989482186734676 +1769682119,472393984,0.0,0.0,0.0,1.0,7.077852205839008e-05,0.003065485041588545,-0.00015007476031314582,-0.2265399694442749,-0.03215818107128143,-0.006727094762027264 +1769682119,507426560,0.0,0.0,0.0,1.0,0.000210518017411232,0.003233111696317792,-0.00014017037756275386,-0.23725014925003052,0.04341331496834755,-0.0060668447986245155 +1769682119,547501824,0.0,0.0,0.0,1.0,0.00022710436314810067,0.003302369499579072,-0.00011247352813370526,-0.15086360275745392,-0.02163141593337059,-0.014052139595150948 +1769682119,576439552,0.0,0.0,0.0,1.0,0.00041279220022261143,0.0027300240471959114,-2.0415234757820144e-05,-0.0009577639866620302,0.0011236242717131972,0.056008949875831604 +1769682119,604532224,0.0,0.0,0.0,1.0,0.00031941564520820975,0.0017876920755952597,6.573085556738079e-05,-0.08700129389762878,0.0657612532377243,0.043695006519556046 +1769682119,648817664,0.0,0.0,0.0,1.0,0.00021163544442970306,0.001158007769845426,0.00015604501822963357,-0.07627071440219879,-0.009834866970777512,0.04181574285030365 +1769682119,671294720,0.0,0.0,0.0,1.0,4.773140244651586e-05,0.0006355195655487478,0.0002327204419998452,-0.08677762001752853,0.06549938023090363,0.030580326914787292 +1769682119,706362368,0.0,0.0,0.0,1.0,0.00010561156523181126,0.00021737471979577094,0.00032280030427500606,-0.010956788435578346,0.07586024701595306,0.014982718974351883 +1769682119,753533952,0.0,0.0,0.0,1.0,0.00026148484903387725,0.00010566340642981231,0.0003745096328202635,-0.07573847472667694,-0.010454539209604263,0.010829086415469646 +1769682119,773323008,0.0,0.0,0.0,1.0,0.0005760896601714194,5.68667528568767e-05,0.0006045080372132361,-0.02119072899222374,0.15088315308094025,-0.011745263822376728 +1769682119,805901568,0.0,0.0,0.0,1.0,3.130148979835212e-05,0.00023042304383125156,0.000861375592648983,0.00016446440713480115,-0.0001917733607115224,-0.009533403441309929 +1769682119,852177920,0.0,0.0,0.0,1.0,0.0005999954883009195,0.00034045043867081404,0.0013075231108814478,-0.07543101906776428,-0.0108075812458992,-0.007046885788440704 +1769682119,872797184,0.0,0.0,0.0,1.0,0.0006039386498741806,0.001559871481731534,0.001606346108019352,0.06436065584421158,0.0868111252784729,0.02917640469968319 +1769682119,904311808,0.0,0.0,0.0,1.0,0.0003645635151769966,0.0027944990433752537,0.0018696399638429284,-0.08639506250619888,0.06508877873420715,0.00911042746156454 +1769682119,954460160,0.0,0.0,0.0,1.0,0.00021861617278773338,0.0033437637612223625,0.0020087012089788914,-0.09704039990901947,0.1406218558549881,0.007391679100692272 +1769682119,972879104,0.0,0.0,0.0,1.0,0.00011657911818474531,0.0037523782812058926,0.002101802732795477,-0.08611658215522766,0.06478670984506607,-0.006399653386324644 +1769682120,4436736,0.0,0.0,0.0,1.0,-5.532929571927525e-05,0.0038985146675258875,0.0021701641380786896,-0.08611002564430237,0.06479409337043762,-0.00641313660889864 +1769682120,47702784,0.0,0.0,0.0,1.0,-0.0001503884996054694,0.0037862518802285194,0.0021861507557332516,-0.12968400120735168,-0.17252115905284882,-0.005988466087728739 +1769682120,73811712,0.0,0.0,0.0,1.0,-6.104270869400352e-05,0.0037524288054555655,0.002183485310524702,0.00010704956366680562,-0.00012024985335301608,-0.005958294030278921 +1769682120,106651136,0.0,0.0,0.0,1.0,-0.00016426669026259333,0.0034969784319400787,0.002136912662535906,0.08617985993623734,-0.06490906327962875,0.001677689841017127 +1769682120,154155776,0.0,0.0,0.0,1.0,-0.00024424894945695996,0.0033642950002104044,0.002084660343825817,-0.20549681782722473,-0.1828707903623581,0.005909077823162079 +1769682120,171787264,0.0,0.0,0.0,1.0,-0.0002983611193485558,0.0032368157990276814,0.002027470851317048,0.08614961802959442,-0.06489578634500504,0.0028858801815658808 +1769682120,204999936,0.0,0.0,0.0,1.0,-9.488762589171529e-05,0.0031279430259019136,0.0019493296276777983,-0.0753866657614708,-0.010799510404467583,-0.009519851766526699 +1769682120,252195584,0.0,0.0,0.0,1.0,-0.0003993803693447262,0.003110102377831936,0.0018887198530137539,-0.06491969525814056,-0.08618565648794174,-0.0006587310344912112 +1769682120,271371008,0.0,0.0,0.0,1.0,-0.00025624182308092713,0.003067584941163659,0.0018338034860789776,-0.010572629980742931,0.07551121711730957,-0.00291054742410779 +1769682120,304305920,0.0,0.0,0.0,1.0,-0.0002645046915858984,0.0029807770624756813,0.0017723330529406667,-0.0860196053981781,0.06479860842227936,-0.008879352360963821 +1769682120,358757888,0.0,0.0,0.0,1.0,-0.00014212903624866158,0.0029234399553388357,0.0017264833441004157,-0.07552006840705872,-0.010637441650032997,-0.002399918856099248 +1769682120,373471488,0.0,0.0,0.0,1.0,-0.0001600052637513727,0.0030128732323646545,0.001678499742411077,0.07556545734405518,0.010585611686110497,2.3427768610417843e-05 +1769682120,405176064,0.0,0.0,0.0,1.0,-0.0002255082072224468,0.0029434242751449347,0.0016042415518313646,-0.07554347813129425,-0.010604655370116234,-0.001224078587256372 +1769682120,461827584,0.0,0.0,0.0,1.0,-0.00017829175340011716,0.002911667339503765,0.0015506611671298742,-0.06499439477920532,-0.08611541241407394,0.0016830088570713997 +1769682120,469638400,0.0,0.0,0.0,1.0,-2.700522236409597e-05,0.002959413919597864,0.001487532164901495,0.07554423809051514,0.010597665794193745,0.0012375686783343554 +1769682120,505904896,0.0,0.0,0.0,1.0,-0.00022140568762551993,0.002009688876569271,0.0013830551179125905,-0.07660287618637085,-0.009490590542554855,0.05356979742646217 +1769682120,551435520,0.0,0.0,0.0,1.0,-0.00014381752407643944,0.0011414734181016684,0.0012884698808193207,0.07450772076845169,0.011668906547129154,0.05487178638577461 +1769682120,571155968,0.0,0.0,0.0,1.0,-0.00031213610782288015,0.00046085621579550207,0.00117558054625988,-0.06567934900522232,-0.08540910482406616,0.03622201830148697 +1769682120,605197312,0.0,0.0,0.0,1.0,-0.00031736373784951866,-0.00014529867621604353,0.0009949596133083105,0.01016283594071865,-0.07513370364904404,0.021979806944727898 +1769682120,649495552,0.0,0.0,0.0,1.0,-0.0004757677670568228,-0.0003327328886371106,0.0008301199995912611,-0.06529290974140167,-0.0858122855424881,0.015962496399879456 +1769682120,671953664,0.0,0.0,0.0,1.0,-0.0003458020801190287,-0.00041581771802157164,0.000511094112880528,0.08600608259439468,-0.0648643895983696,0.007736267521977425 +1769682120,704272640,0.0,0.0,0.0,1.0,0.0002886066504288465,-0.0003784601576626301,-0.0003206460678484291,-0.14042559266090393,-0.09682321548461914,-0.006731540895998478 +1769682120,749827328,0.0,0.0,0.0,1.0,8.376090409001336e-05,-0.00026809528935700655,-0.0008964370936155319,0.06526816636323929,0.08583676815032959,-0.014775015413761139 +1769682120,771568896,0.0,0.0,0.0,1.0,0.00014233510592021048,7.641252159373835e-05,-0.0011157268891111016,-0.08649288862943649,0.065362848341465,0.017289351671934128 +1769682120,804899072,0.0,0.0,0.0,1.0,-0.0003872882225550711,0.0016333883395418525,-0.0014666913775727153,-0.021396270021796227,0.15136738121509552,0.010856104083359241 +1769682120,862105600,0.0,0.0,0.0,1.0,-0.0004986486164852977,0.0025335673708468676,-0.0016583482502028346,-0.06521293520927429,-0.08589296787977219,0.012382591143250465 +1769682120,871430912,0.0,0.0,0.0,1.0,-0.0005487219896167517,0.003098325338214636,-0.0018044142052531242,-0.06516297906637192,-0.08594442903995514,0.009992026723921299 +1769682120,906861824,0.0,0.0,0.0,1.0,-0.0006886097835376859,0.0035126779694110155,-0.0019318392733111978,-0.07547276467084885,-0.010673768818378448,-0.004847282078117132 +1769682120,950645248,0.0,0.0,0.0,1.0,-0.0005720603512600064,0.0035632073413580656,-0.001978771761059761,0.010435524396598339,-0.07539468258619308,0.008869919925928116 +1769682120,970925824,0.0,0.0,0.0,1.0,-0.0007088002748787403,0.003587848274037242,-0.0020049898885190487,-0.07528102397918701,-0.01087308581918478,-0.01439683698117733 +1769682121,4650240,0.0,0.0,0.0,1.0,-0.000341228413162753,0.003399550449103117,-0.0019928463734686375,-0.08605587482452393,0.06484778970479965,-0.006594507955014706 +1769682121,54476800,0.0,0.0,0.0,1.0,-0.0005015825154259801,0.003286432707682252,-0.001982080517336726,0.07561159133911133,0.010550307109951973,-0.0022675134241580963 +1769682121,70783488,0.0,0.0,0.0,1.0,-0.0005228737718425691,0.0031134316232055426,-0.001971476711332798,0.07556302100419998,0.010602317750453949,0.0001230492489412427 +1769682121,105748992,0.0,0.0,0.0,1.0,-0.000475209963042289,0.00296197272837162,-0.0019741251599043608,0.0002907118760049343,-0.00028472888516262174,-0.014299335889518261 +1769682121,153266432,0.0,0.0,0.0,1.0,-0.00035176819073967636,0.0028866934590041637,-0.0019861524924635887,0.1511717140674591,0.021178103983402252,-0.0021049599163234234 +1769682121,172419072,0.0,0.0,0.0,1.0,-0.00026046857237815857,0.00286357500590384,-0.0020059768576174974,-0.01080554910004139,0.07572263479232788,0.007813254371285439 +1769682121,204939264,0.0,0.0,0.0,1.0,-0.0004076180048286915,0.002769240876659751,-0.002030991716310382,0.08600399643182755,-0.06474307924509048,0.010215362533926964 +1769682121,263363072,0.0,0.0,0.0,1.0,-0.0002404112892691046,0.0027712590526789427,-0.0020507515873759985,-0.06496354192495346,-0.08613596856594086,0.0027507790364325047 +1769682121,271829248,0.0,0.0,0.0,1.0,-0.0002559552958700806,0.0027841643895953894,-0.0020556808449327946,0.01082316692918539,-0.07572018355131149,-0.007812561467289925 +1769682121,307052032,0.0,0.0,0.0,1.0,-0.00011616612027864903,0.00280297570861876,-0.0020499543752521276,-0.010431711561977863,0.07534091174602509,-0.011253858916461468 +1769682121,350600704,0.0,0.0,0.0,1.0,-0.00010109929280588403,0.0028790305368602276,-0.0020289025269448757,0.010710487142205238,-0.07560036331415176,-0.0018531589303165674 +1769682121,371316480,0.0,0.0,0.0,1.0,-0.00010857790766749531,0.0028513974975794554,-0.0019989744760096073,-0.06511753797531128,-0.08598779886960983,0.011066244915127754 +1769682121,404295680,0.0,0.0,0.0,1.0,0.00013713283988181502,0.0026274637784808874,-0.0019355305703356862,0.05358262360095978,0.16234804689884186,0.028922999277710915 +1769682121,448612096,0.0,0.0,0.0,1.0,-5.07231306983158e-05,0.001556347357109189,-0.0018842574208974838,0.139092817902565,0.09812008589506149,0.06302481144666672 +1769682121,471294976,0.0,0.0,0.0,1.0,9.73599890130572e-06,0.0006772529450245202,-0.001840056967921555,-0.07636576890945435,-0.009906329214572906,0.03792720288038254 +1769682121,505141504,0.0,0.0,0.0,1.0,-3.803787330980413e-05,-0.00019092572620138526,-0.0017894994234666228,-0.0005579521530307829,0.0005196441779844463,0.026214974001049995 +1769682121,554880256,0.0,0.0,0.0,1.0,-0.00022256329248193651,-0.0005449447780847549,-0.0017610100330784917,-0.0654219314455986,-0.08570157736539841,0.026543840765953064 +1769682121,572073984,0.0,0.0,0.0,1.0,-0.00012317253276705742,-0.0006515112472698092,-0.0017357623437419534,0.08606794476509094,-0.06470736861228943,0.009074196219444275 +1769682121,605460480,0.0,0.0,0.0,1.0,-0.0001297698327107355,-0.0006308001466095448,-0.0017188478959724307,-0.07550116628408432,-0.010728323832154274,-0.0025831065140664577 +1769682121,661194752,0.0,0.0,0.0,1.0,-0.00010032855061581358,-0.0005455164355225861,-0.0017023782711476088,0.06502632051706314,0.08606712520122528,-0.008672282099723816 +1769682121,674567424,0.0,0.0,0.0,1.0,-0.00011330821143928915,-0.0002503308351151645,-0.001695220242254436,-0.05398489162325859,-0.16192463040351868,-0.006289397832006216 +1769682121,707147520,0.0,0.0,0.0,1.0,-0.00013690687774214894,0.00037297981907613575,-0.00167933595366776,-0.08623550087213516,0.06482844799757004,-0.0019185757264494896 +1769682121,752012544,0.0,0.0,0.0,1.0,-0.00020103697897866368,0.0009561809711158276,-0.0016677523963153362,0.054297301918268204,0.16162370145320892,-0.009198667481541634 +1769682121,785756416,0.0,0.0,0.0,1.0,-0.00014334532897919416,0.00143154663965106,-0.0016556769842281938,-0.010642308741807938,0.07547424733638763,-0.004103524144738913 +1769682121,805557760,0.0,0.0,0.0,1.0,-8.47748015075922e-05,0.001777393976226449,-0.001632552477531135,-0.05377107858657837,-0.16210104525089264,-0.01464006956666708 +1769682121,853636864,0.0,0.0,0.0,1.0,-5.806478293379769e-05,0.001879049465060234,-0.0016156226629391313,0.010650452226400375,-0.07547305524349213,0.004104183055460453 +1769682121,871475712,0.0,0.0,0.0,1.0,-8.536871609976515e-05,0.0018149222014471889,-0.0015860034618526697,-0.021282121539115906,0.15092159807682037,-0.009400599636137486 +1769682121,904689920,0.0,0.0,0.0,1.0,-5.732024146709591e-05,0.0017227140488103032,-0.0015385134611278772,0.010658256709575653,-0.0754719078540802,0.0041049811989068985 +1769682121,950520576,0.0,0.0,0.0,1.0,-0.00013976029003970325,0.0016377808060497046,-0.0015111586544662714,0.08631022274494171,-0.06484360992908478,-0.00043563125655055046 +1769682121,973177856,0.0,0.0,0.0,1.0,-0.00013287231558933854,0.0015330383321270347,-0.001481160637922585,0.16165247559547424,-0.053926266729831696,0.00932989176362753 +1769682122,6244352,0.0,0.0,0.0,1.0,-9.280332960770465e-06,0.001460449886508286,-0.0014619111316278577,-0.021260248497128487,0.1508701890707016,-0.011786134913563728 +1769682122,78446080,0.0,0.0,0.0,1.0,-0.00014427707355935127,0.0014129556948319077,-0.0014561170246452093,0.053941428661346436,0.16190797090530396,0.003941178321838379 +1769682122,90869504,0.0,0.0,0.0,1.0,-0.00017955186194740236,0.0014543875586241484,-0.0014524483121931553,0.1616336852312088,-0.05387695133686066,0.010546241886913776 +1769682122,102663680,0.0,0.0,0.0,1.0,-0.0002758967748377472,0.001485734130255878,-0.001457622624002397,-0.0861435979604721,0.06465891748666763,-0.007923985831439495 +1769682122,146914048,0.0,0.0,0.0,1.0,-0.00016218317614402622,0.0015922222519293427,-0.0014595617540180683,0.02139294520020485,-0.1509600728750229,0.007020246237516403 +1769682122,171669248,0.0,0.0,0.0,1.0,-0.00012188695109216496,0.0015398272080346942,-0.0014566712779924273,-0.07554221153259277,-0.010747365653514862,-0.00025174033362418413 +1769682122,208599552,0.0,0.0,0.0,1.0,-0.0001523784885648638,0.0016706170281395316,-0.001452148426324129,0.16185137629508972,-0.054034266620874405,0.0010448818793520331 +1769682122,249823232,0.0,0.0,0.0,1.0,-0.0002054628130281344,0.0017158379778265953,-0.001430880045518279,-0.04325296729803085,-0.23734354972839355,0.002525996183976531 +1769682122,272281088,0.0,0.0,0.0,1.0,-0.00010228955216007307,0.0017448051366955042,-0.0014085735892876983,0.06484495103359222,0.0862247496843338,-0.003842146135866642 +1769682122,304360704,0.0,0.0,0.0,1.0,-0.0001776401768438518,0.0017207404598593712,-0.0013696778332814574,0.07567206025123596,0.010645195841789246,-0.005687948316335678 +1769682122,360450048,0.0,0.0,0.0,1.0,-1.946805787156336e-05,0.0015185002703219652,-0.0013264429289847612,0.15015266835689545,0.022351358085870743,0.042252399027347565 +1769682122,371616768,0.0,0.0,0.0,1.0,-0.0001731643860694021,0.0009178959298878908,-0.0012944408226758242,0.010174978524446487,-0.07499640434980392,0.027939047664403915 +1769682122,405915392,0.0,0.0,0.0,1.0,-0.00023090174363460392,0.0002601706946734339,-0.0012561158509925008,0.08569027483463287,-0.06420033425092697,0.02940831519663334 +1769682122,447027968,0.0,0.0,0.0,1.0,-7.141958485590294e-05,7.935056783026084e-05,-0.0012213460868224502,0.06437522172927856,0.08663743734359741,0.016427570953965187 +1769682122,474732032,0.0,0.0,0.0,1.0,-0.00020513507479336113,4.731239459943026e-05,-0.0011904583079740405,-0.00013272560318000615,0.0001170638352050446,0.005957840476185083 +1769682122,507408128,0.0,0.0,0.0,1.0,-0.00017282486078329384,-6.790528459532652e-07,-0.0011730713304132223,0.010585304349660873,-0.07534635066986084,0.010064128786325455 +1769682122,553486336,0.0,0.0,0.0,1.0,-0.0003044283075723797,5.7527260651113465e-05,-0.001161292428150773,0.010720661841332912,-0.07546302676200867,0.004105820320546627 +1769682122,571810816,0.0,0.0,0.0,1.0,-0.00019346615590620786,0.00020367465913295746,-0.0011479078093543649,0.00010621539695421234,-9.356174268759787e-05,-0.004766273777931929 +1769682122,606214912,0.0,0.0,0.0,1.0,-0.00011175801046192646,0.0003023297758772969,-0.0011384051758795977,-0.0862361267209053,0.06464878469705582,-0.005576600320637226 +1769682122,671635968,0.0,0.0,0.0,1.0,-9.084476914722472e-05,0.000491483137011528,-0.0011221881723031402,0.08639848977327347,-0.06478516012430191,-0.0015718007925897837 +1769682122,678611968,0.0,0.0,0.0,1.0,-6.22747975285165e-05,0.0005581967998296022,-0.0011048910673707724,-0.010705840773880482,0.07543804496526718,-0.0052962652407586575 +1769682122,704504320,0.0,0.0,0.0,1.0,-4.60457886219956e-05,0.0005998884444124997,-0.001076027750968933,-0.09705774486064911,0.14017044007778168,-0.006109973415732384 +1769682122,761446400,0.0,0.0,0.0,1.0,-6.255021435208619e-05,0.0006979249883443117,-0.0010385233908891678,0.06493061780929565,0.08614476770162582,-0.009777052327990532 +1769682122,769458688,0.0,0.0,0.0,1.0,-0.00022179044026415795,0.0007038661860860884,-0.0010038396576419473,-0.06460802257061005,-0.0864269956946373,-0.004523536656051874 +1769682122,805737216,0.0,0.0,0.0,1.0,-0.00016496847092639655,0.0005165613838471472,-0.0009544407948851585,0.23745013773441315,-0.043135300278663635,0.00020466395653784275 +1769682122,849897984,0.0,0.0,0.0,1.0,-0.00018557868315838277,0.00043023659964092076,-0.0009285559644922614,0.22614581882953644,0.03282121941447258,0.021126531064510345 +1769682122,873952256,0.0,0.0,0.0,1.0,-0.00014883026597090065,0.0005437227082438767,-0.0009056791313923895,0.21574606001377106,0.10798349231481552,0.001535751624032855 +1769682122,905028864,0.0,0.0,0.0,1.0,-4.608225208357908e-05,0.0005361305666156113,-0.0008804579847492278,-8.032162440940738e-05,6.99658558005467e-05,0.003574694273993373 +1769682122,948330752,0.0,0.0,0.0,1.0,-0.00024099792062770575,0.0005903231212869287,-0.0008666174835525453,-0.08633674681186676,0.06469061970710754,-0.0020146516617387533 +1769682122,971231744,0.0,0.0,0.0,1.0,-0.00019437223090790212,0.00035826137172989547,-0.0008527797181159258,0.05365154892206192,0.16206037998199463,0.008770693093538284 +1769682123,14321152,0.0,0.0,0.0,1.0,-0.00019728443294297904,0.00014329369878396392,-0.0008373322780244052,0.140066996216774,0.09730669856071472,0.007213565520942211 +1769682123,48486144,0.0,0.0,0.0,1.0,-0.00016572805179748684,-4.4212345528649166e-05,-0.0008232525433413684,0.07561198621988297,0.010751351714134216,-0.0032783891074359417 +1769682123,70996224,0.0,0.0,0.0,1.0,-0.0002814080798998475,-0.00014846977137494832,-0.0008040004759095609,0.23735256493091583,-0.04298859462141991,0.004990234971046448 +1769682123,104962304,0.0,0.0,0.0,1.0,-3.869335341732949e-05,-0.000302920991089195,-0.0007717281114310026,0.1509009599685669,0.021790554746985435,0.0077398912981152534 +1769682123,164114432,0.0,0.0,0.0,1.0,-8.632100070826709e-05,-0.0003035346744582057,-0.0007348844083026052,-0.010843386873602867,0.07552707940340042,-0.0005264513893052936 +1769682123,174550016,0.0,0.0,0.0,1.0,-0.0001067709454218857,-0.00032368864049203694,-0.000698604213539511,0.07539650797843933,0.010945086367428303,0.006251716986298561 +1769682123,204349952,0.0,0.0,0.0,1.0,-0.0001673492370173335,-0.0004465871024876833,-0.0006326789734885097,0.010847000405192375,-0.07552656531333923,0.0005254887510091066 +1769682123,247801344,0.0,0.0,0.0,1.0,-9.624045560485683e-07,-0.000390712171792984,-0.0005769931012764573,-0.09703939408063889,0.14005784690380096,-0.009683210402727127 +1769682123,271202816,0.0,0.0,0.0,1.0,-8.900941611500457e-05,-0.00040570987039245665,-0.000527931668329984,0.0755297914147377,0.010833319276571274,0.00029098609229549766 +1769682123,308440832,0.0,0.0,0.0,1.0,-4.504049138631672e-05,-0.0003959887835662812,-0.0004740200820378959,-0.06457159668207169,-0.08645378053188324,-0.004531831946223974 +1769682123,357913856,0.0,0.0,0.0,1.0,-0.00015572496340610087,-0.0004422259808052331,-0.0004465666424948722,-0.010745317675173283,0.07543288171291351,-0.005289894063025713 +1769682123,372419584,0.0,0.0,0.0,1.0,-0.0002727175015024841,-0.00045583059545606375,-0.00043287946027703583,0.01082644797861576,-0.07550246268510818,0.0017145626479759812 +1769682123,406141440,0.0,0.0,0.0,1.0,-0.00012877208064310253,-0.000434837827924639,-0.0004367823130451143,-0.02162892371416092,0.1509813666343689,-0.0046190135180950165 +1769682123,453977856,0.0,0.0,0.0,1.0,-0.0003244215913582593,-0.00048210148815996945,-0.00045932165812700987,-7.996303611434996e-05,6.963260238990188e-05,0.0035747087094932795 +1769682123,472190976,0.0,0.0,0.0,1.0,-0.0003239572106394917,-0.0005008391453884542,-0.0004844038048759103,0.1510576605796814,0.02168048545718193,0.0005693900166079402 +1769682123,505093888,0.0,0.0,0.0,1.0,-0.0003487978538032621,-0.0005828975117765367,-0.000532936246600002,0.07563505321741104,0.010749032720923424,-0.004483072552829981 +1769682123,548013056,0.0,0.0,0.0,1.0,-0.0003249191795475781,-0.0005904024001210928,-0.0005712456186302006,0.2264789193868637,0.032621853053569794,0.005612642504274845 +1769682123,573974016,0.0,0.0,0.0,1.0,-0.00028056916198693216,-0.0009990750113502145,-0.0006001184810884297,0.08662809431552887,-0.06488871574401855,-0.009926105849444866 +1769682123,606787584,0.0,0.0,0.0,1.0,-0.0002590914664324373,-0.0015009636990725994,-0.0006306790164671838,0.07581951469182968,0.010591617785394192,-0.012830808758735657 +1769682123,639700992,0.0,0.0,0.0,1.0,-0.00040269180317409337,-0.0017653219401836395,-0.0006430846406146884,0.00015865273599047214,-0.00013882690109312534,-0.0071494546718895435 +1769682123,670886400,0.0,0.0,0.0,1.0,-0.00036944958264939487,-0.001987675903365016,-0.0006443791789934039,0.09746984392404556,-0.140383780002594,-0.008236724883317947 +1769682123,709760512,0.0,0.0,0.0,1.0,-0.0002507655881345272,-0.002172286855056882,-0.0006329923053272069,0.0754222497344017,0.010943553410470486,0.005028577987104654 +1769682123,749627904,0.0,0.0,0.0,1.0,-0.0002072350907837972,-0.0021547318901866674,-0.0006103852647356689,-0.1293686181306839,-0.1727057695388794,0.0028900427278131247 +1769682123,773331200,0.0,0.0,0.0,1.0,-0.00015488150529563427,-0.002165710087865591,-0.0005740294000133872,0.15108010172843933,0.02168455719947815,-0.0006865030154585838 +1769682123,805691904,0.0,0.0,0.0,1.0,-0.0002017073566094041,-0.0021081974264234304,-0.0005147896590642631,-0.06455062329769135,-0.08647088706493378,-0.004504335578531027 +1769682123,869608448,0.0,0.0,0.0,1.0,-2.627882349770516e-05,-0.0020919686648994684,-0.00046844009193591774,-0.15092355012893677,-0.021828535944223404,-0.006440893746912479 +1769682123,877088512,0.0,0.0,0.0,1.0,-0.00010833086707862094,-0.0019953588489443064,-0.00042270394624210894,0.06485866755247116,0.08619599044322968,-0.00980319082736969 +1769682123,906696704,0.0,0.0,0.0,1.0,-0.00022223632549867034,-0.0019108615815639496,-0.000398851465433836,7.733671372989193e-05,-6.920738815097138e-05,-0.003574775066226721 +1769682123,951458048,0.0,0.0,0.0,1.0,-0.00019649781461339444,-0.0018900299910455942,-0.00038220814894884825,0.06457266211509705,0.08645133674144745,0.003297997172921896 +1769682123,979408128,0.0,0.0,0.0,1.0,-0.000323315616697073,-0.0018024417804554105,-0.00037252894253470004,-7.687068136874586e-05,6.914436380611733e-05,0.003574786242097616 +1769682124,5885184,0.0,0.0,0.0,1.0,-0.00021075294353067875,-0.0017279188614338636,-0.0003669446741696447,2.5561490474501625e-05,-2.3040909582050517e-05,-0.0011915969662368298 +1769682124,53936384,0.0,0.0,0.0,1.0,-0.00021488135098479688,-0.0017198120476678014,-0.0003670675796456635,-0.07547486573457718,-0.010908534750342369,-0.002596850972622633 +1769682124,72290048,0.0,0.0,0.0,1.0,-0.00021718777134083211,-0.0017652572132647038,-0.0003643165109679103,0.07570382207632065,0.010702138766646385,-0.008131397888064384 +1769682124,109234944,0.0,0.0,0.0,1.0,-0.0001070816651917994,-0.0017247986979782581,-0.00036078126868233085,-0.08628015220165253,0.06454237550497055,-0.006659922190010548 +1769682124,141402112,0.0,0.0,0.0,1.0,-0.00027550337836146355,-0.0017469606827944517,-0.0003591689164750278,-0.07539904862642288,-0.01098020188510418,-0.006158731412142515 +1769682124,171046144,0.0,0.0,0.0,1.0,-0.0003395032836124301,-0.001590639934875071,-0.00036581343738362193,0.07547493278980255,0.010912002064287663,0.002580266445875168 +1769682124,207423232,0.0,0.0,0.0,1.0,-0.0004725008038803935,-0.0013888335088267922,-0.0003997438179794699,0.0003522448823787272,-0.00032163041760213673,-0.016682494431734085 +1769682124,254526464,0.0,0.0,0.0,1.0,-0.00026099657407030463,-0.000775266787968576,-0.0004340053419582546,-0.07504773139953613,-0.011304432526230812,-0.02283099666237831 +1769682124,272474368,0.0,0.0,0.0,1.0,-0.00015377132513094693,-0.0003444150206632912,-0.0004765259800478816,-0.1614590734243393,0.053346678614616394,-0.023511001840233803 +1769682124,304687616,0.0,0.0,0.0,1.0,-0.0002688980021048337,4.778341099154204e-05,-0.0005492573254741728,-0.0214743223041296,0.15076658129692078,-0.015280544757843018 +1769682124,349755648,0.0,0.0,0.0,1.0,-0.0003731480101123452,0.00020890578161925077,-0.0006039320142008364,-0.08618766069412231,0.06444230675697327,-0.011404329910874367 +1769682124,376330496,0.0,0.0,0.0,1.0,-0.00030510182841680944,0.00029857433401048183,-0.0006760614924132824,0.010815693065524101,-0.07545171678066254,0.004064131993800402 +1769682124,407263488,0.0,0.0,0.0,1.0,-0.00037571266875602305,0.00029383902437984943,-0.0007251798524521291,-0.1617898941040039,0.05363152548670769,-0.008021614514291286 +1769682124,449783552,0.0,0.0,0.0,1.0,-0.00018864875892177224,0.0002226249489467591,-0.0007662635180167854,-0.0647551417350769,-0.08628285676240921,0.006254249252378941 +1769682124,471452416,0.0,0.0,0.0,1.0,-0.00022549401910509914,0.00013870133261661977,-0.0008091723429970443,0.06452673673629761,0.08649042993783951,0.0044712526723742485 +1769682124,510793216,0.0,0.0,0.0,1.0,-0.0001548157597426325,-0.0006599370390176773,-0.0008557605906389654,0.129877507686615,0.1722303181886673,-0.03037966787815094 +1769682124,552145920,0.0,0.0,0.0,1.0,-0.00016807155043352395,-0.0015897767152637243,-0.0008686442743055522,0.15137207508087158,0.021470069885253906,-0.015112118795514107 +1769682124,573139712,0.0,0.0,0.0,1.0,-0.00027862112619914114,-0.0023298116866499186,-0.0008667287183925509,0.043139807879924774,0.23714493215084076,-0.016760636121034622 +1769682124,604727296,0.0,0.0,0.0,1.0,-0.0002584301691967994,-0.003006717888638377,-0.0008585404139012098,-0.010656431317329407,0.0752900242805481,-0.012398991733789444 +1769682124,650157824,0.0,0.0,0.0,1.0,-0.00025116530014202,-0.0031153797172009945,-0.0008463847916573286,-0.0756211206316948,-0.010798812843859196,0.0045970226638019085 +1769682124,672017664,0.0,0.0,0.0,1.0,-0.000250262237386778,-0.003183088731020689,-0.0008344665402546525,0.06471113860607147,0.08631864190101624,-0.005083922296762466 +1769682124,707794688,0.0,0.0,0.0,1.0,-0.00021083763567730784,-0.0030464131850749254,-0.0008154138340614736,-0.06473219394683838,-0.08629800379276276,0.006282737012952566 +1769682124,749490176,0.0,0.0,0.0,1.0,-0.00021416856907308102,-0.0029747369699180126,-0.0008033888298086822,0.07532582432031631,0.011078765615820885,0.009679281152784824 +1769682124,772829952,0.0,0.0,0.0,1.0,-0.0001787174987839535,-0.0028339698910713196,-0.000783564813900739,0.010672390460968018,-0.07528909295797348,0.012390907853841782 +1769682124,805603328,0.0,0.0,0.0,1.0,-0.00023077434161677957,-0.002671666909009218,-0.0007714158855378628,0.08631757646799088,-0.0645022988319397,0.006562594324350357 +1769682124,847856640,0.0,0.0,0.0,1.0,-7.003339123912156e-05,-0.0025717748794704676,-0.0007626814767718315,-0.07530350238084793,-0.01110717561095953,-0.01085065770894289 +1769682124,883617792,0.0,0.0,0.0,1.0,-0.00025775612448342144,-0.0025692787021398544,-0.0007639700197614729,0.08622553944587708,-0.06440737098455429,0.011314966715872288 +1769682124,905838848,0.0,0.0,0.0,1.0,-0.0002880283282138407,-0.0025823323521763086,-0.000775184715166688,0.02699127048254013,0.08082112669944763,-0.008157440461218357 +1769682124,952316160,0.0,0.0,0.0,1.0,-0.0002499310066923499,-0.002571332035586238,-0.0007948625716380775,-0.037724073976278305,-0.005488147493451834,-0.0018409444019198418 +1769682124,971933696,0.0,0.0,0.0,1.0,-0.00019036603043787181,-0.002532484708353877,-0.0008305423543788493,-0.03781887888908386,-0.005398144945502281,0.0029284260235726833 +1769682125,7853824,0.0,0.0,0.0,1.0,-0.00020995621162001044,-0.00255547184497118,-0.0008946644375100732,0.12431466579437256,-0.05924833193421364,-0.00475867697969079 +1769682125,57958912,0.0,0.0,0.0,1.0,-0.00043525081127882004,-0.002585090696811676,-0.0009556129807606339,-7.037372415652499e-05,6.808571924921125e-05,0.003574940375983715 +1769682125,70828800,0.0,0.0,0.0,1.0,-0.000301326101180166,-0.002623122651129961,-0.0009892022935673594,-0.048565078526735306,0.06993113458156586,-0.007055047899484634 +1769682125,106045952,0.0,0.0,0.0,1.0,-0.0003219286445528269,-0.002588644390925765,-0.0010411250405013561,0.010984298773109913,-0.07555925846099854,-0.0019254949875175953 +1769682125,162515712,0.0,0.0,0.0,1.0,-0.0004091644659638405,-0.0025839589070528746,-0.0010708890622481704,-0.026760613545775414,-0.08103139698505402,-0.0025572767481207848 +1769682125,173944832,0.0,0.0,0.0,1.0,-0.00017021253006532788,-0.0018721063388511539,-0.0011046602157875896,-0.09624745696783066,0.13896915316581726,-0.06055620685219765 +1769682125,207365632,0.0,0.0,0.0,1.0,-0.00012688389688264579,-0.0006762992707081139,-0.00110942916944623,-0.03687087073922157,-0.00633567851036787,-0.04590906202793121 +1769682125,252471296,0.0,0.0,0.0,1.0,-0.00026455754414200783,5.085503289592452e-07,-0.0011084962170571089,0.03843797370791435,0.004797694273293018,-0.03512372821569443 +1769682125,271886336,0.0,0.0,0.0,1.0,-0.00028611955349333584,0.0004460980126168579,-0.0011025313287973404,0.011481367982923985,-0.07603242993354797,-0.02695491909980774 +1769682125,305239040,0.0,0.0,0.0,1.0,-6.011050572851673e-05,0.0006764566642232239,-0.0010933845769613981,0.027138130739331245,0.08065174520015717,-0.017700809985399246 +1769682125,350075648,0.0,0.0,0.0,1.0,-0.0001469613634981215,0.0007600686512887478,-0.001092275488190353,0.011095511727035046,-0.07564688473939896,-0.006696708034723997 +1769682125,372334848,0.0,0.0,0.0,1.0,-0.00021079361613374203,0.0006933717522770166,-0.0011011805618181825,-9.255836630472913e-05,9.044804755831137e-05,0.004766617901623249 +1769682125,404889856,0.0,0.0,0.0,1.0,-0.00019652652554214,0.0005484838038682938,-0.00111687695607543,0.010684611275792122,-0.07523908466100693,0.014752800576388836 +1769682125,452325632,0.0,0.0,0.0,1.0,-0.0001669377088546753,0.0003942285547964275,-0.001148455892689526,-0.03783809393644333,-0.005394588690251112,0.004136187024414539 +1769682125,473708800,0.0,0.0,0.0,1.0,-0.0002516937965992838,-0.0005945878219790757,-0.0011649454245343804,0.07565256208181381,0.010814479552209377,-0.0070812031626701355 +1769682125,505076992,0.0,0.0,0.0,1.0,-0.0002679795725271106,-0.0015488736098632216,-0.0012029993813484907,-0.0484851635992527,0.06979523599147797,-0.012995749711990356 +1769682125,565016832,0.0,0.0,0.0,1.0,-0.00018597234156914055,-0.0020761743653565645,-0.0012239668285474181,0.02681662328541279,0.08095299452543259,-0.002206664765253663 +1769682125,574283264,0.0,0.0,0.0,1.0,-0.00023851000878494233,-0.0023787720128893852,-0.0012489946093410254,0.000137850089231506,-0.00013532726734410971,-0.007149952929466963 +1769682125,607272704,0.0,0.0,0.0,1.0,-0.0002146035258192569,-0.0024660294875502586,-0.0012844728771597147,0.026626253500580788,0.08113573491573334,0.007323680445551872 +1769682125,653944832,0.0,0.0,0.0,1.0,-0.0004004434449598193,-0.002500904956832528,-0.0013073571026325226,-0.02671472355723381,-0.08104658126831055,-0.002555747050791979 +1769682125,671280128,0.0,0.0,0.0,1.0,-0.00015965377679094672,-0.002440888434648514,-0.001330269267782569,0.08627092093229294,-0.06431270390748978,0.012397698126733303 +1769682125,708405504,0.0,0.0,0.0,1.0,-0.000274992868071422,-0.002299385378137231,-0.001359456917271018,-0.059590552002191544,0.14537972211837769,-0.0086445901542902 +1769682125,760570368,0.0,0.0,0.0,1.0,-0.00011914490460185334,-0.0022300402633845806,-0.0013845328940078616,-0.037788599729537964,-0.005454326514154673,0.0017747636884450912 +1769682125,772547328,0.0,0.0,0.0,1.0,-0.000190457227290608,-0.0020779550541192293,-0.0014047132572159171,-0.03785550594329834,-0.005388460587710142,0.0053521920926868916 +1769682125,805271552,0.0,0.0,0.0,1.0,-5.4986332543194294e-05,-0.0020286848302930593,-0.0014255783753469586,-0.08653273433446884,0.06454361230134964,0.000739178853109479 +1769682125,868014592,0.0,0.0,0.0,1.0,-0.00017614112584851682,-0.001977444626390934,-0.0014358785701915622,-0.010916044004261494,0.07541437447071075,-0.0052034854888916016 +1769682125,878562816,0.0,0.0,0.0,1.0,-0.00017413355817552656,-0.0019822942558676004,-0.001441134954802692,-0.04857488349080086,0.06981709599494934,-0.010566680692136288 +1769682125,906842880,0.0,0.0,0.0,1.0,-6.678790668956935e-05,-0.0020389046985656023,-0.0014366324758157134,-0.08656395971775055,0.06455360352993011,0.0019493766594678164 +1769682125,948020992,0.0,0.0,0.0,1.0,-8.906625589588657e-05,-0.0019880742765963078,-0.0014322376810014248,0.011104057542979717,-0.07559248059988022,-0.004333393648266792 +1769682125,978262528,0.0,0.0,0.0,1.0,-0.00011826175614260137,-0.001980400178581476,-0.0014153668889775872,-0.0864386186003685,0.0644102692604065,-0.005188049282878637 +1769682126,6418688,0.0,0.0,0.0,1.0,-0.00025711397756822407,-0.0019411110552027822,-0.0014012842439115047,0.011001689359545708,-0.07547915726900101,0.0016228151507675648 +1769682126,54949632,0.0,0.0,0.0,1.0,-0.0001706941402517259,-0.0020218873396515846,-0.0013848680537194014,0.04865943267941475,-0.06987359374761581,0.006974611431360245 +1769682126,71228928,0.0,0.0,0.0,1.0,-0.00019206431170459837,-0.001968367723748088,-0.0013789955992251635,0.01122527476400137,-0.07570250332355499,-0.010295933112502098 +1769682126,109978112,0.0,0.0,0.0,1.0,-0.0002009673771681264,-0.0016644110437482595,-0.0013870159164071083,0.0763472467660904,0.010141432285308838,-0.046505510807037354 +1769682126,148706304,0.0,0.0,0.0,1.0,-3.0443639843724668e-05,-0.0008981400751508772,-0.0013929179403930902,-0.04797963798046112,0.06914989650249481,-0.045099250972270966 +1769682126,173530368,0.0,0.0,0.0,1.0,-0.00010902370559051633,-0.0003279638185631484,-0.0014102575369179249,-0.021498560905456543,0.15039344131946564,-0.03302876278758049 +1769682126,205193984,0.0,0.0,0.0,1.0,-2.621379098854959e-05,0.00019470491679385304,-0.0014284186763688922,0.04906552657485008,-0.07026536762714386,-0.01448629517108202 +1769682126,255370496,0.0,0.0,0.0,1.0,-0.00021034352539572865,0.0004015372833237052,-0.0014537014067173004,-0.015406826511025429,-0.15676835179328918,-0.012836025096476078 +1769682126,272190208,0.0,0.0,0.0,1.0,-0.00024740758817642927,0.000472316489322111,-0.0014814558671787381,0.037912726402282715,0.005348550621420145,-0.008953269571065903 +1769682126,305806336,0.0,0.0,0.0,1.0,-0.00014481401012744755,0.00044741720193997025,-0.0015302064130082726,0.022090064361691475,-0.1509714275598526,0.002043056068941951 +1769682126,347817472,0.0,0.0,0.0,1.0,-0.000215077685425058,0.00033424608409404755,-0.0015936926938593388,-0.011081029660999775,0.07551874220371246,0.0007664670702069998 +1769682126,376873984,0.0,0.0,0.0,1.0,-0.0002622444008011371,0.00015662256919313222,-0.001693523838184774,0.05326254293322563,0.16214905679225922,0.005080784671008587 +1769682126,406652416,0.0,0.0,0.0,1.0,-0.0002226777869509533,-0.0004307276103645563,-0.0017711372347548604,0.04898013919591904,-0.07013770937919617,-0.008527816273272038 +1769682126,453689600,0.0,0.0,0.0,1.0,-0.00021696531621273607,-0.0010329252108931541,-0.0018433500081300735,0.015701519325375557,0.15641549229621887,-0.006224098149687052 +1769682126,472549120,0.0,0.0,0.0,1.0,-0.00028176719206385314,-0.0014494635397568345,-0.0019062993815168738,0.011141453869640827,-0.07556083053350449,-0.0031529159750789404 +1769682126,508629248,0.0,0.0,0.0,1.0,-0.00020015519112348557,-0.0017611992079764605,-0.0019493360305204988,-0.022057777270674706,0.15087443590164185,-0.006800154224038124 +1769682126,554710528,0.0,0.0,0.0,1.0,-7.102279778337106e-05,-0.00187493150588125,-0.0019640768878161907,0.0,-0.0,0.0 +1769682126,573568000,0.0,0.0,0.0,1.0,-2.4819159079925157e-05,-0.0018427218310534954,-0.0019484834047034383,0.010942026972770691,-0.07533558458089828,0.00876098033040762 +1769682126,606455552,0.0,0.0,0.0,1.0,-5.637496360577643e-05,-0.0017284577479586005,-0.0018933572573587298,0.07528197020292282,0.011301795020699501,0.011864906176924706 +1769682126,660505344,0.0,0.0,0.0,1.0,2.2051328414818272e-05,-0.001660871203057468,-0.0018448607297614217,-0.059812359511852264,0.14529404044151306,-0.008553028106689453 +1769682126,677649152,0.0,0.0,0.0,1.0,-0.00010341891902498901,-0.0015489753568544984,-0.0017614312237128615,-0.11329279839992523,-0.01657690480351448,0.0030703574884682894 +1769682126,705066240,0.0,0.0,0.0,1.0,-9.589782712282613e-05,-0.0014893452171236277,-0.0017024698900058866,-4.217523382976651e-05,4.45905898232013e-05,0.0023833971936255693 +1769682126,751187456,0.0,0.0,0.0,1.0,-0.00010513590677874163,-0.001437360537238419,-0.0016593176405876875,0.07555527240037918,0.011029225774109364,-0.003642556257545948 +1769682126,776412416,0.0,0.0,0.0,1.0,-4.452027496881783e-05,-0.0014605369651690125,-0.0016116214683279395,0.08646432310342789,-0.0642305314540863,0.008685300126671791 +1769682126,808542208,0.0,0.0,0.0,1.0,-0.00017996082897298038,-0.001386202871799469,-0.0015924430917948484,-0.026548918336629868,-0.08111738413572311,-0.003718981519341469 +1769682126,848169984,0.0,0.0,0.0,1.0,-0.0001308865030296147,-0.0013909153640270233,-0.0015833054203540087,0.0,-0.0,0.0 +1769682126,871336704,0.0,0.0,0.0,1.0,-0.0001607779850019142,-0.001433842466212809,-0.001576347858645022,0.03763040900230408,0.005678440444171429,0.006513721309602261 +1769682126,908286976,0.0,0.0,0.0,1.0,-0.00018167556845583022,-0.0014573734952136874,-0.0015635467134416103,-4.150684253545478e-05,4.4543434341903776e-05,0.0023834097664803267 +1769682126,945145856,0.0,0.0,0.0,1.0,-0.00013603086699731648,-0.001515635522082448,-0.0015435406239703298,0.022238608449697495,-0.1509246975183487,0.003205825574696064 +1769682126,971371776,0.0,0.0,0.0,1.0,-0.00013530639989767224,-0.0014948609750717878,-0.001535424729809165,-0.03777502477169037,-0.0055283852852880955,0.001833674730733037 +1769682127,4908288,0.0,0.0,0.0,1.0,-0.00022478794562630355,-0.0014693762641400099,-0.0015165002550929785,-0.06419642269611359,-0.0867675244808197,-0.007835648953914642 +1769682127,53456896,0.0,0.0,0.0,1.0,-0.00011146236647618935,-0.0015058241551741958,-0.0015187675599008799,0.01104776468127966,-0.07537183910608292,0.006367427762597799 +1769682127,72970496,0.0,0.0,0.0,1.0,-0.00011787028779508546,-0.0009354667272418737,-0.0015396213857457042,0.0004917247570119798,-0.0005338392220437527,-0.028601041063666344 +1769682127,105736448,0.0,0.0,0.0,1.0,-0.0002019731909967959,-0.0002643005282152444,-0.0015825355658307672,-0.010769744403660297,0.0750594213604927,-0.023049987852573395 +1769682127,148875008,0.0,0.0,0.0,1.0,-8.560599235352129e-05,7.634670328116044e-05,-0.0016242294805124402,-0.07089164853096008,0.2205055058002472,-0.020833181217312813 +1769682127,179725568,0.0,0.0,0.0,1.0,-0.0001710707147140056,0.000359238067176193,-0.001681979396380484,0.022498393431305885,-0.15113897621631622,-0.008719767443835735 +1769682127,205750528,0.0,0.0,0.0,1.0,-2.1804007701575756e-05,0.0004075807810295373,-0.0017153301741927862,-0.03760869428515434,-0.005720573477447033,-0.007695043925195932 +1769682127,254395648,0.0,0.0,0.0,1.0,-3.914565604645759e-05,0.0003713360638357699,-0.0017374346498399973,0.02651529759168625,0.08111310750246048,0.0025219512172043324 +1769682127,272672256,0.0,0.0,0.0,1.0,9.884827886708081e-05,0.00033224403159692883,-0.0017394657479599118,-0.07554426044225693,-0.011093556880950928,0.0036754717584699392 +1769682127,306609152,0.0,0.0,0.0,1.0,-9.881405276246369e-07,0.00015118489682208747,-0.0017062061233446002,0.0641334056854248,0.08682117611169815,0.009027068503201008 +1769682127,355213824,0.0,0.0,0.0,1.0,3.205534449080005e-05,-2.3694867195445113e-05,-0.0016677477397024632,0.048712972551584244,-0.06965971738100052,0.012870344333350658 +1769682127,372339968,0.0,0.0,0.0,1.0,0.0001086972260964103,-0.00039700785418972373,-0.001604770659469068,0.037730131298303604,0.005597549024969339,0.0005458340747281909 +1769682127,405731072,0.0,0.0,0.0,1.0,0.00014116166858002543,-0.0006696117925457656,-0.0015136564616113901,-0.00010255005327053368,0.00011107228783657774,0.005958551540970802 +1769682127,454409472,0.0,0.0,0.0,1.0,-9.273084287997335e-05,-0.0008173657115548849,-0.0014572805957868695,0.02659129723906517,0.08101070672273636,-0.0034379782155156136 +1769682127,472937216,0.0,0.0,0.0,1.0,-6.160551492939703e-06,-0.00091409997548908,-0.0014053715858608484,-0.04891183227300644,0.06984994560480118,-0.0021415231749415398 +1769682127,505891328,0.0,0.0,0.0,1.0,-0.00015234762395266443,-0.0009754029451869428,-0.0013611973263323307,-0.015396464616060257,-0.1564657837152481,0.005037877708673477 +1769682127,553967360,0.0,0.0,0.0,1.0,-6.219168426468968e-05,-0.0009577631135471165,-0.0013459965121001005,-0.02666129730641842,-0.08092553168535233,0.008207360282540321 +1769682127,581316352,0.0,0.0,0.0,1.0,-0.00017422871314920485,-0.0009299041121266782,-0.0013475508894771338,-0.048719145357608795,0.06962057203054428,-0.01405335869640112 +1769682127,607460608,0.0,0.0,0.0,1.0,-0.00013386335922405124,-0.0008674134151078761,-0.0013629202730953693,-0.04882385954260826,0.06972964853048325,-0.008093303069472313 +1769682127,649123584,0.0,0.0,0.0,1.0,-0.0001076871485565789,-0.0007978564244695008,-0.0013883394422009587,-0.07557790726423264,-0.011090591549873352,0.00607557687908411 +1769682127,671356672,0.0,0.0,0.0,1.0,-0.0001505094114691019,-0.0007360024028457701,-0.0014133290387690067,-0.07551655173301697,-0.011160371825098991,0.002502134069800377 +1769682127,708547072,0.0,0.0,0.0,1.0,-0.00014187982014846057,-0.0006557918386533856,-0.0014392668381333351,0.037747811526060104,0.005593442358076572,-0.0006562083726748824 +1769682127,748354816,0.0,0.0,0.0,1.0,-1.2636861356440932e-05,-0.0006388730835169554,-0.0014576490502804518,-0.08674658834934235,0.06430314481258392,0.002102842088788748 +1769682127,773103360,0.0,0.0,0.0,1.0,-5.504737055161968e-05,-0.0005877182120457292,-0.0014727399684488773,-0.04880032688379288,0.0696742981672287,-0.010470068082213402 +1769682127,805035520,0.0,0.0,0.0,1.0,-4.8481771955266595e-05,-0.0005754673038609326,-0.0014995496021583676,0.01138016302138567,-0.07562517374753952,-0.007940252311527729 +1769682127,867000576,0.0,0.0,0.0,1.0,-4.8999296268448234e-05,-0.0006096625002101064,-0.0015242267400026321,0.011223578825592995,-0.07544711977243423,0.001592978835105896 +1769682127,874965248,0.0,0.0,0.0,1.0,1.1821766747743823e-05,-0.0006010840879753232,-0.0015448746271431446,0.04899352416396141,-0.06986573338508606,-0.0002589948708191514 +1769682127,906221056,0.0,0.0,0.0,1.0,4.018581239506602e-05,-0.0005688188830390573,-0.0015627703396603465,0.026635920628905296,0.08091792464256287,-0.009403068572282791 +1769682127,948387840,0.0,0.0,0.0,1.0,-1.3297973055159673e-05,-0.0006165870581753552,-0.0015636582393199205,-0.03790630027651787,-0.005429305136203766,0.010194927453994751 +1769682127,983342336,0.0,0.0,0.0,1.0,-6.219315764610656e-06,-0.0006049976800568402,-0.0015503307804465294,0.022275034338235855,-0.15066847205162048,0.015100927092134953 +1769682128,7412224,0.0,0.0,0.0,1.0,4.031717253383249e-06,-0.0003658825298771262,-0.0015212581492960453,0.037965405732393265,0.005366917233914137,-0.013771502301096916 +1769682128,50231808,0.0,0.0,0.0,1.0,0.00018626140081323683,-0.00015441171126440167,-0.0014875122578814626,-0.06408383697271347,-0.08684580773115158,-0.006616335827857256 +1769682128,71814400,0.0,0.0,0.0,1.0,6.9950983743183315e-06,2.9129285394446924e-05,-0.0014556603273376822,0.026555560529232025,0.08099085837602615,-0.005829914472997189 +1769682128,105555200,0.0,0.0,0.0,1.0,-1.7003876564558595e-06,0.00011413318861741573,-0.0014187665656208992,0.011253450065851212,-0.07544269412755966,0.0015921912854537368 +1769682128,152706048,0.0,0.0,0.0,1.0,-2.9156970413168892e-05,0.00023096826043911278,-0.0014025737764313817,-0.011137489229440689,0.07530906796455383,-0.008742669597268105 +1769682128,172002304,0.0,0.0,0.0,1.0,-3.6024834116688e-05,0.00023891888849902898,-0.0014059575041756034,4.007538882433437e-05,-4.432740752235986e-05,-0.0023834386374801397 +1769682128,205656832,0.0,0.0,0.0,1.0,-1.63746444741264e-05,0.00023084282292984426,-0.0014422681415453553,0.06007121503353119,-0.14503908157348633,0.014440066181123257 +1769682128,267421952,0.0,0.0,0.0,1.0,-9.798677638173103e-05,0.00012162046186858788,-0.0014835514593869448,-0.03770318627357483,-0.005667482037097216,-0.001721627777442336 +1769682128,275255808,0.0,0.0,0.0,1.0,5.123731170897372e-06,0.000133126275613904,-0.001544324099086225,-0.04919552430510521,0.07001382857561111,0.00979494396597147 +1769682128,307961600,0.0,0.0,0.0,1.0,1.5821829947526567e-05,0.00017400519573129714,-0.001596026006154716,0.06400913745164871,0.08691538870334625,0.00900251604616642 +1769682128,352194560,0.0,0.0,0.0,1.0,-9.744089766172692e-05,0.00021249889687169343,-0.0016380640445277095,0.0980432853102684,-0.13961949944496155,0.0018611557316035032 +1769682128,373667840,0.0,0.0,0.0,1.0,-5.833179602632299e-05,0.00022139083012007177,-0.0016728827031329274,-0.04896485060453415,0.0697408989071846,-0.004505886230617762 +1769682128,409361408,0.0,0.0,0.0,1.0,-3.42764105880633e-05,0.0001943149691214785,-0.0017089804168790579,-0.04907004162669182,0.06984826922416687,0.0014524287544190884 +1769682128,447949568,0.0,0.0,0.0,1.0,-5.194060577196069e-06,0.0002543776645325124,-0.0017271266551688313,0.00020109745673835278,-0.0002213587868027389,-0.011917279101908207 +1769682128,471462656,0.0,0.0,0.0,1.0,-1.991119461308699e-05,0.00021906106849201024,-0.001739697763696313,0.011376341804862022,-0.07552489638328552,-0.0031751336064189672 +1769682128,507758336,0.0,0.0,0.0,1.0,6.731403118465096e-05,0.00018711399752646685,-0.0017362928483635187,0.03768042474985123,0.005706482101231813,0.0029154084622859955 +1769682128,554980352,0.0,0.0,0.0,1.0,-2.002808469114825e-05,0.00020418960775714368,-0.0017318439204245806,-0.048924706876277924,0.06966011226177216,-0.008083109743893147 +1769682128,572884480,0.0,0.0,0.0,1.0,2.5906389055307955e-05,0.00018553023983258754,-0.0017179076094180346,0.011288758367300034,-0.07541225105524063,0.0027841099072247744 +1769682128,605774080,0.0,0.0,0.0,1.0,8.594294195063412e-05,0.0001770123199094087,-0.0016920572379603982,-4.030796844745055e-05,4.428512693266384e-05,0.0023834353778511286 +1769682128,650366464,0.0,0.0,0.0,1.0,0.00018139142775908113,0.0001640849222894758,-0.001671212026849389,-0.026341119781136513,-0.08117005974054337,-0.002514803782105446 +1769682128,673097984,0.0,0.0,0.0,1.0,0.00013701256830245256,0.00011767518299166113,-0.001639948575757444,-0.04887932911515236,0.06958284229040146,-0.011660141870379448 +1769682128,708559872,0.0,0.0,0.0,1.0,6.649376882705837e-05,0.00016406908980570734,-0.0015946169150993228,-0.03777928650379181,-0.005608445964753628,0.003042066004127264 +1769682128,749796864,0.0,0.0,0.0,1.0,9.488752402830869e-05,0.00018274695321451873,-0.0015740359667688608,-0.011329962871968746,0.07543119788169861,-0.0015941438032314181 +1769682128,771860224,0.0,0.0,0.0,1.0,3.355894659762271e-05,0.00015352439368143678,-0.0015460483264178038,0.026364557445049286,0.08113126456737518,0.00013081880751997232 +1769682128,805732608,0.0,0.0,0.0,1.0,0.0001230298075824976,0.00016156895435415208,-0.001523378537967801,-0.037596676498651505,-0.005813713185489178,-0.007683958858251572 +1769682128,849983488,0.0,0.0,0.0,1.0,4.2174528061877936e-05,0.0001884096855064854,-0.0015225232345983386,0.02651752345263958,0.08095680922269821,-0.009402976371347904 +1769682128,872113408,0.0,0.0,0.0,1.0,1.5895844626356848e-05,0.00016894296277314425,-0.0015261337393894792,-0.03773755952715874,-0.005662052426487207,0.0006576595478691161 +1769682128,906299648,0.0,0.0,0.0,1.0,4.8364337999373674e-05,0.00023271137615665793,-0.001563602825626731,0.0113294068723917,-0.07540605217218399,0.002786817029118538 +1769682128,953310208,0.0,0.0,0.0,1.0,-2.270598452014383e-05,0.00023057784710545093,-0.0016072823200374842,-0.00012140748731326312,0.00013294367818161845,0.00715038925409317 +1769682128,973181696,0.0,0.0,0.0,1.0,-6.29117275821045e-05,0.000121322475024499,-0.0016571343876421452,-0.00010120664956048131,0.00011076463852077723,0.005958579480648041 +1769682129,9169152,0.0,0.0,0.0,1.0,-0.00012768358283210546,5.856535426573828e-05,-0.0017105996375903487,-0.0264350026845932,-0.08103051781654358,0.005826716776937246 +1769682129,68503552,0.0,0.0,0.0,1.0,-3.191032010363415e-05,1.8051197912427597e-05,-0.0017423998797312379,0.04908169433474541,-0.06973104178905487,0.0021298392675817013 +1769682129,77847296,0.0,0.0,0.0,1.0,1.332340525550535e-05,-3.0401824915315956e-05,-0.0017608848866075277,0.037816595286130905,0.005586642771959305,-0.005423592869192362 +1769682129,106179072,0.0,0.0,0.0,1.0,2.0467945432756096e-05,-4.374987111077644e-05,-0.0017577281687408686,0.03771504759788513,0.0056993598118424416,0.0005349512211978436 +1769682129,149028096,0.0,0.0,0.0,1.0,1.3437640518532135e-05,-4.029043338960037e-06,-0.0017403245437890291,-0.00010124897380592301,0.00011073875066358596,0.005958579480648041 +1769682129,173148160,0.0,0.0,0.0,1.0,0.00011176894622622058,-5.014115959056653e-05,-0.0017108262982219458,-0.022887663915753365,0.15097925066947937,0.0039594462141394615 +1769682129,208470016,0.0,0.0,0.0,1.0,0.00022230682952795178,-8.719321158423554e-06,-0.001660339767113328,-0.01136790681630373,0.07540023326873779,-0.002787642879411578 +1769682129,248468480,0.0,0.0,0.0,1.0,0.0001228185137733817,0.00039201119216158986,-0.0016108202980831265,-0.03793656826019287,-0.005464504472911358,0.012573817744851112 +1769682129,271870976,0.0,0.0,0.0,1.0,0.00028200983069837093,0.0006444698083214462,-0.001583579578436911,-0.08698465675115585,0.06417962908744812,0.006866006646305323 +1769682129,306362624,0.0,0.0,0.0,1.0,0.00016395849524997175,0.0008785377140156925,-0.0015293981414288282,-4.0631894080433995e-05,4.435069058672525e-05,0.0023834286257624626 +1769682129,372595456,0.0,0.0,0.0,1.0,0.00023012535530142486,0.0010061373468488455,-0.0014943554997444153,-0.022806834429502487,0.15084005892276764,-0.003196961944922805 +1769682129,378826496,0.0,0.0,0.0,1.0,0.00021021973225288093,0.0011051301844418049,-0.0014508644817396998,-0.05252782627940178,-0.16235895454883575,-0.002646752167493105 +1769682129,404849408,0.0,0.0,0.0,1.0,0.00017446067067794502,0.0011729042744264007,-0.0014292061096057296,0.04908231273293495,-0.0696570947766304,0.0045241485349833965 +1769682129,449946880,0.0,0.0,0.0,1.0,0.00011441813694545999,0.0011170983780175447,-0.0014039394445717335,0.026461781933903694,0.08095978945493698,-0.010592611506581306 +1769682129,476844544,0.0,0.0,0.0,1.0,0.00015805818838998675,0.0010501521173864603,-0.0013770870864391327,-0.03771163523197174,-0.0057210722006857395,-0.000543461472261697 +1769682129,507228416,0.0,0.0,0.0,1.0,4.6928777010180056e-05,0.001008890918456018,-0.0013613152550533414,-0.049173805862665176,0.06973904371261597,0.00023663206957280636 +1769682129,548747776,0.0,0.0,0.0,1.0,0.00011221211752854288,0.0010016027372330427,-0.0013404694618657231,-0.022745463997125626,0.15072254836559296,-0.009164033457636833 +1769682129,571443200,0.0,0.0,0.0,1.0,7.751956582069397e-05,0.0009260271908715367,-0.0013243096182122827,-0.02634560689330101,-0.08107535541057587,0.004631809890270233 +1769682129,607863552,0.0,0.0,0.0,1.0,7.826832006685436e-05,0.000890907715074718,-0.0013123955577611923,0.00010346343333367258,-0.00011105919838882983,-0.005958535708487034 +1769682129,660630528,0.0,0.0,0.0,1.0,6.903217581566423e-05,0.0009055892005562782,-0.0013063607038930058,0.026400620117783546,0.081011101603508,-0.008205778896808624 +1769682129,671787520,0.0,0.0,0.0,1.0,5.759164196206257e-05,0.0009055426344275475,-0.001308843377046287,0.026314621791243553,0.08110098540782928,-0.0034384692553430796 +1769682129,706416640,0.0,0.0,0.0,1.0,4.714047827292234e-05,0.0008557525579817593,-0.0013322466984391212,0.00014560887939296663,-0.00015552421973552555,-0.008341935463249683 +1769682129,754501376,0.0,0.0,0.0,1.0,2.4342569304280914e-05,0.0009104216005653143,-0.0013525837566703558,-2.0834277165704407e-05,2.2220243408810347e-05,0.0011917045339941978 +1769682129,773877504,0.0,0.0,0.0,1.0,-6.269041477935389e-06,0.0008672188268974423,-0.0013687952887266874,0.037792742252349854,0.005646793637424707,-0.004213453736156225 +1769682129,806055168,0.0,0.0,0.0,1.0,0.00023872364545240998,0.0008842721581459045,-0.0013718532864004374,0.011471960693597794,-0.0754348486661911,0.00041555752977728844 +1769682129,849377792,0.0,0.0,0.0,1.0,0.00014834225294180214,0.0008902703411877155,-0.0013608136214315891,-0.022908197715878487,0.15082430839538574,-0.0032155970111489296 +1769682129,875398656,0.0,0.0,0.0,1.0,7.024556543910876e-05,0.0008422050159424543,-0.0013209307799115777,-0.02310502529144287,0.15102314949035645,0.007508147973567247 +1769682129,906379264,0.0,0.0,0.0,1.0,0.00019067707762587816,0.0004717277188319713,-0.001267065410502255,0.026079099625349045,0.0813317522406578,0.008481936529278755 +1769682129,952313088,0.0,0.0,0.0,1.0,0.00011527699825819582,0.0001970928133232519,-0.0012006836477667093,-0.011800039559602737,0.07576654106378555,0.017457451671361923 +1769682129,973698304,0.0,0.0,0.0,1.0,0.00035708333598449826,-9.707026038086042e-05,-0.0010870159603655338,0.06380103528499603,0.08705763518810272,0.00784726720303297 +1769682130,8850688,0.0,0.0,0.0,1.0,0.00021423297584988177,-0.00018209198606200516,-0.0009959365706890821,-0.026448186486959457,-0.08093418180942535,0.01297029573470354 +1769682130,48732928,0.0,0.0,0.0,1.0,0.00028350326465442777,-0.00024933842360042036,-0.0009085106430575252,-0.014806164428591728,-0.15652240812778473,0.0050488184206187725 +1769682130,72746496,0.0,0.0,0.0,1.0,0.0002445043355692178,-0.00027186068473383784,-0.0008343446534126997,8.399663056479767e-05,-8.910580072551966e-05,-0.004766801837831736 +1769682130,105718016,0.0,0.0,0.0,1.0,4.6468183427350596e-05,-0.00022163597168400884,-0.0007539288490079343,2.0988158212276176e-05,-2.2282360077952035e-05,-0.0011917005758732557 +1769682130,170824960,0.0,0.0,0.0,1.0,0.000168761340319179,-0.00017930618196260184,-0.00069975241785869,0.011603438295423985,-0.07554222643375397,-0.005537677556276321 +1769682130,179972864,0.0,0.0,0.0,1.0,3.7469391827471554e-05,0.00033192604314535856,-0.0006655670586042106,-0.03789558634161949,-0.00555146811529994,0.010168945416808128 +1769682130,206369280,0.0,0.0,0.0,1.0,8.477806113660336e-05,0.0009867498883977532,-0.0006611880380660295,-0.06073172762989998,0.14512991905212402,-0.00020842329831793904 +1769682130,248521472,0.0,0.0,0.0,1.0,-2.443383345962502e-05,0.0014724290231242776,-0.0006657936028204858,-0.11320362240076065,-0.017171604558825493,0.003090804908424616 +1769682130,278109952,0.0,0.0,0.0,1.0,2.6177400286542252e-05,0.0018532524118199944,-0.0006807985482737422,-0.026412146165966988,-0.08096130937337875,0.011778763495385647 +1769682130,307334912,0.0,0.0,0.0,1.0,5.81387103011366e-05,0.0020212724339216948,-0.0006895172991789877,0.02297172322869301,-0.15081430971622467,0.003231203183531761 +1769682130,349436672,0.0,0.0,0.0,1.0,0.00013331366062629968,0.0020188128110021353,-0.0007007128442637622,-0.04902302846312523,0.0694722831249237,-0.011715883389115334 +1769682130,371943424,0.0,0.0,0.0,1.0,0.00010703867155825719,0.0020007574930787086,-0.0007007785607129335,0.00012814727961085737,-0.00013385072816163301,-0.007150161080062389 +1769682130,411387136,0.0,0.0,0.0,1.0,0.0001852664427133277,0.0018883974989876151,-0.0006951509858481586,0.06398474425077438,0.0868554562330246,-0.004052169620990753 +1769682130,450676224,0.0,0.0,0.0,1.0,0.00018435427045915276,0.0018048655474558473,-0.0006833905354142189,-0.026299238204956055,-0.08107561618089676,0.0058136917650699615 +1769682130,472628992,0.0,0.0,0.0,1.0,5.4872572945896536e-05,0.0017654087860137224,-0.0006782484124414623,-0.07538903504610062,-0.011541496030986309,-0.0023415847681462765 +1769682130,506315520,0.0,0.0,0.0,1.0,0.00018998044834006578,0.001685380470007658,-0.0006563735660165548,0.08688417822122574,-0.06386201828718185,0.003968925215303898 +1769682130,556299008,0.0,0.0,0.0,1.0,0.00022486227680929005,0.0016582104144617915,-0.0006400401471182704,0.026316599920392036,0.0810549184679985,-0.00700230710208416 +1769682130,573087488,0.0,0.0,0.0,1.0,0.000207938501262106,0.0015977526782080531,-0.0006268362631089985,0.026097580790519714,0.08127883821725845,0.004915488883852959 +1769682130,606004736,0.0,0.0,0.0,1.0,4.983948383596726e-05,0.0015894972020760179,-0.0006005573668517172,-0.060595519840717316,0.14493483304977417,-0.009792574681341648 +1769682130,651429888,0.0,0.0,0.0,1.0,0.0002506278397049755,0.00163327157497406,-0.0005777395563200116,-0.011413655243813992,0.07531511783599854,-0.006393187213689089 +1769682130,680135680,0.0,0.0,0.0,1.0,0.00012071566743543372,0.0016501086065545678,-0.0005627473583444953,0.023115847259759903,-0.15092042088508606,-0.002703057136386633 +1769682130,705448448,0.0,0.0,0.0,1.0,0.0002459634270053357,0.0016323360614478588,-0.0005450777825899422,0.011393819004297256,-0.07529222220182419,0.007587072905153036 +1769682130,749203200,0.0,0.0,0.0,1.0,0.00015390040061902255,0.0016152929747477174,-0.000534784805495292,-4.4229822378838435e-05,4.4760134187527e-05,0.0023833569139242172 +1769682130,771888128,0.0,0.0,0.0,1.0,5.861672980245203e-05,0.0016612948384135962,-0.0005244782660156488,-0.02608676254749298,-0.08128196746110916,-0.0049211857840418816 +1769682130,806841088,0.0,0.0,0.0,1.0,0.00021355766511987895,0.0016543444944545627,-0.0004917657352052629,0.0262850821018219,0.08108098804950714,-0.005802917294204235 +1769682130,848870912,0.0,0.0,0.0,1.0,0.0001310785737587139,0.001281039323657751,-0.0004646692832466215,0.0108841797336936,-0.07477619498968124,0.03499945253133774 +1769682130,872473088,0.0,0.0,0.0,1.0,0.00012302192044444382,0.0006236053886823356,-0.0004300143918953836,0.025345122441649437,0.08202255517244339,0.04424864798784256 +1769682130,905477888,0.0,0.0,0.0,1.0,6.129438406787813e-05,2.6821122446563095e-05,-0.00038130831671878695,0.04876750707626343,-0.06918607652187347,0.02606569603085518 +1769682130,950472192,0.0,0.0,0.0,1.0,0.00012299083755351603,-0.00027619083994068205,-0.0003318164381198585,-0.049528200179338455,0.06994727998971939,0.014451156370341778 +1769682130,972484608,0.0,0.0,0.0,1.0,0.00013073396985419095,-0.00038470953586511314,-0.0003060447925236076,0.04926055669784546,-0.06967801600694656,-0.00015123008051887155 +1769682131,6371840,0.0,0.0,0.0,1.0,1.4126879250397906e-05,-0.00038340932223945856,-0.0002655418938957155,-2.2312315195449628e-05,2.24200794036733e-05,0.0011916740331798792 +1769682131,50773248,0.0,0.0,0.0,1.0,0.00011487884330563247,-0.0003682738752104342,-0.00023889711883384734,0.0001560909004183486,-0.00015697695198468864,-0.008341718465089798 +1769682131,73175040,0.0,0.0,0.0,1.0,3.1503054742643144e-06,-0.0002627887006383389,-0.0002183240867452696,-0.03754729777574539,-0.005927463062107563,-0.008938257582485676 +1769682131,107220736,0.0,0.0,0.0,1.0,0.00018623184587340802,-4.186328442301601e-05,-0.00019640197569970042,0.037747822701931,0.005725913215428591,-0.0017871075542643666 +1769682131,158266368,0.0,0.0,0.0,1.0,0.00011469117453088984,0.000795123225543648,-0.00018743763212114573,0.02276337519288063,-0.15053518116474152,0.017570510506629944 +1769682131,173870848,0.0,0.0,0.0,1.0,0.00015658076154068112,0.001476125093176961,-0.00017859571380540729,-0.011917968280613422,0.07580608874559402,0.01981423795223236 +1769682131,209767424,0.0,0.0,0.0,1.0,9.657073678681627e-05,0.0020231169182807207,-0.00015963075566105545,0.026029877364635468,0.08133066445589066,0.0073054940439760685 +1769682135,206176768,0.0,0.0,0.0,1.0,0.00010796443530125543,0.0006270327139645815,0.00014319349429570138,0.0,-0.0,0.0 +1769682135,268644352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682135,278599168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682135,305750016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682135,353288192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682135,373659648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.517884710570797e-05,4.617815648089163e-05,0.0023831031285226345 +1769682135,406767872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682135,463384576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682135,469104640,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,2.7589378078118898e-05,-2.308908005943522e-05,-0.0011915515642613173 +1769682135,508369920,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682135,555499264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-2.7589347155299038e-05,2.308908551640343e-05,0.0011915515642613173 +1769682135,573111552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682135,605796352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.517862882697955e-05,-4.617817103280686e-05,-0.0023831031285226345 +1769682135,652794368,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682135,672740608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.5178570619318634e-05,4.617818194674328e-05,0.0023831031285226345 +1769682135,705798912,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682135,748889088,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-2.7589252567850053e-05,2.3089083697414026e-05,0.0011915515642613173 +1769682135,773230336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682135,808034560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682135,871100928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682135,876546816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.5178345064632595e-05,4.6178163756849244e-05,0.0023831031285226345 +1769682135,906259456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,2.7589145247475244e-05,-2.3089081878424622e-05,-0.0011915515642613173 +1769682135,950782976,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682135,977829632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682136,8216576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682136,51127552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682136,72933888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.517801037058234e-05,-4.6178189222700894e-05,-0.0023831031285226345 +1769682136,106181376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682136,161505280,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682136,173460224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,2.7588914235820994e-05,-2.3089100068318658e-05,-0.0011915515642613173 +1769682136,206231040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-2.7588879675022326e-05,2.3089100068318658e-05,0.0011915515642613173 +1769682136,255074048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.517769022844732e-05,-4.617820741259493e-05,-0.0023831031285226345 +1769682136,273503744,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.517765384865925e-05,-4.617820741259493e-05,-0.0023831031285226345 +1769682136,307613952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.517758472706191e-05,4.6178211050573736e-05,0.0023831031285226345 +1769682136,351697408,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682136,380146176,0.0,0.0,0.0,1.0,-0.003983581438660622,-0.0015931444941088557,-0.00011476226791273803,-0.08732053637504578,0.06426568329334259,0.01582440175116062 +1769682136,407035904,0.0,0.0,0.0,1.0,-0.003801055485382676,-0.011262516491115093,-0.0004280477296561003,-0.10950096696615219,0.06417102366685867,0.1608433723449707 +1769682136,452483072,0.0,0.0,0.0,1.0,-0.0029165290761739016,-0.019499847665429115,-0.0007668595644645393,-0.3155055046081543,0.03140956163406372,0.09966851770877838 +1769682136,472954624,0.0,0.0,0.0,1.0,-0.001950010540895164,-0.02224811539053917,-0.001034882152453065,-0.5666674375534058,-0.08537005633115768,0.04057762026786804 +1769682136,511994880,0.0,0.0,0.0,1.0,-0.0007911009015515447,-0.020171500742435455,-0.0013165404088795185,-0.7391451597213745,0.04122927784919739,-0.025767242535948753 +1769682136,545243904,0.0,0.0,0.0,1.0,0.0001714335521683097,-0.014796840026974678,-0.0015436095418408513,-0.7501024603843689,0.1160726547241211,-0.05433288589119911 +1769682136,572322816,0.0,0.0,0.0,1.0,0.0004817940352950245,-0.011758972890675068,-0.0016444862121716142,-0.7614466547966003,0.19129499793052673,-0.06414518505334854 +1769682136,606430976,0.0,0.0,0.0,1.0,0.0010489663109183311,-0.00605389941483736,-0.0018127358052879572,-0.7685048580169678,0.11263658106327057,-0.07924744486808777 +1769682136,655677696,0.0,0.0,0.0,1.0,0.0013418832095339894,-0.002770002232864499,-0.0019147454295307398,-0.7194535136222839,0.043088797479867935,-0.06972961127758026 +1769682136,674328832,0.0,0.0,0.0,1.0,0.0013761221198365092,-0.00024819886311888695,-0.002007385017350316,-0.6630880236625671,0.05187777429819107,-0.05923731252551079 +1769682136,706199296,0.0,0.0,0.0,1.0,0.001376227824948728,0.001978240441530943,-0.00210975157096982,-0.6747223734855652,0.12733463943004608,-0.054981160908937454 +1769682136,739168768,0.0,0.0,0.0,1.0,0.0012484518811106682,0.0022605464328080416,-0.0021844429429620504,-0.6145681142807007,-0.017168141901493073,-0.021273255348205566 +1769682136,775657216,0.0,0.0,0.0,1.0,0.001017567701637745,0.000788830395322293,-0.002314104000106454,-0.5889781713485718,0.06452392786741257,0.00744234211742878 +1769682136,807176704,0.0,0.0,0.0,1.0,0.0007448052638210356,-0.0003673793689813465,-0.002409970387816429,-0.6340495347976685,-0.019541358575224876,0.010553297586739063 +1769682136,843711488,0.0,0.0,0.0,1.0,0.0006599900661967695,-0.0009925569174811244,-0.0024969272781163454,-0.6036583781242371,-0.09209422767162323,0.012560766190290451 +1769682136,872548352,0.0,0.0,0.0,1.0,0.0004903869703412056,-0.001925224787555635,-0.0026019783690571785,-0.6381906270980835,0.13395828008651733,0.002793530933558941 +1769682136,908998144,0.0,0.0,0.0,1.0,0.00028354726964607835,-0.0029881629161536694,-0.002749799285084009,-0.71369469165802,0.1224023774266243,0.006375427357852459 +1769682136,956275712,0.0,0.0,0.0,1.0,0.00018322055984754115,-0.003701108507812023,-0.002867826260626316,-0.721160352230072,0.04420994222164154,0.01615723967552185 +1769682136,974583040,0.0,0.0,0.0,1.0,4.1672406950965524e-05,-0.004307618830353022,-0.0029950274620205164,-0.716763436794281,-0.10965389758348465,0.013330213725566864 +1769682137,6374400,0.0,0.0,0.0,1.0,-6.229435530258343e-05,-0.004180125426501036,-0.003148820949718356,-0.7772995233535767,0.034942373633384705,-0.00599246472120285 +1769682137,60358144,0.0,0.0,0.0,1.0,-7.535910117439926e-05,-0.003919695969671011,-0.0033057399559766054,-0.7845040559768677,-0.043521638959646225,-0.008075140416622162 +1769682137,68318976,0.0,0.0,0.0,1.0,-5.0949322030646726e-05,-0.0038097198121249676,-0.0033858988899737597,-0.8074991703033447,0.1070232093334198,-0.020887941122055054 +1769682137,107492096,0.0,0.0,0.0,1.0,-5.255891301203519e-05,-0.003977248445153236,-0.0035599772818386555,-0.8529077172279358,0.023258963599801064,0.0038483310490846634 +1769682137,152023808,0.0,0.0,0.0,1.0,-0.00022330251522362232,-0.004023985471576452,-0.00369097082875669,-0.909165620803833,0.014140542596578598,-0.012424214743077755 +1769682137,181085184,0.0,0.0,0.0,1.0,-0.00012445097672753036,-0.0037480820901691914,-0.003848482621833682,-0.9323458075523376,0.16470491886138916,-0.0191861130297184 +1769682137,208863232,0.0,0.0,0.0,1.0,-8.386594709008932e-05,-0.003322738455608487,-0.003957120701670647,-0.8786951303482056,-0.05857395380735397,-0.010237008333206177 +1769682137,252887808,0.0,0.0,0.0,1.0,-0.00010646534792613238,-0.003440727712586522,-0.004082832485437393,-0.9280877709388733,0.010938117280602455,-0.008811533451080322 +1769682137,273435904,0.0,0.0,0.0,1.0,-0.00011006544809788465,-0.003324884455651045,-0.004192446358501911,-0.9585207104682922,0.08321617543697357,-0.014237632043659687 +1769682137,310188032,0.0,0.0,0.0,1.0,-2.4624903744552284e-05,-0.002468372229486704,-0.004310763906687498,-0.9610278010368347,-0.1491578221321106,-0.021639598533511162 +1769682137,352156416,0.0,0.0,0.0,1.0,-3.928314981749281e-05,-0.0022413244005292654,-0.00439868401736021,-0.9281805157661438,0.01063396967947483,-0.0037837326526641846 +1769682137,373305088,0.0,0.0,0.0,1.0,5.833989416714758e-05,-0.0012449747882783413,-0.004450461361557245,-1.0146902799606323,0.0735836774110794,-0.037504203617572784 +1769682137,406407936,0.0,0.0,0.0,1.0,0.000189193116966635,0.0002371571899857372,-0.004495067521929741,-0.9653823971748352,0.00395691953599453,-0.031697794795036316 +1769682137,450761984,0.0,0.0,0.0,1.0,9.356149530503899e-05,0.0007851589471101761,-0.00451604463160038,-0.965639054775238,0.004100808873772621,-0.017416736111044884 +1769682137,473907712,0.0,0.0,0.0,1.0,0.00027839874383062124,0.0023566982708871365,-0.004491198342293501,-0.8970900177955627,-0.06291493028402328,-0.03164035081863403 +1769682137,507447552,0.0,0.0,0.0,1.0,0.00036670485860668123,0.004526521544903517,-0.004412050824612379,-0.8947312831878662,0.1690683662891388,-0.0278521329164505 +1769682137,539924992,0.0,0.0,0.0,1.0,0.00044560752576217055,0.004873557481914759,-0.004346319939941168,-0.8456240296363831,0.09978793561458588,-0.009058443829417229 +1769682137,573205504,0.0,0.0,0.0,1.0,0.00039493030635640025,0.003555918112397194,-0.004299016669392586,-0.8459874391555786,0.10004537552595139,0.009901254437863827 +1769682137,608945152,0.0,0.0,0.0,1.0,0.0002968914923258126,0.001137261395342648,-0.004251035396009684,-0.8459612131118774,0.09985523670911789,0.007448170334100723 +1769682137,639890688,0.0,0.0,0.0,1.0,0.0001878128678072244,-0.0002402140380581841,-0.004200358875095844,-0.8155161738395691,0.02749619260430336,0.017746055498719215 +1769682137,673739264,0.0,0.0,0.0,1.0,0.00015868362970650196,-0.0010531431762501597,-0.0041071888990700245,-0.8647432327270508,0.09656387567520142,0.0024102237075567245 +1769682137,706749184,0.0,0.0,0.0,1.0,0.00018863372679334134,-0.0017284239875152707,-0.00404451135545969,-0.859951376914978,-0.057283416390419006,0.001920357346534729 +1769682137,758165248,0.0,0.0,0.0,1.0,0.00013816298451274633,-0.002024913439527154,-0.003975261468440294,-0.9024695754051208,0.09046368300914764,0.0031101349741220474 +1769682137,772513024,0.0,0.0,0.0,1.0,0.00021389484754763544,-0.0010178163647651672,-0.003867452498525381,-0.9277595281600952,0.008463559672236443,-0.0279336329549551 +1769682137,806862592,0.0,0.0,0.0,1.0,0.00028571367147378623,0.0005394851323217154,-0.0036851223558187485,-0.87828129529953,-0.06108318269252777,-0.02449434995651245 +1769682137,851207168,0.0,0.0,0.0,1.0,0.00028278594254516065,0.0011669276282191277,-0.003506967332214117,-0.8339584469795227,0.023428332060575485,-0.005076766014099121 +1769682137,872945152,0.0,0.0,0.0,1.0,0.0002492508210707456,0.0008100762497633696,-0.0034202635288238525,-0.871726393699646,0.017530813813209534,-0.0009052380919456482 +1769682137,907435776,0.0,0.0,0.0,1.0,0.00023405480897054076,0.0004380708560347557,-0.003245958825573325,-0.8527357578277588,0.020222926512360573,-0.008975177071988583 +1769682137,969116928,0.0,0.0,0.0,1.0,0.00018715739133767784,-4.637853999156505e-05,-0.0031215560156852007,-0.8716422319412231,0.017240630462765694,-0.005694274324923754 +1769682137,979914752,0.0,0.0,0.0,1.0,0.000169770501088351,-0.0003348016180098057,-0.0029581009875983,-0.8953059315681458,0.16776087880134583,-0.012607649900019169 +1769682138,10613248,0.0,0.0,0.0,1.0,0.00020037942158523947,-0.0003546451043803245,-0.002832273952662945,-0.8834283351898193,0.0923142284154892,-0.012115865014493465 +1769682138,57497600,0.0,0.0,0.0,1.0,0.00022909065592102706,-0.00021904753521084785,-0.0026927320286631584,-0.8409332633018494,-0.05538124218583107,-0.003703285939991474 +1769682138,73588992,0.0,0.0,0.0,1.0,0.0002272071287734434,-0.0001957396016223356,-0.0025469984393566847,-0.8715608716011047,0.01682836189866066,-0.010429727844893932 +1769682138,112862720,0.0,0.0,0.0,1.0,0.0002181228919653222,-0.00018285853730048984,-0.0023299166932702065,-0.8528351783752441,0.019838456064462662,-0.004175576381385326 +1769682138,149309952,0.0,0.0,0.0,1.0,0.00023868477728683501,-0.0002253524580737576,-0.002171281957998872,-0.8972771763801575,-0.06468621641397476,-0.012895639054477215 +1769682138,174433024,0.0,0.0,0.0,1.0,0.00022002402693033218,-0.00030263341614045203,-0.0020063493866473436,-0.90934818983078,0.010784287005662918,-0.005031176842749119 +1769682138,208907776,0.0,0.0,0.0,1.0,0.00023212541418615729,-7.745484617771581e-05,-0.0017836976330727339,-0.8972685933113098,-0.0648089349269867,-0.012880783528089523 +1769682138,274003456,0.0,0.0,0.0,1.0,0.00018357340013608336,-3.692875543492846e-05,-0.001625186763703823,-0.878450870513916,-0.0618472620844841,-0.0113991629332304 +1769682138,281123072,0.0,0.0,0.0,1.0,0.00013385276542976499,0.0002514767402317375,-0.0014144995948299766,-0.8595128655433655,-0.05903211236000061,-0.017072021961212158 +1769682138,306526208,0.0,0.0,0.0,1.0,0.0001535195333417505,0.0004048720293212682,-0.0012490252265706658,-0.9212008118629456,0.08585023880004883,-0.010291272774338722 +1769682138,339412480,0.0,0.0,0.0,1.0,0.0001910420396598056,0.00046355099766515195,-0.0010834040585905313,-0.9093508720397949,0.010549364611506462,-0.005050265230238438 +1769682138,374392576,0.0,0.0,0.0,1.0,0.00015272195741999894,0.0002242952468805015,-0.0009289683657698333,-0.897254228591919,-0.06500029563903809,-0.012911956757307053 +1769682138,408961536,0.0,0.0,0.0,1.0,0.0001275532995350659,-0.00011749298573704436,-0.0007288481574505568,-0.9093955159187317,0.010539468377828598,-0.002673730254173279 +1769682138,454582016,0.0,0.0,0.0,1.0,0.00017287168884649873,-0.00015126238577067852,-0.0005815734621137381,-0.9212110042572021,0.08574727177619934,-0.010308375582098961 +1769682138,473248256,0.0,0.0,0.0,1.0,0.00016056661843322217,-3.341323463246226e-05,-0.0004312925157137215,-0.8785682916641235,-0.06190945580601692,-0.004272026009857655 +1769682138,509086464,0.0,0.0,0.0,1.0,0.00013756526459474117,0.00029909811564721167,-0.0002317432372365147,-0.9024210572242737,0.08875425159931183,-0.007639783434569836 +1769682138,556420864,0.0,0.0,0.0,1.0,0.0002212922991020605,0.0003972066624555737,-8.148492634063587e-05,-0.8783471584320068,-0.0621548667550087,-0.016203779727220535 +1769682138,575136768,0.0,0.0,0.0,1.0,0.00019880011677742004,0.0004819643800146878,6.401529390132055e-05,-0.8525805473327637,0.01913636177778244,-0.018508993089199066 +1769682138,607512832,0.0,0.0,0.0,1.0,0.00021578946325462312,0.0004834278079215437,0.0002621360763441771,-0.8785235285758972,-0.06196308508515358,-0.006698275450617075 +1769682138,655717120,0.0,0.0,0.0,1.0,0.00019869129755534232,0.0005067564197815955,0.0004573076730594039,-0.8458012342453003,0.09761983156204224,-0.012785034254193306 +1769682138,672186112,0.0,0.0,0.0,1.0,0.00012892132508568466,0.0006078579463064671,0.0005492763011716306,-0.9024398922920227,0.08880408108234406,-0.006517909932881594 +1769682138,706640128,0.0,0.0,0.0,1.0,0.00018937760614790022,0.0006727962754666805,0.0007284195744432509,-0.8477902412414551,-0.13424457609653473,-0.003578939475119114 +1769682138,755239936,0.0,0.0,0.0,1.0,0.00018347382138017565,0.0007307165651582181,0.0008540830458514392,-0.8527098894119263,0.01934657245874405,-0.01144260074943304 +1769682138,780961280,0.0,0.0,0.0,1.0,0.00013156005297787488,0.0007722439477220178,0.001016068970784545,-0.9261336326599121,0.2394225150346756,-0.01711316965520382 +1769682138,807920384,0.0,0.0,0.0,1.0,0.00019022861670237035,0.0008137416443787515,0.0011330277193337679,-0.9140549302101135,0.16395160555839539,-0.02379056252539158 +1769682138,841831936,0.0,0.0,0.0,1.0,0.00016438576858490705,0.0007979893125593662,0.0012447494082152843,-0.8220028877258301,-0.052870284765958786,-0.007144221570342779 +1769682138,872576000,0.0,0.0,0.0,1.0,0.0001674197119427845,0.0007547397399321198,0.0013571740128099918,-0.8408856987953186,-0.05577550828456879,-0.005073236767202616 +1769682138,908722688,0.0,0.0,0.0,1.0,0.00011251328396610916,0.0007291542715393007,0.0014935916988179088,-0.8100137114524841,-0.128223717212677,-0.010262991301715374 +1769682138,944224768,0.0,0.0,0.0,1.0,0.00020694492559414357,0.0008542549912817776,0.0016273504588752985,-0.8031964302062988,-0.04973338544368744,-0.00572527851909399 +1769682138,973081344,0.0,0.0,0.0,1.0,0.00016116378537844867,0.0008919452666305006,0.0016952779842540622,-0.8457403779029846,0.09790278226137161,-0.014183010905981064 +1769682139,6284288,0.0,0.0,0.0,1.0,0.00019313901429995894,0.0009179974440485239,0.0018126923823729157,-0.8456881642341614,0.09791605919599533,-0.016597826033830643 +1769682139,55278080,0.0,0.0,0.0,1.0,0.00018378871027380228,0.0009152964339591563,0.0018967625219374895,-0.7962770462036133,0.028740569949150085,-0.00599499000236392 +1769682139,73756160,0.0,0.0,0.0,1.0,0.00015344779239967465,0.000981335761025548,0.001983488444238901,-0.8268836140632629,0.10103710740804672,-0.013965873047709465 +1769682139,106530304,0.0,0.0,0.0,1.0,0.00014365723473019898,0.0010979382786899805,0.0020961035043001175,-0.8267397880554199,0.10096538811922073,-0.021151229739189148 +1769682139,139432448,0.0,0.0,0.0,1.0,0.0001600693358341232,0.0010180753888562322,0.002176156733185053,-0.8151082396507263,0.025928925722837448,-0.0063744657672941685 +1769682139,175528192,0.0,0.0,0.0,1.0,0.0002226895885542035,0.0008980751154012978,0.0022605638951063156,-0.8150837421417236,0.02596021443605423,-0.007589332293719053 +1769682139,208233472,0.0,0.0,0.0,1.0,0.0001882710203062743,0.0008345009991899133,0.002361510181799531,-0.7771562337875366,0.03172377124428749,-0.02012644335627556 +1769682139,251500544,0.0,0.0,0.0,1.0,0.00026474351761862636,0.0009555737487971783,0.0024377552326768637,-0.770395815372467,0.11033163219690323,-0.009629510343074799 +1769682139,272984576,0.0,0.0,0.0,1.0,0.0001968997239600867,0.0011158334091305733,0.002506860066205263,-0.7843667268753052,-0.04624767601490021,-0.0068584345281124115 +1769682139,307121408,0.0,0.0,0.0,1.0,0.00019165550475008786,0.0011002154788002372,0.0025762354489415884,-0.7961667776107788,0.02913595549762249,-0.010975442826747894 +1769682139,356473856,0.0,0.0,0.0,1.0,9.282621613238007e-05,0.0010616716463118792,0.002626184606924653,-0.746559739112854,-0.040314674377441406,-0.013464333489537239 +1769682139,374838784,0.0,0.0,0.0,1.0,0.00015079317381605506,0.0009930426022037864,0.002683867234736681,-0.7584361433982849,0.03516388684511185,-0.012812684290111065 +1769682139,406447872,0.0,0.0,0.0,1.0,0.00010986431880155578,0.0010260379640385509,0.002721223747357726,-0.758478581905365,0.03527206927537918,-0.01045250054448843 +1769682139,453388032,0.0,0.0,0.0,1.0,0.00012910242367070168,0.0009334750939160585,0.0027540731243789196,-0.7892213463783264,0.1078215092420578,-0.007714180741459131 +1769682139,473722624,0.0,0.0,0.0,1.0,9.728535223985091e-05,0.0008638942381367087,0.00279400497674942,-0.7772665619850159,0.032391779124736786,-0.01318177580833435 +1769682139,510251520,0.0,0.0,0.0,1.0,0.0001658405817579478,0.0009998611640185118,0.002846818882972002,-0.7702674269676208,0.11083998531103134,-0.01222765538841486 +1769682139,567262976,0.0,0.0,0.0,1.0,0.00014709346578456461,0.0011427131248638034,0.002886839909479022,-0.689988374710083,-0.031106527894735336,-0.016269216313958168 +1769682139,576922880,0.0,0.0,0.0,1.0,0.00015558782615698874,0.001237814431078732,0.002937430515885353,-0.7397337555885315,0.038707174360752106,-0.004321551416069269 +1769682139,608261120,0.0,0.0,0.0,1.0,0.0001887259422801435,0.0012022764421999454,0.0029707869980484247,-0.7255566716194153,0.19534935057163239,-0.009531490504741669 +1769682139,653533184,0.0,0.0,0.0,1.0,0.00014852717868052423,0.001206460758112371,0.0029961769469082355,-0.7018356323242188,0.044528208673000336,-0.014485102146863937 +1769682139,672922112,0.0,0.0,0.0,1.0,0.00014297878078650683,0.0011294230353087187,0.0030215755105018616,-0.7395377159118652,0.038718730211257935,-0.013933783397078514 +1769682139,708724992,0.0,0.0,0.0,1.0,0.0001247843320015818,0.0010234862565994263,0.003039705567061901,-0.6760810017585754,0.12611928582191467,-0.006097795441746712 +1769682139,758487040,0.0,0.0,0.0,1.0,0.00015682046068832278,0.0009311342728324234,0.0030533745884895325,-0.6783747673034668,-0.1059212014079094,-0.008762801997363567 +1769682139,768467456,0.0,0.0,0.0,1.0,0.0001566702703712508,0.0009187760297209024,0.003052009269595146,-0.6641772389411926,0.05073659121990204,-0.01157616637647152 +1769682139,806728960,0.0,0.0,0.0,1.0,0.0001097297717933543,0.0011283657513558865,0.0030569215305149555,-0.7135880589485168,0.12030471861362457,-0.013937941752374172 +1769682139,855738112,0.0,0.0,0.0,1.0,0.00012149449321441352,0.0011726892553269863,0.0030560349114239216,-0.6596531867980957,-0.10270262509584427,-0.0037485011853277683 +1769682139,874114560,0.0,0.0,0.0,1.0,0.0001550842571305111,0.0011841984232887626,0.003058303613215685,-0.6829572319984436,0.047955937683582306,-0.014347371645271778 +1769682139,906727680,0.0,0.0,0.0,1.0,0.00012017488188575953,0.0012095231795683503,0.003051202744245529,-0.6571118235588074,0.12941953539848328,-0.008318589068949223 +1769682139,940334848,0.0,0.0,0.0,1.0,0.0001437688188161701,0.0011731716804206371,0.0030458495020866394,-0.6264604330062866,0.056946560740470886,-0.011080807074904442 +1769682139,979224320,0.0,0.0,0.0,1.0,0.00011412664025556296,0.0011700238101184368,0.0030235194135457277,-0.6782214045524597,0.20349079370498657,-0.009054300375282764 +1769682140,10031616,0.0,0.0,0.0,1.0,0.00010213644418399781,0.0011671371757984161,0.003001491306349635,-0.6147858500480652,-0.018271874636411667,-0.00822452548891306 +1769682140,52047616,0.0,0.0,0.0,1.0,0.00011721358896465972,0.0012594128493219614,0.0029897617641836405,-0.6263001561164856,0.056994274258613586,-0.01830468513071537 +1769682140,74118656,0.0,0.0,0.0,1.0,9.073915134649724e-05,0.0012923028552904725,0.0029629990458488464,-0.6288705468177795,0.13423652946949005,-0.003213491290807724 +1769682140,107696896,0.0,0.0,0.0,1.0,8.464639540761709e-05,0.0013371624518185854,0.0029500385280698538,-0.5937285423278809,-0.09198199957609177,-0.005233812611550093 +1769682140,145931520,0.0,0.0,0.0,1.0,0.00016231661720667034,0.001321930903941393,0.0029322162736207247,-0.6286523342132568,0.13417813181877136,-0.012805618345737457 +1769682140,173316352,0.0,0.0,0.0,1.0,0.00011551647912710905,0.0012552258558571339,0.002925548702478409,-0.6170673966407776,0.05891156196594238,-0.007527616340667009 +1769682140,208838400,0.0,0.0,0.0,1.0,0.00018309189181309193,0.0011743434006348252,0.0029234790708869696,-0.5931760668754578,0.21698683500289917,-0.012583325617015362 +1769682140,254802944,0.0,0.0,0.0,1.0,0.00010577603825367987,0.0012425276217982173,0.002919059945270419,-0.6215939521789551,0.2128295600414276,-0.004745050799101591 +1769682140,274500352,0.0,0.0,0.0,1.0,0.00011642183380899951,0.00129184580873698,0.002912735566496849,-0.6215033531188965,0.21281324326992035,-0.00834488682448864 +1769682140,307814656,0.0,0.0,0.0,1.0,6.761511758668348e-05,0.0013381644384935498,0.002895441371947527,-0.5352129340171814,-0.1595749706029892,0.005487145856022835 +1769682140,349155584,0.0,0.0,0.0,1.0,0.00012066788622178137,0.0012855872046202421,0.0028790005017071962,-0.5583056807518005,-0.008898915722966194,-0.005130622535943985 +1769682140,379971840,0.0,0.0,0.0,1.0,6.825744640082121e-05,0.0012423942098394036,0.0028505679219961166,-0.5351249575614929,-0.1595851331949234,-0.0005179215222597122 +1769682140,409790208,0.0,0.0,0.0,1.0,0.00010950813884846866,0.001164030283689499,0.002821466652676463,-0.5488105416297913,-0.007404997944831848,-0.008591446094214916 +1769682140,454160384,0.0,0.0,0.0,1.0,4.271926445653662e-05,0.0010834732092916965,0.0027903816662728786,-0.5700668096542358,0.06681296229362488,0.0014177234843373299 +1769682140,474836480,0.0,0.0,0.0,1.0,4.757502756547183e-05,0.0009660697542130947,0.0027499860152602196,-0.5320717096328735,0.07239919900894165,-0.012252843007445335 +1769682140,509142272,0.0,0.0,0.0,1.0,8.794839231995866e-05,0.0008461151155643165,0.002707005012780428,-0.513313889503479,0.07543836534023285,-0.007174408063292503 +1769682140,544544512,0.0,0.0,0.0,1.0,8.36649996927008e-05,0.0006792239146307111,0.0026476895436644554,-0.5227786302566528,0.0740906372666359,-0.004970065783709288 +1769682140,572817152,0.0,0.0,0.0,1.0,5.533524017664604e-05,0.0006490415544249117,0.0026183100417256355,-0.5321507453918457,0.07262169569730759,-0.007523564156144857 +1769682140,608681216,0.0,0.0,0.0,1.0,2.7584912459133193e-05,0.0007445151568390429,0.002572174184024334,-0.4879303276538849,-0.1521749645471573,-0.008147701621055603 +1769682140,654484736,0.0,0.0,0.0,1.0,6.370688788592815e-05,0.0007916923495940864,0.0025364134926348925,-0.5131900906562805,0.0755181834101677,-0.011989433318376541 +1769682140,675808000,0.0,0.0,0.0,1.0,3.389179255464114e-05,0.0007774002151563764,0.0024812694173306227,-0.5112360119819641,-0.0011079348623752594,-0.002099737524986267 +1769682140,706533888,0.0,0.0,0.0,1.0,7.391862163785845e-05,0.0007686672615818679,0.002437766408547759,-0.49228811264038086,0.0017270762473344803,-0.0065484498627483845 +1769682140,749674752,0.0,0.0,0.0,1.0,2.9656599508598447e-05,0.0007450912380591035,0.002385537140071392,-0.4850662350654602,0.0801452174782753,-0.003193426411598921 +1769682140,778254848,0.0,0.0,0.0,1.0,3.3254629670409486e-05,0.0006848177290521562,0.0023145212326198816,-0.4736083149909973,0.0048627303913235664,0.0020981524139642715 +1769682140,808084480,0.0,0.0,0.0,1.0,5.145765680936165e-05,0.0006954226410016418,0.0022551645524799824,-0.47336292266845703,0.004658995196223259,-0.009827487170696259 +1769682140,843429376,0.0,0.0,0.0,1.0,4.2434603528818116e-05,0.0007034974405542016,0.0021979426965117455,-0.47350960969924927,0.004832153208553791,-0.002687727101147175 +1769682140,872866048,0.0,0.0,0.0,1.0,7.01480166753754e-05,0.0007572080940008163,0.002143296878784895,-0.49645280838012695,0.15559419989585876,-0.009735798463225365 +1769682140,908909056,0.0,0.0,0.0,1.0,5.998877895763144e-05,0.0007732292870059609,0.002076164586469531,-0.45668473839759827,0.0845823884010315,-0.006330257281661034 +1769682140,961595136,0.0,0.0,0.0,1.0,8.815506589598954e-05,0.0007734508253633976,0.0020294850692152977,-0.45458295941352844,0.007742890156805515,-0.005966258235275745 +1769682140,970416384,0.0,0.0,0.0,1.0,8.051586337387562e-05,0.0007338650757446885,0.0019935511518269777,-0.4565756022930145,0.08454330265522003,-0.01111752912402153 +1769682141,6811136,0.0,0.0,0.0,1.0,0.00012629244884010404,0.0006498581496998668,0.0019464032957330346,-0.43776601552963257,0.08750592172145844,-0.008413569070398808 +1769682141,56705024,0.0,0.0,0.0,1.0,0.00011070035543525591,0.0005784814129583538,0.0019074123119935393,-0.4377344250679016,0.08751591295003891,-0.009615685790777206 +1769682141,73560832,0.0,0.0,0.0,1.0,4.6500957978423685e-05,0.0005354955792427063,0.0018893418600782752,-0.42630207538604736,0.012174098752439022,-0.005503435153514147 +1769682141,108634880,0.0,0.0,0.0,1.0,5.326849714037962e-05,0.00042022307752631605,0.0018593487329781055,-0.43557897210121155,0.010626141913235188,-0.012827647849917412 +1769682141,141266176,0.0,0.0,0.0,1.0,9.072174725588411e-05,0.00045681872870773077,0.0018451000796630979,-0.39804619550704956,0.016565702855587006,-0.0038234416861087084 +1769682141,174512384,0.0,0.0,0.0,1.0,0.00013613754708785564,0.00042626261711120605,0.0018295291811227798,-0.4209250807762146,0.16736173629760742,-0.009682411327958107 +1769682141,207034112,0.0,0.0,0.0,1.0,9.539058373775333e-05,0.0004762874450534582,0.0018116772407665849,-0.39177364110946655,-0.2140837162733078,-0.007473836187273264 +1769682141,251878912,0.0,0.0,0.0,1.0,0.00011312911374261603,0.0005385284894146025,0.0017996678361669183,-0.3659054934978485,-0.13255535066127777,0.009329341351985931 +1769682141,273235968,0.0,0.0,0.0,1.0,3.225976615794934e-05,0.0005805269465781748,0.0017778802430257201,-0.4074438214302063,0.015200464986264706,-0.005209134425967932 +1769682141,311072000,0.0,0.0,0.0,1.0,5.3316827688831836e-05,0.0007168113952502608,0.0017503082053735852,-0.39385467767715454,-0.13714508712291718,-0.007872316986322403 +1769682141,350669568,0.0,0.0,0.0,1.0,-7.278133853105828e-05,0.0007810314418748021,0.0017028757138177752,-0.41850993037223816,0.09030625224113464,-0.024839947000145912 +1769682141,374333696,0.0,0.0,0.0,1.0,2.983952253998723e-05,0.0008507220190949738,0.001648270757868886,-0.42066478729248047,0.16731466352939606,-0.019269680604338646 +1769682141,409253120,0.0,0.0,0.0,1.0,-4.6799446863587946e-05,0.0008743164944462478,0.0015666797989979386,-0.4301303029060364,0.16595588624477386,-0.017069481313228607 +1769682141,456752640,0.0,0.0,0.0,1.0,4.512887971941382e-05,0.0008966780733317137,0.0015076696872711182,-0.3997891843318939,0.0933803841471672,-0.01738804578781128 +1769682141,474422016,0.0,0.0,0.0,1.0,4.215843364363536e-05,0.0009009635541588068,0.0014549961779266596,-0.34162309765815735,0.025529250502586365,0.004248687997460365 +1769682141,506940160,0.0,0.0,0.0,1.0,2.7556323402677663e-05,0.0008091863710433245,0.0014254441484808922,-0.3698284327983856,0.021177999675273895,0.0001564333215355873 +1769682141,543975936,0.0,0.0,0.0,1.0,0.00010720090358518064,0.0007854755385778844,0.001408684067428112,-0.36037495732307434,0.02260628715157509,-0.0008771633729338646 +1769682141,573416192,0.0,0.0,0.0,1.0,9.120481263380498e-05,0.0007500730571337044,0.0014073813799768686,-0.3697513937950134,0.02113821730017662,-0.003435986815020442 +1769682141,606984192,0.0,0.0,0.0,1.0,0.00012603271170519292,0.0007349586812779307,0.0014144330052658916,-0.34881171584129333,-0.052921220660209656,-0.006302608642727137 +1769682141,639943936,0.0,0.0,0.0,1.0,0.00012621242785826325,0.00042861478868871927,0.0014293689746409655,-0.3599948585033417,0.022296667098999023,-0.01877327263355255 +1769682141,684148480,0.0,0.0,0.0,1.0,0.00011410027946112677,0.00012855140084866434,0.0014414455508813262,-0.33381372690200806,0.10356538742780685,-0.013876715674996376 +1769682141,709945088,0.0,0.0,0.0,1.0,7.27474907762371e-05,-0.00013978932111058384,0.0014487272128462791,-0.3298635184764862,-0.050108134746551514,-0.010734744369983673 +1769682141,757782528,0.0,0.0,0.0,1.0,9.283910185331479e-05,-0.0001954636536538601,0.001446520909667015,-0.3184693455696106,-0.12551173567771912,-0.008991426788270473 +1769682141,773110016,0.0,0.0,0.0,1.0,-8.208384315366857e-06,-0.00019668656750582159,0.0014419034123420715,-0.3393208086490631,-0.05148393660783768,-0.00970962829887867 +1769682141,812912384,0.0,0.0,0.0,1.0,-5.92289688938763e-06,-0.0002402020472800359,0.0014274996938183904,-0.3131272494792938,0.02978351153433323,-0.004808441270142794 +1769682141,855344896,0.0,0.0,0.0,1.0,2.7006328309653327e-05,-0.00022264555445872247,0.0014134031953290105,-0.33203184604644775,0.02698986977338791,-0.002763490192592144 +1769682141,874957312,0.0,0.0,0.0,1.0,3.207050758646801e-05,-0.0002049061586149037,0.0014002058887854218,-0.3205980360507965,-0.04846362769603729,-0.0034035304561257362 +1769682141,907467776,0.0,0.0,0.0,1.0,-6.023517926223576e-05,-0.00018918154819402844,0.0013839160092175007,-0.3112214505672455,-0.04699935019016266,-0.0020397300831973553 +1769682141,958400256,0.0,0.0,0.0,1.0,-1.8947685020975769e-07,-0.0001696282997727394,0.0013769230572506785,-0.30723029375076294,-0.20074810087680817,-0.0024705773685127497 +1769682141,989505792,0.0,0.0,0.0,1.0,-2.4512472009519115e-05,-8.195358532248065e-05,0.0013689578045159578,-0.3170563876628876,0.18359926342964172,-0.005557030905038118 +1769682142,8060416,0.0,0.0,0.0,1.0,-4.3701129470719025e-06,-8.26318864710629e-05,0.0013572880998253822,-0.30165085196495056,-0.04564676061272621,-0.007823153398931026 +1769682142,45873920,0.0,0.0,0.0,1.0,-1.5938068827381358e-05,-9.061487799044698e-05,0.0013394124107435346,-0.3337341845035553,0.10371953248977661,-0.015048443339765072 +1769682142,75364096,0.0,0.0,0.0,1.0,-3.7089288525749e-05,-6.140724144643173e-05,0.0013145277043804526,-0.2829239070415497,-0.0426516979932785,-0.001523673301562667 +1769682142,108732416,0.0,0.0,0.0,1.0,-7.235460361698642e-05,-4.795250060851686e-05,0.0012744928244501352,-0.28488025069236755,0.034230440855026245,-0.0019024128559976816 +1769682142,141243904,0.0,0.0,0.0,1.0,-6.601968925679103e-05,-3.4236061765113845e-05,0.0012238952331244946,-0.2867557108402252,0.11104114353656769,-0.005855725612491369 +1769682142,183380224,0.0,0.0,0.0,1.0,-7.586161518702284e-05,-3.8707319617969915e-05,0.0011649871012195945,-0.27347517013549805,-0.04122084006667137,-0.002544386312365532 +1769682142,207630080,0.0,0.0,0.0,1.0,-0.00012531592801678926,-4.053644443047233e-05,0.0010776958661153913,-0.2733516991138458,-0.04132729768753052,-0.008502354845404625 +1769682142,252285184,0.0,0.0,0.0,1.0,-7.956338959047571e-05,-3.118106906185858e-05,0.0010147766442969441,-0.28671836853027344,0.11104927957057953,-0.007045459467917681 +1769682142,274393344,0.0,0.0,0.0,1.0,-4.834538049180992e-05,2.9527134756790474e-05,0.0009416808607056737,-0.25467273592948914,-0.03829823434352875,0.0001787042710930109 +1769682142,307058688,0.0,0.0,0.0,1.0,-4.569717566482723e-05,2.893005876103416e-05,0.0008947547757998109,-0.2565368711948395,0.03850918635725975,-0.0037742999847978354 +1769682142,345698560,0.0,0.0,0.0,1.0,-3.810987254837528e-05,9.544202475808561e-05,0.0008466169820167124,-0.25467509031295776,-0.03828250616788864,0.0001780178863555193 +1769682142,373649664,0.0,0.0,0.0,1.0,-3.92630354326684e-05,0.00034504462382756174,0.0008262881310656667,-0.25241562724113464,-0.11545827239751816,-0.014936434105038643 +1769682142,409064448,0.0,0.0,0.0,1.0,7.199773244792596e-05,0.0007231933996081352,0.0008055689977481961,-0.23077897727489471,-0.03502603620290756,-0.014894595369696617 +1769682142,465725440,0.0,0.0,0.0,1.0,4.8155110562220216e-05,0.0008986839675344527,0.0007901964709162712,-0.25643208622932434,0.03844184800982475,-0.008555242791771889 +1769682142,473909504,0.0,0.0,0.0,1.0,9.613324073143303e-05,0.0009788471506908536,0.0007899041520431638,-0.23095586895942688,-0.03484907001256943,-0.0065657529048621655 +1769682142,507573760,0.0,0.0,0.0,1.0,4.255733801983297e-05,0.0010675089433789253,0.0007750808726996183,-0.2215278148651123,-0.033421698957681656,-0.006404154933989048 +1769682142,555158016,0.0,0.0,0.0,1.0,7.17002694727853e-05,0.0010209878673776984,0.0007737688138149679,-0.20766262710094452,-0.031025581061840057,0.006953688338398933 +1769682142,575501056,0.0,0.0,0.0,1.0,1.0357201063015964e-05,0.0009434831445105374,0.0007566537242382765,-0.2010277956724167,-0.10718140751123428,0.007410882040858269 +1769682142,609958912,0.0,0.0,0.0,1.0,2.362372470088303e-05,0.0008545390446670353,0.0007487632683478296,-0.21694183349609375,-0.03257641941308975,-0.00038139685057103634 +1769682142,655060992,0.0,0.0,0.0,1.0,3.120831388514489e-05,0.0008196540293283761,0.0007358156726695597,-0.223575159907341,0.04359087347984314,-0.0008526153396815062 +1769682142,673330688,0.0,0.0,0.0,1.0,4.8386791604571044e-05,0.0006978882593102753,0.0007190870819613338,-0.20461471378803253,0.046338874846696854,-0.005279208533465862 +1769682142,708480512,0.0,0.0,0.0,1.0,-3.316109359730035e-05,0.00035437196493148804,0.0006883479072712362,-0.19321919977664948,-0.02915629744529724,-0.0071137892082333565 +1769682142,754449664,0.0,0.0,0.0,1.0,1.5540526874247007e-06,8.500556577928364e-05,0.0006604819209314883,-0.19059538841247559,0.048596594482660294,0.0009325593709945679 +1769682142,773736192,0.0,0.0,0.0,1.0,-5.7426473176747095e-06,6.67002586851595e-06,0.0006424628663808107,-0.18200697004795074,-0.10448379069566727,-0.0006046365015208721 +1769682142,808638208,0.0,0.0,0.0,1.0,-4.5408647565636784e-05,-7.252716750372201e-05,0.0006235093460418284,-0.1773204356431961,-0.10374635457992554,0.0006736896466463804 +1769682142,873238784,0.0,0.0,0.0,1.0,-6.574474355147686e-06,-9.463064634473994e-05,0.0006158248288556933,-0.19515487551689148,0.04775597155094147,-0.006302159279584885 +1769682142,882188032,0.0,0.0,0.0,1.0,1.454068024031585e-05,-4.3404776079114527e-05,0.0006173147121444345,-0.20465907454490662,0.046414248645305634,-0.0028994898311793804 +1769682142,909500160,0.0,0.0,0.0,1.0,-1.2011152648483403e-05,1.9211774997529574e-06,0.0006112344563007355,-0.1971081644296646,0.12468431144952774,-0.0042981551960110664 +1769682142,943146496,0.0,0.0,0.0,1.0,-1.1025192179658916e-05,3.220516737201251e-05,0.0005966806202195585,-0.18775279819965363,0.12617655098438263,-0.0005510887131094933 +1769682142,972983552,0.0,0.0,0.0,1.0,-2.8249485694686882e-05,0.00016256928211078048,0.0005773649318143725,-0.19515110552310944,0.047771353274583817,-0.006302329711616039 +1769682143,11548160,0.0,0.0,0.0,1.0,-5.0901013310067356e-05,0.00023201503790915012,0.000525902898516506,-0.1604505181312561,-0.02394731715321541,0.0042130607180297375 +1769682143,52226560,0.0,0.0,0.0,1.0,-0.00010288378689438105,0.0002611173258628696,0.00046532542910426855,-0.18103069067001343,0.049927614629268646,-0.004854321945458651 +1769682143,74118912,0.0,0.0,0.0,1.0,-9.007287735585123e-05,0.00025767620536498725,0.00041228302870877087,-0.13766953349113464,-0.1749732345342636,-0.0006429001223295927 +1769682143,106794240,0.0,0.0,0.0,1.0,-5.490209878189489e-05,0.00019700484699569643,0.0003232065646443516,-0.16870583593845367,0.1288589984178543,-0.00855125579982996 +1769682143,159040000,0.0,0.0,0.0,1.0,-0.00013441524060908705,0.00013642416161019355,0.00022576277842745185,-0.14618068933486938,-0.021932799369096756,-0.0014902944676578045 +1769682143,169015808,0.0,0.0,0.0,1.0,-7.561919483123347e-05,9.395949018653482e-05,0.0001759962469805032,-0.17062516510486603,0.20575781166553497,-0.007738861721009016 +1769682143,208113152,0.0,0.0,0.0,1.0,-6.619826308451593e-05,0.0001472456060582772,9.294154006056488e-05,-0.11597186326980591,-0.09457851201295853,-0.0017855094047263265 +1769682143,257210368,0.0,0.0,0.0,1.0,-3.4544096706667915e-05,0.00026268992223776877,4.5460485125659034e-05,-0.12734758853912354,-0.01907454989850521,4.514853935688734e-05 +1769682143,281195264,0.0,0.0,0.0,1.0,6.057283826521598e-06,0.00023248681100085378,2.658723678905517e-05,-0.11123201251029968,-0.0938936173915863,-0.0028923931531608105 +1769682143,308089856,0.0,0.0,0.0,1.0,7.059353811200708e-05,0.0001640382397454232,2.349933492951095e-05,-0.11786730587482452,-0.017705343663692474,-0.0021663520019501448 +1769682143,345397504,0.0,0.0,0.0,1.0,5.024761048844084e-05,0.00023212669475469738,4.4296968553680927e-05,-0.1175871267914772,-0.01796618103981018,-0.015274498611688614 +1769682143,373058048,0.0,0.0,0.0,1.0,6.929407390998676e-05,0.00039042840944603086,5.9272366343066096e-05,-0.1335240751504898,0.056687090545892715,-0.020680535584688187 +1769682143,410330880,0.0,0.0,0.0,1.0,0.000168184022186324,0.000666863052174449,0.00010067594121210277,-0.1034681648015976,-0.01581748202443123,-0.013825892470777035 +1769682143,453864704,0.0,0.0,0.0,1.0,0.00016421196050941944,0.0007815802819095552,0.00012921438610646874,-0.12606428563594818,0.13504807651042938,-0.017318176105618477 +1769682143,474204928,0.0,0.0,0.0,1.0,0.00016142477397806942,0.0008338643237948418,0.00015630156849510968,-0.1007491946220398,0.06185907498002052,-0.00935722142457962 +1769682143,509330944,0.0,0.0,0.0,1.0,9.943263285094872e-05,0.0008317988249473274,0.00017735021538101137,-0.06703595072031021,-0.16427220404148102,0.004218887537717819 +1769682143,556339200,0.0,0.0,0.0,1.0,6.092037438065745e-05,0.0008055137586779892,0.00019920364138670266,-0.09183405339717865,-0.013902626931667328,-0.006469593849033117 +1769682143,574079744,0.0,0.0,0.0,1.0,8.084468572633341e-05,0.0007520586950704455,0.00021332611504476517,-0.10991685092449188,0.13786178827285767,-0.0003459622384980321 +1769682143,607497728,0.0,0.0,0.0,1.0,2.6779000108945183e-05,0.0007133254548534751,0.0002324498345842585,-0.08255872875452042,-0.012342864647507668,0.0008508834289386868 +1769682143,641371904,0.0,0.0,0.0,1.0,7.567012653453276e-05,0.0007038921467028558,0.00025922199711203575,-0.07548676431179047,-0.011280265636742115,0.000980663811787963 +1769682143,677117184,0.0,0.0,0.0,1.0,4.382492625154555e-05,0.0004048670525662601,0.0002936679811682552,-0.0705147385597229,-0.010809101164340973,-0.010848911479115486 +1769682143,709833472,0.0,0.0,0.0,1.0,6.527059213112807e-06,0.00023931896430440247,0.00032343881321139634,-0.04580255225300789,-0.1611071527004242,0.00341574614867568 +1769682143,743177728,0.0,0.0,0.0,1.0,1.8571005057310686e-05,6.28293928457424e-05,0.00034464854979887605,-0.05667975917458534,-0.008399027399718761,0.0037126424722373486 +1769682143,773417728,0.0,0.0,0.0,1.0,-2.8975082386750728e-05,1.0255987490381813e-06,0.00035604022559709847,-0.05458573251962662,-0.08546139299869537,-0.005438641645014286 +1769682143,807965952,0.0,0.0,0.0,1.0,-8.002436516107991e-06,-3.284436752437614e-05,0.00036106296465732157,-0.06126591935753822,-0.009224163368344307,-0.002333039650693536 +1769682143,851998976,0.0,0.0,0.0,1.0,-3.8129641325213015e-05,-8.519175935362e-06,0.0003602088545449078,-0.08146258443593979,0.14197413623332977,-0.0069776903837919235 +1769682143,875218432,0.0,0.0,0.0,1.0,1.0060109161713626e-05,-4.735612674267031e-05,0.0003628888516686857,-0.03166799619793892,-0.1589815765619278,0.0036787232384085655 +1769682143,908066816,0.0,0.0,0.0,1.0,3.499092417769134e-05,-4.302751403884031e-05,0.000372632232028991,-0.06985234469175339,0.1439114511013031,0.001583104021847248 +1769682143,951781888,0.0,0.0,0.0,1.0,1.9662586055346765e-05,3.397609543753788e-05,0.0004052802105434239,-0.05961325764656067,0.06818260252475739,-0.002648330759257078 +1769682143,973653504,0.0,0.0,0.0,1.0,4.4172069465275854e-05,4.473551962291822e-05,0.00043516093865036964,-0.05314438417553902,-0.007863611914217472,0.0037785677704960108 +1769682144,7457024,0.0,0.0,0.0,1.0,5.725687151425518e-05,0.00010989396105287597,0.0004940989310853183,-0.06417163461446762,0.06733425706624985,-0.009886079467833042 +1769682144,68528384,0.0,0.0,0.0,1.0,5.405307820183225e-05,9.954085544450209e-05,0.0005402386304922402,-0.05130784958600998,0.06937535852193832,-0.004878520034253597 +1769682144,77259520,0.0,0.0,0.0,1.0,4.316508420743048e-05,0.00010458500764798373,0.0006001178990118206,-0.05095549672842026,0.14672207832336426,0.0007411262486129999 +1769682144,108832000,0.0,0.0,0.0,1.0,7.689277117606252e-05,7.565641135443002e-05,0.0006322651752270758,-0.021157778799533844,-0.08029988408088684,0.0011447628494352102 +1769682144,152535296,0.0,0.0,0.0,1.0,-3.867365012411028e-05,4.087246998096816e-05,0.0006447381456382573,-0.03059500642120838,-0.004642972722649574,-0.0029542723204940557 +1769682144,174610944,0.0,0.0,0.0,1.0,-3.9840298995841295e-05,-4.018423715024255e-05,0.0006366170127876103,-0.023522820323705673,-0.0035818833857774734,-0.0028224748093634844 +1769682144,209388800,0.0,0.0,0.0,1.0,-1.8886708858190104e-05,-8.557182445656508e-05,0.000615003751590848,-0.02472737990319729,-0.0037343590520322323,-0.001652817940339446 +1769682144,250377216,0.0,0.0,0.0,1.0,-6.746361032128334e-05,-6.813844811404124e-05,0.0005771505529992282,-0.021726947277784348,-0.0033669453114271164,-0.005173018667846918 +1769682144,275538176,0.0,0.0,0.0,1.0,-0.00010796930291689932,-8.676627476233989e-05,0.0005566935869865119,-0.00587279349565506,-0.07792293280363083,0.005005090031772852 +1769682144,306929920,0.0,0.0,0.0,1.0,-7.799468585290015e-05,-5.9842743212357163e-05,0.0005383135285228491,-0.02067713439464569,-0.003070745849981904,0.000806905678473413 +1769682144,354522112,0.0,0.0,0.0,1.0,-2.0388139091664925e-05,0.0002295477461302653,0.0005351663567125797,-0.02044535055756569,-0.0032841775100678205,-0.009917397983372211 +1769682144,375150080,0.0,0.0,0.0,1.0,2.549666169215925e-05,0.00039724179077893496,0.000544393842574209,-0.02164505608379841,0.07363388687372208,-0.012670149095356464 +1769682144,407633152,0.0,0.0,0.0,1.0,1.0494024536455981e-05,0.000529227836523205,0.0005646063946187496,0.005321801640093327,-0.07627248764038086,0.004021590109914541 +1769682144,441204224,0.0,0.0,0.0,1.0,5.5123065976658836e-05,0.0005624298355542123,0.0005811062874272466,-0.006891780067235231,-0.001225626445375383,-0.008473296649754047 +1769682144,475282176,0.0,0.0,0.0,1.0,3.156993989250623e-05,0.0005816978518851101,0.0005895759677514434,-0.010557047091424465,-0.0016361736925318837,-0.002581497188657522 +1769682144,507539456,0.0,0.0,0.0,1.0,3.4433665859978646e-05,0.0005397031200118363,0.0005852858885191381,-0.009466324001550674,0.07565151900053024,-0.004099688492715359 +1769682144,552427520,0.0,0.0,0.0,1.0,-7.031067070784047e-05,0.000533103768248111,0.0005738120526075363,0.013860690407454967,-0.15233872830867767,-0.0038160420954227448 +1769682144,573853952,0.0,0.0,0.0,1.0,-4.263910886947997e-05,0.0004510910948738456,0.0005505491863004863,-0.007800956256687641,0.07603894174098969,0.0018916993867605925 +1769682144,607501056,0.0,0.0,0.0,1.0,-2.750373096205294e-05,0.00035184918669983745,0.0005344715318642557,0.017177995294332504,-0.0745801031589508,0.0006683543906547129 +1769682144,641572352,0.0,0.0,0.0,1.0,-2.0140214473940432e-05,0.00010020458284998313,0.0005311159184202552,0.009481924585998058,0.001363749266602099,-0.002206182572990656 +1769682144,673568256,0.0,0.0,0.0,1.0,3.887069397023879e-05,-0.00010609882156131789,0.0005421286914497614,0.014196999371051788,0.002069157548248768,-0.0021177143789827824 +1769682144,709023232,0.0,0.0,0.0,1.0,2.8958071197848767e-05,-0.00027329300064593554,0.0005817253841087222,0.00020724369096569717,-0.00019011374388355762,-0.009532601572573185 +1769682144,754450688,0.0,0.0,0.0,1.0,3.227565321139991e-05,-0.00033437242382206023,0.000646879430860281,0.01596740633249283,-0.07473403960466385,0.001837496878579259 +1769682144,773623808,0.0,0.0,0.0,1.0,8.488414459861815e-05,-0.00037047002115286887,0.0006873345701023936,0.01950274035334587,-0.07420529425144196,0.0019037388265132904 +1769682144,807286272,0.0,0.0,0.0,1.0,4.122105019632727e-05,-0.0003869906940963119,0.0007607316365465522,0.011736083775758743,0.0018103846814483404,0.0026038330979645252 +1769682144,856226816,0.0,0.0,0.0,1.0,1.1277006706222892e-05,-0.00034811472869478166,0.0008040011744014919,7.754674879834056e-05,-7.131951861083508e-05,-0.0035747287329286337 +1769682144,875024896,0.0,0.0,0.0,1.0,-6.073575059417635e-05,-0.000360698759322986,0.0008292148704640567,0.015934228897094727,-0.07471185177564621,0.0030285711400210857 +1769682144,908362752,0.0,0.0,0.0,1.0,-7.613842171849683e-05,-0.0003672406019177288,0.0008305995725095272,0.027720360085368156,-0.07295037806034088,0.003248535795137286 +1769682144,942237696,0.0,0.0,0.0,1.0,-8.537499525118619e-05,-0.00038417603354901075,0.0008143200539052486,0.0005210023955442011,0.0772264152765274,-0.0003364694130141288 +1769682144,974901248,0.0,0.0,0.0,1.0,-0.00018791720503941178,-0.00036240729968994856,0.0007749565993435681,0.007124410476535559,0.0010092058219015598,-0.002251173136755824 +1769682145,9637632,0.0,0.0,0.0,1.0,-0.0001318917638855055,-0.000356037839083001,0.0007511158473789692,0.004818330053240061,0.0006093496340326965,-0.004678374156355858 +1769682145,41490176,0.0,0.0,0.0,1.0,-3.220977305318229e-05,-0.00036652348353527486,0.0007404081989079714,0.023126661777496338,-0.07377627491950989,-0.0027997647412121296 +1769682145,73781504,0.0,0.0,0.0,1.0,-9.746998694026843e-05,-0.0003945293719880283,0.0007450451957993209,0.006570030469447374,-0.07619387656450272,-0.0007245276938192546 +1769682145,109693184,0.0,0.0,0.0,1.0,-7.010529952822253e-05,-0.000408041087212041,0.0007686500903218985,0.007047224789857864,0.0010797865688800812,0.0013232219498604536 +1769682145,140069120,0.0,0.0,0.0,1.0,-4.184346835245378e-05,-0.0004001704801339656,0.0008000871166586876,0.004792442079633474,0.0006326636648736894,-0.003487036097794771 +1769682145,173979392,0.0,0.0,0.0,1.0,-3.3330716178170405e-06,-0.00043901000753976405,0.0008454754715785384,0.02291293628513813,-0.0735887885093689,0.006731092929840088 +1769682145,210306816,0.0,0.0,0.0,1.0,-1.2862616131315008e-05,-0.0004562322865240276,0.0008755443268455565,0.0046896906569600105,0.0007273845258168876,0.0012791394256055355 +1769682145,254159616,0.0,0.0,0.0,1.0,-3.731519609573297e-05,-0.00047196392551995814,0.0008992168004624546,0.007150030694901943,0.0009840147104114294,-0.003443502588197589 +1769682145,273792512,0.0,0.0,0.0,1.0,-6.219052011147141e-05,-0.0004195091314613819,0.0009266643901355565,0.013732152059674263,-0.07523501664400101,-0.005360810551792383 +1769682145,308748032,0.0,0.0,0.0,1.0,-8.544750744476914e-05,-0.0002569633652456105,0.000940262689255178,0.02266770228743553,-0.15110273659229279,-0.007234837859869003 +1769682145,350953472,0.0,0.0,0.0,1.0,-4.7832552809268236e-05,-0.00013343890896067023,0.0009581511840224266,-0.017614947631955147,0.1514977514743805,-0.008168108761310577 +1769682145,373996544,0.0,0.0,0.0,1.0,-2.2834419723949395e-05,-4.915221506962553e-05,0.0009864240419119596,-0.015775321051478386,0.07459991425275803,-0.008981226943433285 +1769682145,407057152,0.0,0.0,0.0,1.0,-7.163959526224062e-05,6.031624252500478e-06,0.0010150743182748556,0.011262424290180206,-0.07549310475587845,-0.0006388546898961067 +1769682145,440354560,0.0,0.0,0.0,1.0,-4.8866575525607914e-05,1.596258516656235e-05,0.0010443378705531359,0.006518955808132887,-0.07617229968309402,0.0004653295618481934 +1769682145,475312640,0.0,0.0,0.0,1.0,-2.7980187951470725e-05,-3.245277184760198e-07,0.0010914038866758347,-0.004715550225228071,-0.0007023921934887767,-8.732941932976246e-05 +1769682145,508546816,0.0,0.0,0.0,1.0,-7.109349826350808e-05,-3.0070736102061346e-05,0.00113075808621943,-5.1205533964093775e-05,4.748683932120912e-05,0.0023831643629819155 +1769682145,565629952,0.0,0.0,0.0,1.0,-3.9705650124233216e-05,-6.57420459901914e-05,0.0011730650439858437,0.011174009181559086,-0.07542359828948975,0.002935580210760236 +1769682145,574131456,0.0,0.0,0.0,1.0,-8.900059037841856e-05,-0.00013652959023602307,0.0011854019248858094,0.01586225815117359,-0.07469821721315384,0.004214317072182894 +1769682145,607990784,0.0,0.0,0.0,1.0,-0.00011670665116980672,-0.0003016799164470285,0.001208771369419992,0.004766826052218676,0.0006541988113895059,-0.002295896876603365 +1769682145,653996800,0.0,0.0,0.0,1.0,-0.00011521538544911891,-0.00040300004184246063,0.0012181061320006847,0.016009440645575523,-0.07484200596809387,-0.002936017932370305 +1769682145,675954944,0.0,0.0,0.0,1.0,-0.00010450957779539749,-0.00048005106509663165,0.0012219606433063745,0.00461353175342083,0.0007962011732161045,0.004853471647948027 +1769682145,707587840,0.0,0.0,0.0,1.0,-0.0001655972737353295,-0.0005213016411289573,0.0012098266743123531,-0.006469352170825005,0.07615064084529877,-0.0016549370484426618 +1769682145,740752128,0.0,0.0,0.0,1.0,-0.0001563566183904186,-0.000510308425873518,0.0011866448912769556,-0.00461373757570982,-0.0007958202622830868,-0.004853338003158569 +1769682145,774750976,0.0,0.0,0.0,1.0,-0.0001946173724718392,-0.0004721847362816334,0.0011412696912884712,0.0017728203674778342,-0.07687561959028244,0.0003752906632144004 +1769682145,808774400,0.0,0.0,0.0,1.0,-0.00014404808462131768,-0.00045850727474316955,0.0010970872826874256,-0.00010186631698161364,9.483947360422462e-05,0.0047663431614637375 +1769682145,843620608,0.0,0.0,0.0,1.0,-0.00021247152471914887,-0.00042735383613035083,0.001050582155585289,-0.02055487409234047,0.07400301843881607,-0.004296288825571537 +1769682145,874230272,0.0,0.0,0.0,1.0,-0.0002024703862844035,-0.0004027315881103277,0.0009835637174546719,0.015836076810956,-0.07470409572124481,0.004208663944154978 +1769682145,907290112,0.0,0.0,0.0,1.0,-0.00023496705398429185,-0.000377520511392504,0.0009356736554764211,-0.0047667371109128,-0.0006527010118588805,0.0022965080570429564 +1769682145,942445312,0.0,0.0,0.0,1.0,-0.00013619172386825085,-0.0003504041815176606,0.000896938203368336,-0.009584262035787106,-0.001257796655409038,0.0069762892089784145 +1769682145,975867136,0.0,0.0,0.0,1.0,-0.00017866755661088973,-0.0003441128646954894,0.000854808371514082,0.0223793126642704,-0.15095281600952148,0.0010909729171544313 +1769682146,8877824,0.0,0.0,0.0,1.0,-0.00012815056834369898,-0.0003399157430976629,0.0008315242012031376,-0.004792083986103535,-0.0006286469870246947,0.003488254500553012 +1769682146,58461440,0.0,0.0,0.0,1.0,-0.00010502859367989004,-0.0003381040587555617,0.0008145276224240661,0.0016772454837337136,-0.07680507749319077,0.0039464570581912994 +1769682146,81386496,0.0,0.0,0.0,1.0,-9.089829836739227e-05,-0.0004031322314403951,0.0008085028966888785,0.011158131062984467,-0.07545367628335953,0.001735841273330152 +1769682146,107397632,0.0,0.0,0.0,1.0,-8.852651808410883e-05,-0.00037682955735363066,0.0008067807066254318,-0.020613716915249825,0.07407904416322708,-0.0007166285649873316 +1769682146,145744640,0.0,0.0,0.0,1.0,-8.398119825869799e-05,-0.0003849727218039334,0.0008107578614726663,-0.015971191227436066,0.07484983652830124,0.0029449723660945892 +1769682146,174754560,0.0,0.0,0.0,1.0,-3.0951021471992135e-05,-0.0004120464436709881,0.0008196316193789244,-0.031786900013685226,0.14955845475196838,-0.0012588831596076488 +1769682146,210935040,0.0,0.0,0.0,1.0,-9.381979907630011e-05,-0.00042473740177229047,0.0008324669906869531,-0.0030485866591334343,-0.0775042474269867,0.0038592510391026735 +1769682146,248008704,0.0,0.0,0.0,1.0,-8.94566546776332e-05,-0.000336871191393584,0.0008384614484384656,0.008424950763583183,-0.15326690673828125,-0.009897527284920216 +1769682146,273724416,0.0,0.0,0.0,1.0,-0.00015094754053279757,-0.00019777331908699125,0.0008331940043717623,-0.013971678912639618,-0.002261406509205699,-0.008599305525422096 +1769682146,307240192,0.0,0.0,0.0,1.0,-0.00014294024731498212,-9.523100015940145e-05,0.0008191484375856817,0.00010096433834405616,-9.459369903197512e-05,-0.0047663673758506775 +1769682146,353687296,0.0,0.0,0.0,1.0,-0.0001486471010139212,-7.380729584838264e-06,0.0007697815890423954,-0.010990183800458908,0.07531432807445526,-0.008882655762135983 +1769682146,374619904,0.0,0.0,0.0,1.0,-0.00021608846145682037,7.331107917707413e-05,0.0007151116733439267,-0.011013745330274105,0.07533825933933258,-0.007690679747611284 +1769682146,407325696,0.0,0.0,0.0,1.0,-0.00018967522191815078,9.325384598923847e-05,0.0006604641093872488,-0.018789086490869522,-0.002863488160073757,-0.003919029142707586 +1769682146,440922112,0.0,0.0,0.0,1.0,-0.0002327195106772706,6.591519922949374e-05,0.0006038012797944248,0.01113698910921812,-0.0754568874835968,0.00173186045140028 +1769682146,475478272,0.0,0.0,0.0,1.0,-0.0001958157226908952,4.9710331950336695e-05,0.000544289534445852,-0.01891542226076126,-0.0027445845771580935,0.0020388192497193813 +1769682146,509550592,0.0,0.0,0.0,1.0,-0.00014654554252047092,1.974618135136552e-05,0.0005106627941131592,0.009306250140070915,0.0015138100134208798,0.006130159832537174 +1769682146,541965056,0.0,0.0,0.0,1.0,-0.000166804384207353,-8.772945147939026e-05,0.000486246106447652,2.5244946300517768e-05,-2.3605054593645036e-05,-0.0011915926588699222 +1769682146,573847040,0.0,0.0,0.0,1.0,-0.00020515269716270268,-0.00024297204799950123,0.0004614979261532426,-0.00943253468722105,-0.0013954403111711144,-0.00017213280079886317 +1769682146,613693952,0.0,0.0,0.0,1.0,-0.00021968796500004828,-0.00034139654599130154,0.0004465820384211838,-0.03009658306837082,0.07276163250207901,0.0026928409934043884 +1769682146,643536384,0.0,0.0,0.0,1.0,-0.00025437137810513377,-0.0003942814946640283,0.000435982015915215,0.020461320877075195,-0.0739685446023941,0.006667084526270628 +1769682146,675286016,0.0,0.0,0.0,1.0,-0.0002711676643230021,-0.0003858486597891897,0.0004214709915686399,-0.020485352724790573,0.0739925280213356,-0.005474391859024763 +1769682146,707783936,0.0,0.0,0.0,1.0,-0.0002879335661418736,-0.0003785229055210948,0.0004200881812721491,0.02050965093076229,-0.07401639223098755,0.004282026551663876 +1769682146,753044992,0.0,0.0,0.0,1.0,-0.0002800108049996197,-0.0003594759909901768,0.0004282885347492993,-0.007688845973461866,-0.07829519361257553,-0.0010002359049394727 +1769682146,775906816,0.0,0.0,0.0,1.0,-0.000262533692875877,-0.0003661156806629151,0.000442174932686612,-0.017122555524110794,-0.07968970388174057,-0.0011722245253622532 +1769682146,807600896,0.0,0.0,0.0,1.0,-0.0002730113628786057,-0.00035841454518958926,0.00046428237692452967,0.001716586179099977,-0.07687696069478989,0.0003617741749621928 +1769682146,841241856,0.0,0.0,0.0,1.0,-0.00019806143245659769,-0.00034327656612731516,0.0004869576951023191,-0.02839861623942852,-0.004088942892849445,0.004252387676388025 +1769682146,876611584,0.0,0.0,0.0,1.0,-0.00023621231957804412,-0.000317161378916353,0.000520741508807987,-0.01891569420695305,-0.0027412790805101395,0.002040744526311755 +1769682146,908591616,0.0,0.0,0.0,1.0,-0.00026124718715436757,-0.0003040842420887202,0.0005468426970764995,0.02221563272178173,-0.1508956104516983,0.00463690934702754 +1769682146,945888000,0.0,0.0,0.0,1.0,-0.00022390797676052898,-0.000275676604360342,0.0005852439790032804,-0.0598682276904583,0.14525052905082703,-0.008894302882254124 +1769682146,974249728,0.0,0.0,0.0,1.0,-0.00010622918489389122,-0.00021387987362686545,0.0006257434724830091,-0.03944085165858269,0.07130268216133118,-0.0010427741799503565 +1769682147,9896704,0.0,0.0,0.0,1.0,-0.00011643821198958904,-0.00016258606046903878,0.0006631599389947951,-0.007699739187955856,-0.07829407602548599,-0.0010040294146165252 +1769682147,46952704,0.0,0.0,0.0,1.0,-0.00010869662219192833,-0.00012773914204444736,0.0006947239162400365,-0.007827180437743664,-0.07817646116018295,0.004953679628670216 +1769682147,73960448,0.0,0.0,0.0,1.0,-0.00012539180170278996,-7.305467443075031e-05,0.0007065142854116857,-0.050422921776771545,0.1466488093137741,-0.008719894103705883 +1769682147,107541248,0.0,0.0,0.0,1.0,-0.0001373648556182161,-7.134549377951771e-05,0.000708115694578737,-0.02819865196943283,-0.0042721922509372234,-0.0052790213376283646 +1769682147,153977600,0.0,0.0,0.0,1.0,-0.00019973833695985377,-5.0563998229335994e-05,0.0006766581791453063,-0.03007468208670616,0.07277023047208786,0.0027050364296883345 +1769682147,175843584,0.0,0.0,0.0,1.0,-0.00016741969739086926,-5.525286906049587e-05,0.0006309691816568375,0.0015738490037620068,-0.07676006108522415,0.006314779166132212 +1769682147,208137728,0.0,0.0,0.0,1.0,-0.00020475254859775305,-1.3046354069956578e-05,0.0005751691060140729,0.00020034184854011983,-0.00018764402193482965,-0.009532799012959003 +1769682147,240642816,0.0,0.0,0.0,1.0,-0.0002923124993685633,0.00010006393858930096,0.0005142997833900154,-0.018740909174084663,-0.0029012244194746017,-0.006299743428826332 +1769682147,274599168,0.0,0.0,0.0,1.0,-0.00031274501816369593,0.00015685646212659776,0.00043326709419488907,-0.018740929663181305,-0.0029008060228079557,-0.006299874745309353 +1769682147,308062976,0.0,0.0,0.0,1.0,-0.00032789362012408674,0.00016792396490927786,0.00038692416273988783,-0.007738999091088772,-0.07826919853687286,0.0001831597473938018 +1769682147,341893888,0.0,0.0,0.0,1.0,-0.0002269932592753321,0.00017316965386271477,0.0003528775123413652,-0.009282748214900494,-0.0015320804668590426,-0.007320658769458532 +1769682147,374262016,0.0,0.0,0.0,1.0,-0.00025028406525962055,0.00018668189295567572,0.0003337934613227844,-0.00771584315225482,-0.07829242199659348,-0.001009976607747376 +1769682147,408459008,0.0,0.0,0.0,1.0,-0.00022848270600661635,0.0002015100617427379,0.00033561920281499624,-0.017099618911743164,-0.07973049581050873,-0.003564937738701701 +1769682147,443219712,0.0,0.0,0.0,1.0,-0.00017950199253391474,0.0001678205735515803,0.00034897090517915785,0.00943316612392664,0.0013912776485085487,0.00017126250895671546 +1769682147,476277760,0.0,0.0,0.0,1.0,-0.00021342314721550792,0.00017090083565562963,0.0003783094580285251,-0.02058097906410694,0.0741187185049057,0.0004977184580639005 +1769682147,510864128,0.0,0.0,0.0,1.0,-0.0004257995169609785,0.0001342095638392493,0.00038981009856797755,-0.009232430718839169,-0.0015779533423483372,-0.009704199619591236 +1769682147,543187200,0.0,0.0,0.0,1.0,-0.0005507842288352549,1.7598458725842647e-05,0.000403268844820559,-0.020604336634278297,0.07414253056049347,0.0016910245176404715 +1769682147,574124288,0.0,0.0,0.0,1.0,-0.0006651045405305922,-6.629830750171095e-05,0.0004183652636129409,0.031697697937488556,-0.14960646629333496,1.780287129804492e-05 +1769682147,607372032,0.0,0.0,0.0,1.0,-0.0006469032960012555,-0.00011504918802529573,0.0004324102192185819,-0.009408165700733662,-0.0014139254344627261,-0.0013630498433485627 +1769682147,644502528,0.0,0.0,0.0,1.0,-0.0006730785826221108,-0.0001853332796599716,0.000447684433311224,-0.009383116848766804,-0.0014369883574545383,-0.002554627601057291 +1769682147,676570112,0.0,0.0,0.0,1.0,-0.0006737593794241548,-0.00023691046226304024,0.0004660161503124982,-0.018766308203339577,-0.0028736162930727005,-0.005109186749905348 +1769682147,709025536,0.0,0.0,0.0,1.0,-0.0006370577029883862,-0.0002689115353859961,0.0004875222803093493,-0.04102197661995888,0.14812526106834412,-0.004941905848681927 +1769682147,742170880,0.0,0.0,0.0,1.0,-0.0006023937021382153,-0.0002712446148507297,0.0005074852961115539,-0.00948345847427845,-0.001343641895800829,0.0022119174245744944 +1769682147,774993664,0.0,0.0,0.0,1.0,-0.000641736201941967,-0.00027755129849538207,0.0005240985192358494,-0.02054595574736595,0.07409822195768356,-0.0006798654212616384 +1769682147,809539584,0.0,0.0,0.0,1.0,-0.0006806424935348332,-0.00025060962070710957,0.0005257842713035643,-0.026747381314635277,-0.08093126118183136,0.005780377890914679 +1769682147,853755904,0.0,0.0,0.0,1.0,-0.0007407772936858237,-0.0002647780056577176,0.0005095578380860388,0.0032026839908212423,-0.153617262840271,0.00781725998967886 +1769682147,874274304,0.0,0.0,0.0,1.0,-0.0007240995182655752,-0.0002505849115550518,0.0004777667054440826,-0.05046780779957771,0.14676310122013092,-0.003902953118085861 +1769682147,907922432,0.0,0.0,0.0,1.0,-0.0006476608105003834,-0.00023390684509649873,0.0004469416744541377,-0.03938313201069832,0.07129810750484467,-0.002206390257924795 +1769682147,959487744,0.0,0.0,0.0,1.0,-0.0003771046467591077,-6.089529051678255e-05,0.0004294005630072206,-0.026427648961544037,-0.081229567527771,-0.009716571308672428 +1769682147,973541632,0.0,0.0,0.0,1.0,-0.0002571330696810037,1.3708765436604153e-05,0.0004093817842658609,0.022160904482007027,-0.15093226730823517,0.0033825822174549103 +1769682148,8073472,0.0,0.0,0.0,1.0,-0.00023040478117763996,0.00010004255454987288,0.0003895058180205524,0.010929574258625507,-0.07532810419797897,0.008840504102408886 +1769682148,53896960,0.0,0.0,0.0,1.0,-0.00010123558604391292,0.00011503854329930618,0.0003651958832051605,-0.007888397201895714,-0.07815171778202057,0.006114873569458723 +1769682148,74143232,0.0,0.0,0.0,1.0,-7.392106635961682e-05,0.00012477606651373208,0.0003499082231428474,-0.018817121163010597,-0.002823186106979847,-0.0027254910673946142 +1769682148,109031680,0.0,0.0,0.0,1.0,-9.749293894856237e-06,0.00010561302042333409,0.0003341651754453778,-0.02991899475455284,0.0726667121052742,-0.0032243402674794197 +1769682148,143643392,0.0,0.0,0.0,1.0,8.904951755539514e-06,0.0001285446633119136,0.00032993245986290276,-0.009558663703501225,-0.0012732802424579859,0.005786837078630924 +1769682148,174371328,0.0,0.0,0.0,1.0,-0.00020743347704410553,0.00019111948495265096,0.00030624924693256617,-0.015359001234173775,-0.15669406950473785,-0.008029035292565823 +1769682148,208262656,0.0,0.0,0.0,1.0,-0.0002829856821335852,0.0002699802571441978,0.0002919352555181831,-0.03753424435853958,-0.005736773833632469,-0.01021826732903719 +1769682148,241501696,0.0,0.0,0.0,1.0,-0.0003471547388471663,0.0003621106152422726,0.00028145441319793463,-0.03768443688750267,-0.005598376039415598,-0.003069060854613781 +1769682148,274273536,0.0,0.0,0.0,1.0,-0.0004125368141103536,0.00042281675268895924,0.0002807992568705231,-0.02983996458351612,0.07259942591190338,-0.006797820795327425 +1769682148,309803264,0.0,0.0,0.0,1.0,-0.0004796026332769543,0.00046806238242425025,0.00028857591678388417,-0.029864316806197166,0.07262273132801056,-0.00560562452301383 +1769682148,343132928,0.0,0.0,0.0,1.0,-0.000534233869984746,0.0004641906707547605,0.0003031526575796306,-0.01889241673052311,-0.0027526903431862593,0.0008477548253722489 +1769682148,375298560,0.0,0.0,0.0,1.0,-0.0005952334031462669,0.0004546742420643568,0.0003240275545977056,0.010819430463016033,-0.07523853331804276,0.013600926846265793 +1769682148,407481600,0.0,0.0,0.0,1.0,-0.000566887145396322,0.00044000823982059956,0.00033697503386065364,0.0003266763233114034,-0.0002977063995786011,-0.015490913763642311 +1769682148,457621760,0.0,0.0,0.0,1.0,-0.0006601673667319119,0.0004917105543427169,0.0003414403763599694,-0.01894286274909973,-0.0027063109446316957,0.003229863476008177 +1769682148,476661504,0.0,0.0,0.0,1.0,-0.000863215303979814,3.296094655524939e-05,0.0003388716431800276,0.018892593681812286,0.002751880558207631,-0.0008464772254228592 +1769682148,507805440,0.0,0.0,0.0,1.0,-0.000988124986179173,-0.000436511094449088,0.00031801903969608247,-0.03753376752138138,-0.0057315281592309475,-0.010222963988780975 +1769682148,544774400,0.0,0.0,0.0,1.0,-0.0010302709415555,-0.0008071899064816535,0.00026637615519575775,0.011367741972208023,-0.07574170082807541,-0.012624561786651611 +1769682148,580535296,0.0,0.0,0.0,1.0,-0.001019350253045559,-0.0009975574212148786,0.00020588250481523573,-0.030033770948648453,0.07278542965650558,0.002750186715275049 +1769682148,609841920,0.0,0.0,0.0,1.0,-0.0008164274040609598,-0.0012368093011900783,0.0001395715371472761,-0.026894863694906235,-0.08081267029047012,0.011707035824656487 +1769682148,645607680,0.0,0.0,0.0,1.0,-0.0007355543784797192,-0.0014059481909498572,4.6655270125484094e-05,-0.019042404368519783,-0.002615391742438078,0.007998637855052948 +1769682148,674145024,0.0,0.0,0.0,1.0,-0.0007014911388978362,-0.001430579344742,-9.601853889762424e-06,-0.00810118205845356,-0.07797132432460785,0.015622178092598915 +1769682148,709278464,0.0,0.0,0.0,1.0,-0.0005664037307724357,-0.001466164831072092,-5.269182656775229e-05,0.007752209901809692,0.07828814536333084,0.001061537186615169 +1769682148,746629888,0.0,0.0,0.0,1.0,-0.0005110337515361607,-0.0014315115986391902,-8.155097020789981e-05,-0.04877643659710884,0.06989827752113342,-0.0035325386561453342 +1769682148,775818496,0.0,0.0,0.0,1.0,-0.00039280345663428307,-0.0013881601626053452,-8.221861207857728e-05,-0.03780952841043472,-0.005480457562953234,0.0028961151838302612 +1769682148,809281792,0.0,0.0,0.0,1.0,-0.00037497826269827783,-0.0013957085320726037,-7.15581263648346e-05,4.940476719639264e-05,-4.510980215854943e-05,-0.002383248647674918 +1769682148,853775616,0.0,0.0,0.0,1.0,-0.0003109944227617234,-0.0013261225540190935,-5.458651503431611e-05,-0.007924082688987255,-0.07813039422035217,0.0072767664678394794 +1769682148,874869504,0.0,0.0,0.0,1.0,-0.00024792036856524646,-0.001303703524172306,-3.693009784910828e-05,-0.007923686876893044,-0.07813046872615814,0.007276349700987339 +1769682148,907476224,0.0,0.0,0.0,1.0,-0.00014851118612568825,-0.001234251307323575,-1.2162445273133926e-05,-0.03771080821752548,-0.0055709113366901875,-0.0018640451598912477 +1769682148,940674304,0.0,0.0,0.0,1.0,-0.00012015571701340377,-0.0011347172548994422,6.761875283700647e-06,0.011140609160065651,-0.07553648203611374,-0.0019211892504245043 +1769682148,978288384,0.0,0.0,0.0,1.0,-6.564403156517074e-05,-0.0010711830109357834,1.8362099581281655e-05,-0.048851437866687775,0.06996559351682663,6.0802733059972525e-05 +1769682149,8993024,0.0,0.0,0.0,1.0,-7.671571074752137e-05,-0.0010256064124405384,3.503628249745816e-05,-0.034493330866098404,-0.15923789143562317,0.00349435000680387 +1769682149,41567488,0.0,0.0,0.0,1.0,-2.6299196633772226e-06,-0.0010352664394304156,5.818105273647234e-05,-0.011140185408294201,0.07553650438785553,0.001922642346471548 +1769682149,74017280,0.0,0.0,0.0,1.0,4.484807141125202e-05,-0.0010497996117919683,9.682938980404288e-05,-0.026595644652843475,-0.08108469843864441,-0.002588558942079544 +1769682149,112650496,0.0,0.0,0.0,1.0,-1.898578557302244e-05,-0.0011006114073097706,0.00011152132356073707,-0.06764572113752365,0.06712446361780167,-0.00383966788649559 +1769682149,144889088,0.0,0.0,0.0,1.0,-0.00011223168985452503,-0.0005859403172507882,0.00012119112943764776,-0.037323351949453354,-0.005930508486926556,-0.020920902490615845 +1769682149,175268352,0.0,0.0,0.0,1.0,-0.00024352410400751978,-0.00017624405154492706,0.00012700956722255796,-0.07800851762294769,0.14194168150424957,-0.04004364833235741 +1769682149,207265024,0.0,0.0,0.0,1.0,-0.0002537918626330793,0.00013703355216421187,0.00013435243454296142,-0.034011274576187134,-0.1596871018409729,-0.020336108282208443 +1769682149,257259008,0.0,0.0,0.0,1.0,-0.00033231565612368286,0.000378943863324821,0.00015059352153912187,-0.026500526815652847,-0.08117396384477615,-0.007355993147939444 +1769682149,275006976,0.0,0.0,0.0,1.0,-0.0003007692866958678,0.00048448334564454854,0.00017456857312936336,0.018989190459251404,0.00266123004257679,-0.005626192316412926 +1769682149,307950848,0.0,0.0,0.0,1.0,-0.00033045344753190875,0.0005000400124117732,0.00020025522098876536,-0.02995665930211544,0.07271844148635864,-0.0007882987847551703 +1769682149,342965504,0.0,0.0,0.0,1.0,-0.0003864294558297843,0.0004700009012594819,0.00022436687140725553,-0.011112615466117859,0.07551441341638565,0.0007363329059444368 +1769682149,376605696,0.0,0.0,0.0,1.0,-0.0004084026732016355,0.0004040827916469425,0.0002627889043651521,-0.011038909666240215,0.07544723898172379,-0.002837540814653039 +1769682149,410151168,0.0,0.0,0.0,1.0,-0.0004527608398348093,0.0003658888745121658,0.0002939074474852532,-0.030052173882722855,0.07280884683132172,0.003979838453233242 +1769682149,442327552,0.0,0.0,0.0,1.0,-0.000450030027423054,6.420507997972891e-05,0.0003318229573778808,0.00031651719473302364,-0.0002910770126618445,-0.015491250902414322 +1769682149,474107648,0.0,0.0,0.0,1.0,-0.00029827741673216224,-0.0007998694782145321,0.00038607639726251364,0.011304001323878765,-0.07569383829832077,-0.010273477993905544 +1769682149,514982144,0.0,0.0,0.0,1.0,-0.0002627905341796577,-0.0012535983696579933,0.00042574977851472795,-0.010841351002454758,0.0752689465880394,-0.01236662920564413 +1769682149,549191680,0.0,0.0,0.0,1.0,-0.0001641248381929472,-0.0016322109149768949,0.00046449160436168313,0.026725975796580315,0.08096959441900253,-0.0033613070845603943 +1769682149,575583488,0.0,0.0,0.0,1.0,-3.435845428612083e-06,-0.0018016749527305365,0.0004908745177090168,0.0,-0.0,0.0 +1769682149,608036352,0.0,0.0,0.0,1.0,0.0001824800274334848,-0.0018672349397093058,0.000515665567945689,-0.011249224655330181,0.07564966380596161,0.007893433794379234 +1769682149,656246272,0.0,0.0,0.0,1.0,0.0001536846102681011,-0.0018386561423540115,0.0005373993190005422,-0.018964266404509544,-0.0026815058663487434,0.004438685718923807 +1769682149,674169856,0.0,0.0,0.0,1.0,0.00018366066797170788,-0.0018038938287645578,0.0005415850318968296,-0.02987445890903473,0.07265575975179672,-0.004349098540842533 +1769682149,707427840,0.0,0.0,0.0,1.0,0.00020750176918227226,-0.0016900161281228065,0.0005528933834284544,-0.01905934512615204,-0.0025913151912391186,0.009207302704453468 +1769682149,740841472,0.0,0.0,0.0,1.0,0.00013093059533275664,-0.0015956228598952293,0.0005474022473208606,0.018939903005957603,0.0027028867043554783,-0.0032500249799340963 +1769682149,777721600,0.0,0.0,0.0,1.0,0.0001950003788806498,-0.0015509296208620071,0.0005357324262149632,-0.04106370359659195,0.14826342463493347,0.001165538327768445 +1769682149,808113664,0.0,0.0,0.0,1.0,0.0002026803995249793,-0.0015102955512702465,0.0005214304546825588,-0.04883359745144844,0.0699780136346817,9.923230390995741e-05 +1769682149,841318656,0.0,0.0,0.0,1.0,0.00022119091590866446,-0.0014522576238960028,0.000510417390614748,0.011095155030488968,-0.07551689445972443,-0.0007446808740496635 +1769682149,875800576,0.0,0.0,0.0,1.0,0.00013115575711708516,-0.0014576137764379382,0.0004860427579842508,0.011164283379912376,-0.07558438926935196,-0.004319754894822836 +1769682149,910823168,0.0,0.0,0.0,1.0,1.980471279239282e-05,-0.0015500738518312573,0.00046413790551014245,0.018751299008727074,0.0028805520851165056,0.006278274580836296 +1769682149,943255040,0.0,0.0,0.0,1.0,-3.469512739684433e-05,-0.0015747155994176865,0.0004519422654993832,0.00011722140334313735,-0.00011212382378289476,-0.005958260968327522 +1769682149,974681856,0.0,0.0,0.0,1.0,-4.639361213776283e-05,-0.0015313742915168405,0.00044547460856847465,0.02979537658393383,-0.0725928321480751,0.00791300367563963 +1769682150,7889920,0.0,0.0,0.0,1.0,-1.894525485113263e-05,-0.001516763586550951,0.00044473851448856294,-0.029771460220217705,0.07257082313299179,-0.009103119373321533 +1769682150,60310272,0.0,0.0,0.0,1.0,-0.00012420566054061055,-0.001475451048463583,0.00044121438986621797,-0.01122710108757019,0.07565245777368546,0.00789818074554205 +1769682150,67710720,0.0,0.0,0.0,1.0,-9.020157449413091e-05,-0.0014522775309160352,0.00043835528776980937,0.007851758971810341,0.07821789383888245,-0.002510796533897519 +1769682150,108037632,0.0,0.0,0.0,1.0,-4.2209056118736044e-05,-0.0009182970388792455,0.0004195565707050264,0.019563622772693634,0.0020945831201970577,-0.035435210913419724 +1769682150,143294976,0.0,0.0,0.0,1.0,8.12112630228512e-05,-0.0002644220367074013,0.0004383897758089006,-0.02147534117102623,0.15036453306674957,-0.034250084310770035 +1769682150,174130944,0.0,0.0,0.0,1.0,0.00017254096746910363,0.00041577662341296673,0.00044774464913643897,0.030484799295663834,-0.07326795160770416,-0.02784307859838009 +1769682150,209195264,0.0,0.0,0.0,1.0,0.00010172814654652029,0.0007276819087564945,0.00044920307118445635,-0.010734847746789455,0.07518243044614792,-0.017126062884926796 +1769682150,243452160,0.0,0.0,0.0,1.0,0.0001611296902410686,0.0008688748348504305,0.0004371821996755898,0.00020874090841971338,-0.00020183849846944213,-0.010724913328886032 +1769682150,274106624,0.0,0.0,0.0,1.0,0.0001782274921424687,0.0009243597160093486,0.00041007279651239514,0.04902784898877144,-0.07019028812646866,-0.010840332135558128 +1769682150,307599616,0.0,0.0,0.0,1.0,0.00014321127673611045,0.0008569101337343454,0.00038361255428753793,0.048771366477012634,-0.06994405388832092,0.0022694533690810204 +1769682150,347506688,0.0,0.0,0.0,1.0,0.00023761429474689066,0.000721271731890738,0.00034865341149270535,0.007837846875190735,0.07823935151100159,-0.0013208076125010848 +1769682150,376085504,0.0,0.0,0.0,1.0,0.00019976505427621305,0.0006386928143911064,0.0003237938799429685,0.0596836656332016,-0.1453074961900711,0.00986951868981123 +1769682150,408304640,0.0,0.0,0.0,1.0,0.0001961278758244589,0.0004848188254982233,0.0003050205414183438,0.08634427934885025,-0.064259372651577,0.011250745505094528 +1769682150,456145664,0.0,0.0,0.0,1.0,0.0002835886843968183,0.00031409371877089143,0.0003047583741135895,0.05670176073908806,0.008203115314245224,-0.003813363378867507 +1769682150,474633984,0.0,0.0,0.0,1.0,0.0005401225644163787,-0.000351002934621647,0.00033075985265895724,0.10544580966234207,-0.06172184273600578,-0.0003458610735833645 +1769682150,510411008,0.0,0.0,0.0,1.0,0.0006719852099195123,-0.0006624439265578985,0.0003466376510914415,0.0755947157740593,0.010943072848021984,-0.004689319059252739 +1769682150,541070848,0.0,0.0,0.0,1.0,0.0005538374534808099,-0.000839939049910754,0.00035929324803873897,0.08655165135860443,-0.0644652396440506,0.0005268475506454706 +1769682150,574303744,0.0,0.0,0.0,1.0,0.0005369357531890273,-0.0009540727478452027,0.00037420607986859977,0.08655072003602982,-0.06446650624275208,0.000525100389495492 +1769682150,608188928,0.0,0.0,0.0,1.0,0.00047391062253154814,-0.0009401725837960839,0.00038324258639477193,0.0534982830286026,0.1619357466697693,-0.005603892263025045 +1769682150,646255872,0.0,0.0,0.0,1.0,0.0005087777972221375,-0.000843112706206739,0.00040025467751547694,0.08657219260931015,-0.06449142843484879,-0.0006698155775666237 +1769682150,676341760,0.0,0.0,0.0,1.0,0.0005155755789019167,-0.000771111052017659,0.0004209328326396644,0.10539481788873672,-0.06168452277779579,0.002026586327701807 +1769682150,710055936,0.0,0.0,0.0,1.0,0.0005290963454172015,-0.0007069445564411581,0.0004410201217979193,0.045564185827970505,0.08378574252128601,0.0004846242954954505 +1769682150,759569408,0.0,0.0,0.0,1.0,0.0005174829275347292,-0.0005413581384345889,0.0004779778828378767,0.04561194032430649,0.08373956382274628,-0.0019014767603948712 +1769682150,773827072,0.0,0.0,0.0,1.0,0.0005478016682900488,-0.00047981349052861333,0.0005008454318158329,0.05663273110985756,0.00826291460543871,-0.00025297171669080853 +1769682150,807789824,0.0,0.0,0.0,1.0,0.00041484879329800606,-0.00048543658340349793,0.0005180697189643979,0.10534504055976868,-0.06164547801017761,0.004405842162668705 +1769682150,850885120,0.0,0.0,0.0,1.0,0.0004559934895951301,-0.00048411087482236326,0.0005297237075865269,0.08337870985269547,0.0892372578382492,-0.002474042121320963 +1769682150,875192832,0.0,0.0,0.0,1.0,0.0003160693740937859,-0.0004977394128218293,0.0005195836420170963,0.0754111111164093,0.011111801490187645,0.004822420421987772 +1769682150,910010112,0.0,0.0,0.0,1.0,6.964860222069547e-05,-0.0006605804082937539,0.0004798712907359004,0.11644872277975082,-0.13721837103366852,0.001288940547965467 +1769682150,941024000,0.0,0.0,0.0,1.0,-7.709004421485588e-06,-0.0007858762401156127,0.0004508362035267055,0.09432771056890488,0.013824543915688992,0.002747048856690526 +1769682150,980920832,0.0,0.0,0.0,1.0,-9.33575356611982e-05,-0.0009407991892658174,0.0004194126813672483,0.16512852907180786,-0.20711062848567963,0.007130267098546028 +1769682151,26363136,0.0,0.0,0.0,1.0,-0.00014327677490655333,-0.0009109099628403783,0.00041951172170229256,0.11335879564285278,0.016422336921095848,-0.005290552973747253 +1769682151,49396736,0.0,0.0,0.0,1.0,-0.00012156589946243912,-0.0008588160271756351,0.0004379234742373228,0.14321660995483398,-0.056274645030498505,-0.0021425094455480576 +1769682151,74232576,0.0,0.0,0.0,1.0,-0.00011542494758032262,-0.0007739586289972067,0.00046963163185864687,0.12432260811328888,-0.059013091027736664,-0.0012632026337087154 +1769682151,111534848,0.0,0.0,0.0,1.0,-0.00015689560677856207,-0.0006598547915928066,0.0005150871584191918,0.08680889755487442,-0.06476011127233505,-0.013799470849335194 +1769682151,144381440,0.0,0.0,0.0,1.0,0.00017669454973656684,-0.00018950623052660376,0.000590217940043658,0.09480787068605423,0.013338337652385235,-0.02229238674044609 +1769682151,174265600,0.0,0.0,0.0,1.0,0.0003265433188062161,0.00024748319992795587,0.0006707163411192596,0.1056993305683136,-0.062028668820858,-0.01468245591968298 +1769682151,208183040,0.0,0.0,0.0,1.0,0.00041688952478580177,0.00043583428487181664,0.000722667493391782,0.151055708527565,0.021970830857753754,-0.0022996291518211365 +1769682151,257125888,0.0,0.0,0.0,1.0,0.0003918106376659125,0.0005668386584147811,0.0007678757538087666,0.12436184287071228,-0.05907224118709564,-0.003643882228061557 +1769682151,274503168,0.0,0.0,0.0,1.0,0.0004184096760582179,0.0006685755797661841,0.000782644550781697,0.15418478846549988,-0.1317516714334488,0.0007067002588883042 +1769682151,307941376,0.0,0.0,0.0,1.0,0.00039419057429768145,0.000668418244458735,0.0007847632514312863,0.12431345880031586,-0.059032537043094635,-0.0012543379561975598 +1769682151,340753152,0.0,0.0,0.0,1.0,0.00033684799564071,0.0006464050966314971,0.0007837998564355075,0.10222925990819931,0.09201440960168839,0.00020096113439649343 +1769682151,378742272,0.0,0.0,0.0,1.0,0.00039359781658276916,0.0005924225552007556,0.0007557586068287492,0.1807863563299179,-0.05064227059483528,0.006833173334598541 +1769682151,408626432,0.0,0.0,0.0,1.0,0.0004024827212560922,0.00046067070798017085,0.0007327017956413329,0.12110507488250732,0.0947638675570488,0.0005127287004143 +1769682151,448925952,0.0,0.0,0.0,1.0,0.0003831909561995417,0.0004460696072783321,0.0006865790928713977,0.16977034509181976,0.024857686832547188,0.006370825227349997 +1769682151,475461120,0.0,0.0,0.0,1.0,0.0003829152847174555,0.0003681713715195656,0.0006353021017275751,0.18873369693756104,0.027516836300492287,0.0019169142469763756 +1769682151,510948608,0.0,0.0,0.0,1.0,0.0005920411203987896,0.00011044315760955215,0.00058988225646317,0.1998126357793808,-0.048058707267045975,-0.0011856579221785069 +1769682151,541876480,0.0,0.0,0.0,1.0,0.0005808405694551766,-0.0001289786450797692,0.0005445132264867425,0.1402827352285385,0.09720905125141144,-0.014669392257928848 +1769682151,576022784,0.0,0.0,0.0,1.0,0.0004373838019091636,-0.00013906903041061014,0.0004933162708766758,0.14016979932785034,0.09732069075107574,-0.008713810704648495 +1769682151,607677696,0.0,0.0,0.0,1.0,0.000366711727110669,-0.00010557024506852031,0.0004649334878195077,0.20760688185691833,0.030256487429142,0.002224904950708151 +1769682151,655801344,0.0,0.0,0.0,1.0,0.0003343008575029671,3.388539334991947e-05,0.0004430926637724042,0.21083654463291168,-0.12359978258609772,-0.00190034881234169 +1769682151,674727424,0.0,0.0,0.0,1.0,0.00028875083080492914,6.871926598250866e-05,0.0004289406933821738,0.22654806077480316,0.03293319046497345,-0.001039855182170868 +1769682151,710182144,0.0,0.0,0.0,1.0,0.00029437115881592035,7.4630523158703e-05,0.00042001958354376256,0.18082185089588165,-0.05071462690830231,0.0044644721783697605 +1769682151,742340864,0.0,0.0,0.0,1.0,0.0002597165002953261,9.568851965013891e-05,0.00040610515861772,0.18866823613643646,0.027562376111745834,0.0054893940687179565 +1769682151,781029632,0.0,0.0,0.0,1.0,0.00029068096773698926,0.00019158168288413435,0.0003899885923601687,0.19962289929389954,-0.047899190336465836,0.008352899923920631 +1769682151,808333568,0.0,0.0,0.0,1.0,0.0002589013602118939,0.0001849670079536736,0.0003687012067530304,0.2075633853673935,0.03028545156121254,0.004610501229763031 +1769682151,844125696,0.0,0.0,0.0,1.0,0.0002853904734365642,0.00017798502813093364,0.00035056271008215845,0.2153906673192978,0.10858523100614548,0.006825213320553303 +1769682151,875481856,0.0,0.0,0.0,1.0,0.00021963901235722005,0.0002602324530016631,0.00033129664370790124,0.19668151438236237,0.105670265853405,-0.001826189924031496 +1769682151,915579136,0.0,0.0,0.0,1.0,0.00023338083701673895,0.0002605935442261398,0.0003222720988560468,0.23757074773311615,-0.04261462390422821,-0.001742529682815075 +1769682151,945168384,0.0,0.0,0.0,1.0,0.0001417066960129887,0.0001276883267564699,0.0002952935465145856,0.25618863105773926,-0.03961341083049774,0.011678784154355526 +1769682151,975056128,0.0,0.0,0.0,1.0,1.695583159744274e-05,1.681202593317721e-05,0.000281159533187747,0.2484038919210434,-0.11796342581510544,0.007083800621330738 +1769682152,11312128,0.0,0.0,0.0,1.0,-1.585304744367022e-05,-5.4322379583027214e-05,0.0002802802191581577,0.23768459260463715,-0.04273698478937149,-0.007698602043092251 +1769682152,56369664,0.0,0.0,0.0,1.0,-5.260953548713587e-05,-3.1991308787837625e-05,0.0002913649077527225,0.28621402382850647,-0.11253814399242401,0.004130241461098194 +1769682152,74968576,0.0,0.0,0.0,1.0,-1.7206908523803577e-05,-4.568125223158859e-05,0.0003081892791669816,0.25634828209877014,-0.039784543216228485,0.0033364000264555216 +1769682152,107636480,0.0,0.0,0.0,1.0,-6.0599886637646705e-05,3.041182026208844e-05,0.000319550366839394,0.2750815451145172,-0.036899127066135406,0.010797644034028053 +1769682152,140692480,0.0,0.0,0.0,1.0,-0.00014137348625808954,4.19333518948406e-05,0.0003284377744421363,0.29399892687797546,-0.03419880568981171,0.008725753054022789 +1769682152,176151552,0.0,0.0,0.0,1.0,-4.100523074157536e-05,0.0001591992622707039,0.00032975818612612784,0.24867293238639832,-0.11825554817914963,-0.007217162288725376 +1769682152,209049344,0.0,0.0,0.0,1.0,6.85940685798414e-05,0.0003914614499080926,0.0003149570256937295,0.26455095410346985,0.03813660517334938,-0.013513640500605106 +1769682152,245012736,0.0,0.0,0.0,1.0,8.796474139671773e-05,0.0005640461458824575,0.00028460679459385574,0.2645514905452728,0.03813423961400986,-0.013509754091501236 +1769682152,275096064,0.0,0.0,0.0,1.0,0.00011029353481717408,0.0008940964471548796,0.00021833977370988578,0.24860072135925293,-0.11819342523813248,-0.0036273386795073748 +1769682152,309621248,0.0,0.0,0.0,1.0,0.00011885992716997862,0.000977058312855661,0.0001492466835770756,0.3617851734161377,-0.10165867954492569,0.00064091756939888 +1769682152,341629696,0.0,0.0,0.0,1.0,0.00012834490917157382,0.0010049904230982065,8.241533214459196e-05,0.37739095091819763,0.05501130595803261,0.00865267775952816 +1769682152,374487552,0.0,0.0,0.0,1.0,0.0001718078419798985,0.0009831361239776015,-2.1464413293870166e-05,0.26427555084228516,0.0384061336517334,0.0008241680916398764 +1769682152,408172288,0.0,0.0,0.0,1.0,0.00019079876074101776,0.0008857361390255392,-8.72225864441134e-05,0.19968296587467194,-0.048000529408454895,0.004824417643249035 +1769682152,445083904,0.0,0.0,0.0,1.0,0.00023049947049003094,0.0007908943807706237,-0.00016531985602341592,0.28604212403297424,-0.11239667236804962,0.012537524104118347 +1769682152,476360448,0.0,0.0,0.0,1.0,0.00025885095237754285,0.0006769630126655102,-0.00020938956004101783,0.35061097145080566,-0.025963932275772095,0.009744878858327866 +1769682152,508602368,0.0,0.0,0.0,1.0,0.00029694868135266006,0.000632047769613564,-0.00023744870850350708,0.3617633879184723,-0.10162961483001709,0.0018983755726367235 +1769682152,555137024,0.0,0.0,0.0,1.0,0.0003425611066631973,0.0006406651227734983,-0.0002655611024238169,0.324020653963089,-0.10712437331676483,0.0012735091149806976 +1769682152,575116032,0.0,0.0,0.0,1.0,0.00017775646119844168,0.0004599006788339466,-0.0003189301351085305,0.3996489644050598,-0.0962633565068245,-0.0046003712341189384 +1769682152,608646400,0.0,0.0,0.0,1.0,0.00012093687109882012,0.00010610777826514095,-0.00036721309879794717,0.302133709192276,0.04380214214324951,-0.004462869837880135 +1769682152,641347072,0.0,0.0,0.0,1.0,3.9346592529909685e-05,-0.0001304458564845845,-0.0004192245251033455,0.39962777495384216,-0.09623118489980698,-0.003406439907848835 +1769682152,674790656,0.0,0.0,0.0,1.0,-0.00024212854623328894,-0.00021263145026750863,-0.0005059099057689309,0.3995594084262848,-0.09615416824817657,0.0001649702899158001 +1769682152,708119552,0.0,0.0,0.0,1.0,-0.00032554648350924253,-0.0003009964420925826,-0.0005810487200506032,0.30189794301986694,0.04404797777533531,0.007448875345289707 +1769682152,745982976,0.0,0.0,0.0,1.0,-0.0004045280220452696,-0.0003309885796625167,-0.0006728253792971373,0.33982664346694946,0.04937175661325455,-0.001454905141144991 +1769682152,775030784,0.0,0.0,0.0,1.0,-0.0004065344110131264,-0.0002861951070372015,-0.0007395403808914125,0.29106083512306213,0.1194051206111908,-0.0013854056596755981 +1769682152,809226496,0.0,0.0,0.0,1.0,-0.0004203127173241228,-0.00020056241191923618,-0.0008023072732612491,0.38840413093566895,-0.020453037694096565,0.008000530302524567 +1769682152,847166464,0.0,0.0,0.0,1.0,-0.0004005185910500586,-0.0001408750977134332,-0.000880843959748745,0.38831159472465515,-0.020347632467746735,0.012764403596520424 +1769682152,874972672,0.0,0.0,0.0,1.0,-0.0004459105839487165,-7.765590999042615e-05,-0.0009440902504138649,0.3993872404098511,-0.09591016918420792,0.00967160239815712 +1769682152,907603968,0.0,0.0,0.0,1.0,-0.0004534746112767607,-8.548299956601113e-05,-0.0010141842067241669,0.38838282227516174,-0.02039477787911892,0.009186792187392712 +1769682152,960875776,0.0,0.0,0.0,1.0,-0.0004236237145960331,-0.00015087828796822578,-0.0011211398523300886,0.4261489808559418,-0.014893263578414917,0.008624733425676823 +1769682152,969246976,0.0,0.0,0.0,1.0,-0.0004408914828673005,-0.00018902831652667373,-0.0011818811763077974,0.3994198739528656,-0.09589509665966034,0.00847175158560276 +1769682153,8823040,0.0,0.0,0.0,1.0,-0.00045929549378342927,-0.0001451906282454729,-0.0013126588892191648,0.44808924198150635,-0.16577482223510742,0.014344785362482071 +1769682153,41551872,0.0,0.0,0.0,1.0,-0.0004191495245322585,-0.0001705390022834763,-0.0014124701265245676,0.4150850176811218,0.06070337072014809,0.010523112490773201 +1769682153,75695872,0.0,0.0,0.0,1.0,-0.0002313688164576888,-4.1644609154900536e-05,-0.0015019202837720513,0.3885970711708069,-0.02051762491464615,-0.0015485193580389023 +1769682153,112130048,0.0,0.0,0.0,1.0,-0.00013181452231947333,-1.7988350009545684e-06,-0.0015675934264436364,0.3507874011993408,-0.025946959853172302,0.001394468592479825 +1769682153,144054272,0.0,0.0,0.0,1.0,-5.627899008686654e-05,3.356861634529196e-05,-0.0016177314100787044,0.42622390389442444,-0.014854157343506813,0.005041459575295448 +1769682153,174650624,0.0,0.0,0.0,1.0,2.9703725886065513e-05,7.772095705149695e-05,-0.0016612838953733444,0.46387094259262085,-0.0092079509049654,0.010440687648952007 +1769682153,208009728,0.0,0.0,0.0,1.0,0.00013167253928259015,-1.7156671674456447e-05,-0.001669536461122334,0.4261082112789154,-0.014684137888252735,0.011000871658325195 +1769682153,259796480,0.0,0.0,0.0,1.0,0.00014168050256557763,-0.0001326517085544765,-0.0016677046660333872,0.43710726499557495,-0.0901079773902893,0.013859553262591362 +1769682153,275483392,0.0,0.0,0.0,1.0,0.00013416618457995355,-8.530638297088444e-05,-0.0016575860790908337,0.49056339263916016,0.07189396768808365,0.010591469705104828 +1769682153,308036352,0.0,0.0,0.0,1.0,0.00017727560771163553,1.2615568266483024e-05,-0.0016509194392710924,0.4639661908149719,-0.009199262596666813,0.005670640151947737 +1769682153,356460800,0.0,0.0,0.0,1.0,6.376155943144113e-05,0.00048694113502278924,-0.0016717045800760388,0.4155673682689667,0.060406528413295746,-0.015691837295889854 +1769682153,375121920,0.0,0.0,0.0,1.0,-2.6601208446663804e-05,0.0007899890770204365,-0.0016886383527889848,0.49099454283714294,0.07153953611850739,-0.012034701183438301 +1769682153,408536320,0.0,0.0,0.0,1.0,-9.246716945199296e-05,0.00096350401872769,-0.00172006047796458,0.4374578297138214,-0.0903121680021286,-0.002798170316964388 +1769682153,442567424,0.0,0.0,0.0,1.0,-0.00012433886877261102,0.0010242591379210353,-0.0017515509389340878,0.4263705015182495,-0.014771690592169762,-0.0020721103064715862 +1769682153,479049216,0.0,0.0,0.0,1.0,-0.00014544464647769928,0.0011087844613939524,-0.0017816786421462893,0.4262542724609375,-0.01462679821997881,0.003904844168573618 +1769682153,510327040,0.0,0.0,0.0,1.0,-0.00015630939742550254,0.0010712658986449242,-0.0017998798284679651,0.41503581404685974,0.061027027666568756,0.010589953511953354 +1769682153,546184704,0.0,0.0,0.0,1.0,-0.0001942886592587456,0.0010341766756027937,-0.001810053363442421,0.5504782795906067,-0.07333730161190033,0.011099749244749546 +1769682153,574972928,0.0,0.0,0.0,1.0,-0.00020816341566387564,0.0009910265216603875,-0.0018136162543669343,0.4749387502670288,-0.08435794711112976,0.012218007817864418 +1769682153,612824576,0.0,0.0,0.0,1.0,-0.00020364735973998904,0.0009019756689667702,-0.001813333947211504,0.42618632316589355,-0.014458036981523037,0.0075358860194683075 +1769682153,644097280,0.0,0.0,0.0,1.0,-0.00015883904416114092,0.0008013842161744833,-0.0018181189661845565,0.4749472737312317,-0.08430641144514084,0.0122421495616436 +1769682153,676097280,0.0,0.0,0.0,1.0,-0.0002127947227563709,0.000819273991510272,-0.0018203133950009942,0.4749056100845337,-0.08422622084617615,0.014640545472502708 +1769682153,707991296,0.0,0.0,0.0,1.0,-0.0001959243672899902,0.0007733852253295481,-0.0018354374915361404,0.42623576521873474,-0.014426428824663162,0.005187088157981634 +1769682153,759490304,0.0,0.0,0.0,1.0,-0.0002503813593648374,0.0006744813872501254,-0.0018638874171301723,0.5127451419830322,-0.07869856059551239,0.010543351992964745 +1769682153,769222912,0.0,0.0,0.0,1.0,-0.0004832327540498227,0.0004536673950497061,-0.0018914614338427782,0.5019432902336121,-0.0034883925691246986,-0.005420058034360409 +1769682153,824697088,0.0,0.0,0.0,1.0,-0.0008944551809690893,-0.00015105791680980474,-0.0019759731367230415,0.5509159564971924,-0.07348796725273132,-0.010255743749439716 +1769682153,843800576,0.0,0.0,0.0,1.0,-0.0011230423115193844,-0.0005257384036667645,-0.00204836786724627,0.5130442380905151,-0.07888225466012955,-0.003761136904358864 +1769682153,875620352,0.0,0.0,0.0,1.0,-0.0011706211371347308,-0.00074677326483652,-0.00213801022619009,0.5019439458847046,-0.003376009874045849,-0.0054382444359362125 +1769682153,907827968,0.0,0.0,0.0,1.0,-0.0012189908884465694,-0.0009175756713375449,-0.002209076890721917,0.463950514793396,-0.008663788437843323,0.007011789362877607 +1769682153,943765248,0.0,0.0,0.0,1.0,-0.0012275507906451821,-0.0010065864771604538,-0.0022713528014719486,0.4793547987937927,0.1479538530111313,0.009100127965211868 +1769682153,974700544,0.0,0.0,0.0,1.0,-0.0012253758031874895,-0.0010679414262995124,-0.002356338081881404,0.5393686890602112,0.00260789692401886,0.010646333917975426 +1769682154,26318336,0.0,0.0,0.0,1.0,-0.0011889147572219372,-0.0010799787705764174,-0.00239686481654644,0.512837827205658,-0.07846040278673172,0.008059061132371426 +1769682154,57502208,0.0,0.0,0.0,1.0,-0.0011399934301152825,-0.0010742483427748084,-0.002423187717795372,0.5503411293029785,-0.07260395586490631,0.020590659230947495 +1769682154,70796032,0.0,0.0,0.0,1.0,-0.0010855747386813164,-0.0011260871542617679,-0.0024221620988100767,0.5727909207344055,-0.22365157306194305,0.015517177060246468 +1769682154,109023232,0.0,0.0,0.0,1.0,-0.0009589087567292154,-0.000891247414983809,-0.0023948836605995893,0.5282447934150696,0.07821007072925568,0.007744367700070143 +1769682154,141266944,0.0,0.0,0.0,1.0,-0.0009343404090031981,-0.0007979048532433808,-0.002358362078666687,0.5017334222793579,-0.002866966649889946,0.005156231112778187 +1769682154,180605440,0.0,0.0,0.0,1.0,-0.0008537682006135583,-0.000643938547000289,-0.002295105252414942,0.6037610173225403,0.08941757678985596,0.0054204994812607765 +1769682154,208217856,0.0,0.0,0.0,1.0,-0.0008476721704937518,-0.0006557086599059403,-0.0022503489162772894,0.5016872882843018,-0.002742122858762741,0.0075161037966609 +1769682154,243528192,0.0,0.0,0.0,1.0,-0.0008512359345331788,-0.0007268001791089773,-0.0022021611221134663,0.5505401492118835,-0.07249371707439423,0.01334407553076744 +1769682154,275793408,0.0,0.0,0.0,1.0,-0.0008645869675092399,-0.0008396573248319328,-0.0021540222223848104,0.4904642105102539,0.0728321522474289,0.008247911930084229 +1769682154,313842944,0.0,0.0,0.0,1.0,-0.0008252689149230719,-0.0008646381902508438,-0.002123679732903838,0.52823406457901,0.078423872590065,0.006487155333161354 +1769682154,343906304,0.0,0.0,0.0,1.0,-0.0008274560677818954,-0.0008727024542167783,-0.0020971433259546757,0.6149174571037292,0.014175286516547203,0.006978148594498634 +1769682154,375622400,0.0,0.0,0.0,1.0,-0.0002472829073667526,-0.0005648898659273982,-0.0019219384994357824,0.6037700772285461,0.0896308422088623,0.0029589608311653137 +1769682154,408099328,0.0,0.0,0.0,1.0,-6.61508966004476e-05,-0.000394173403037712,-0.0018331923056393862,0.599351167678833,-0.14203400909900665,0.02147486060857773 +1769682154,449506560,0.0,0.0,0.0,1.0,5.808345304103568e-05,-0.00023695359413977712,-0.0017614952521398664,0.5882518291473389,-0.06662997603416443,0.015083039179444313 +1769682154,475159296,0.0,0.0,0.0,1.0,5.811516166431829e-05,-0.00021228360128588974,-0.0017602378502488136,0.5015506744384766,-0.0023396145552396774,0.014583287760615349 +1769682154,508271872,0.0,0.0,0.0,1.0,8.32843070384115e-05,-0.00022053760767448694,-0.0017774782609194517,0.6148205995559692,0.014455655589699745,0.011704444885253906 +1769682154,540782336,0.0,0.0,0.0,1.0,0.00013902691716793925,-0.00025931434356607497,-0.001824133563786745,0.5884251594543457,-0.06669052690267563,0.006730060093104839 +1769682154,580736512,0.0,0.0,0.0,1.0,0.00014988075417932123,-0.0002616993442643434,-0.001895342138595879,0.5771635174751282,0.008844735100865364,0.0074888793751597404 +1769682154,610514688,0.0,0.0,0.0,1.0,0.00013963556557428092,-0.00019870130927301943,-0.0019518950721248984,0.5995197296142578,-0.14192602038383484,0.015489799901843071 +1769682154,643019520,0.0,0.0,0.0,1.0,0.00014488381566479802,-0.0001796216965885833,-0.0020057987421751022,0.6148637533187866,0.014563120901584625,0.009302639402449131 +1769682154,675770880,0.0,0.0,0.0,1.0,1.7102371202781796e-05,-1.2264483302715234e-05,-0.002081417478621006,0.6002582907676697,-0.14252716302871704,-0.021457653492689133 +1769682154,710088448,0.0,0.0,0.0,1.0,-0.00021325808484107256,0.0005233513074927032,-0.0021542985923588276,0.5510721206665039,-0.07245716452598572,-0.011784017086029053 +1769682154,741755904,0.0,0.0,0.0,1.0,-0.00037291209446266294,0.0008805944817140698,-0.002196925925090909,0.5774622559547424,0.008747106418013573,-0.007994182407855988 +1769682154,774604288,0.0,0.0,0.0,1.0,-0.0005362334195524454,0.0011963717406615615,-0.0022237382363528013,0.5886204838752747,-0.06655565649271011,-0.0015838779509067535 +1769682154,809218048,0.0,0.0,0.0,1.0,-0.0005569016211666167,0.0013589991722255945,-0.002225446281954646,0.5773450136184692,0.008947428315877914,-0.001987638883292675 +1769682154,857473280,0.0,0.0,0.0,1.0,-0.0007009675027802587,0.0014885426498949528,-0.002239341614767909,0.5395057797431946,0.003463760018348694,0.0033684284426271915 +1769682154,874555136,0.0,0.0,0.0,1.0,-0.0007665797020308673,0.0014972164062783122,-0.0022653306368738413,0.6147368550300598,0.014994235709309578,0.015393219888210297 +1769682154,907934720,0.0,0.0,0.0,1.0,-0.0008112182840704918,0.001431444426998496,-0.002296973718330264,0.550614058971405,-0.07174839824438095,0.013371292501688004 +1769682154,942749440,0.0,0.0,0.0,1.0,-0.0008583316812291741,0.0013455305015668273,-0.002331996103748679,0.6259889602661133,-0.06034122034907341,0.018249783664941788 +1769682157,982834432,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,8748800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,46414080,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,75254016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,7.235601515276358e-05,-4.3057490984210745e-05,-0.0023827017284929752 +1769682158,111570688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,150701312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,176898048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,208294400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,260433152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,270217472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,308558336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,341800960,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,376958464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,411895040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,445829888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,475502336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,511804160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,546373376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,575665152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,608755712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,661246208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,668736000,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,710725120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,753724416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,7.235661905724555e-05,-4.305758557165973e-05,-0.0023827017284929752 +1769682158,775923200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,802105856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.03771260380744934,0.0056450446136295795,0.001043225871399045 +1769682158,845812480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,875195136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,909945856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,957712384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682158,974922240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682159,9288192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682159,54940928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-3.6178436857881024e-05,2.152878550987225e-05,0.0011913508642464876 +1769682159,75723776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682159,109018624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682159,147242240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682159,175731712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,3.6178498703520745e-05,-2.1528781871893443e-05,-0.0011913508642464876 +1769682159,210075904,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682159,247044608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682159,275342336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682159,308494080,0.0,0.0,0.0,1.0,-0.005357267335057259,-0.05125614255666733,1.4754361473023891e-05,2.2145848274230957,-0.2665383815765381,0.918380081653595 +1769682159,342375424,0.0,0.0,0.0,1.0,-0.007381204981356859,-0.0982644334435463,-6.770242907805368e-05,0.837634265422821,-0.017085306346416473,0.5644326210021973 +1769682159,376398592,0.0,0.0,0.0,1.0,-0.006765956990420818,-0.1168249249458313,-0.00026779109612107277,-0.4304896295070648,0.016703445464372635,0.18202978372573853 +1769682159,410364928,0.0,0.0,0.0,1.0,-0.00551670603454113,-0.10841453820466995,-0.00046804925659671426,-1.0517606735229492,0.07343439757823944,-0.04881182312965393 +1769682159,456365568,0.0,0.0,0.0,1.0,-0.0039102910086512566,-0.08943179994821548,-0.0006716771167702973,-1.3848280906677246,0.2517596483230591,-0.21878519654273987 +1769682159,475952896,0.0,0.0,0.0,1.0,-0.001875261659733951,-0.05822903662919998,-0.0009486908675171435,-1.3878320455551147,0.017850175499916077,-0.3230014741420746 +1769682159,508740352,0.0,0.0,0.0,1.0,-0.000571624783333391,-0.03585948795080185,-0.0011346471728757024,-1.3991115093231201,0.09266825765371323,-0.3571909964084625 +1769682159,549813248,0.0,0.0,0.0,1.0,0.0007168333977460861,-0.011965662240982056,-0.001338423229753971,-1.124382734298706,0.05721002444624901,-0.3225291967391968 +1769682159,575200512,0.0,0.0,0.0,1.0,0.0013047362444922328,0.0005897427326999605,-0.0014575772220268846,-0.9099204540252686,0.16735699772834778,-0.27181583642959595 +1769682159,609319168,0.0,0.0,0.0,1.0,0.0016293812077492476,0.008710010908544064,-0.0015503631439059973,-0.7635596990585327,-0.04095543175935745,-0.20237189531326294 +1769682159,647936000,0.0,0.0,0.0,1.0,0.001708128023892641,0.013391285203397274,-0.0016381550813093781,-0.6362792253494263,0.13410261273384094,-0.11004053056240082 +1769682159,675405056,0.0,0.0,0.0,1.0,0.001553805428557098,0.013295787386596203,-0.0017021624371409416,-0.5012484192848206,0.0012501385062932968,-0.0431576631963253 +1769682159,709694464,0.0,0.0,0.0,1.0,0.0012858135160058737,0.011202992871403694,-0.0017585981404408813,-0.528377115726471,-0.07888710498809814,0.01493459939956665 +1769682159,744887808,0.0,0.0,0.0,1.0,0.0010001442860811949,0.007702217902988195,-0.0018285540863871574,-0.48731905221939087,0.15933990478515625,0.04697326570749283 +1769682159,776923904,0.0,0.0,0.0,1.0,0.0006357516394928098,0.0029315692372620106,-0.001937613938935101,-0.5403127074241638,-0.002691483125090599,0.060916222631931305 +1769682159,809100544,0.0,0.0,0.0,1.0,0.0004166416765656322,0.00041070423321798444,-0.002002206863835454,-0.5176954865455627,-0.15357361733913422,0.06500591337680817 +1769682159,845369600,0.0,0.0,0.0,1.0,0.00014916289364919066,-0.002882492495700717,-0.0021186417434364557,-0.6761058568954468,0.1310718059539795,0.05563673377037048 +1769682159,875332608,0.0,0.0,0.0,1.0,9.198520274367183e-06,-0.004128474276512861,-0.0022062212228775024,-0.5890588760375977,0.06656692177057266,0.0365012101829052 +1769682159,909184256,0.0,0.0,0.0,1.0,-0.0001125194612541236,-0.005611565429717302,-0.0023210428189486265,-0.7511975169181824,0.11915503442287445,0.027636658400297165 +1769682159,943255552,0.0,0.0,0.0,1.0,-0.00010648708848748356,-0.005868107080459595,-0.0024153694976121187,-0.7660452723503113,-0.03771073743700981,0.014802834019064903 +1769682159,975424256,0.0,0.0,0.0,1.0,-0.00019081651407759637,-0.006302548106759787,-0.0025830273516476154,-0.7771933674812317,0.03737436234951019,-0.0019468367099761963 +1769682160,11292672,0.0,0.0,0.0,1.0,-0.00014948575699236244,-0.005426667630672455,-0.002696768846362829,-0.9015512466430664,0.09546107798814774,-0.017459280788898468 +1769682160,44540416,0.0,0.0,0.0,1.0,-0.00018289951549377292,-0.004771477542817593,-0.0028643307741731405,-0.8902426362037659,0.019993489608168602,-0.012258877046406269 +1769682160,75045888,0.0,0.0,0.0,1.0,-0.00015254550089593977,-0.004023903515189886,-0.002988915191963315,-0.8637552857398987,0.10082870721817017,-0.02515466697514057 +1769682160,108525312,0.0,0.0,0.0,1.0,-0.00015311542665585876,-0.0036106915213167667,-0.0031256454531103373,-0.852449893951416,0.025404758751392365,-0.018850475549697876 +1769682160,143469056,0.0,0.0,0.0,1.0,-0.0001328984508290887,-0.0033162827603518963,-0.003266574814915657,-0.9164736270904541,-0.06154380366206169,-0.020392585545778275 +1769682160,176523776,0.0,0.0,0.0,1.0,-0.00012119370512664318,-0.0030255629681050777,-0.003453589044511318,-0.9278488159179688,0.013736903667449951,-0.02290475368499756 +1769682160,209200384,0.0,0.0,0.0,1.0,-9.35394418775104e-05,-0.002477791626006365,-0.0035880464129149914,-0.9278793931007385,0.013678831979632378,-0.02044752612709999 +1769682160,255484416,0.0,0.0,0.0,1.0,-8.79083017935045e-05,-0.001966133713722229,-0.003722026012837887,-0.9016190767288208,0.09477309882640839,-0.017915748059749603 +1769682160,275956992,0.0,0.0,0.0,1.0,9.741121175466105e-06,-0.001554614631459117,-0.003918513655662537,-0.9507722854614258,0.16433672606945038,-0.019618503749370575 +1769682160,312110592,0.0,0.0,0.0,1.0,-3.624844248406589e-05,-0.0012465736363083124,-0.004078058060258627,-1.0034104585647583,0.0020205602049827576,-0.012600625865161419 +1769682160,342969344,0.0,0.0,0.0,1.0,-2.9654140234924853e-05,-0.0012741833925247192,-0.004231732804328203,-0.9280793070793152,0.013495957478880882,-0.0035666925832629204 +1769682160,375435520,0.0,0.0,0.0,1.0,-3.535619907779619e-05,-0.00015344267012551427,-0.004393334966152906,-1.0029823780059814,0.0010607913136482239,-0.0506625697016716 +1769682160,409400064,0.0,0.0,0.0,1.0,-3.417510015424341e-05,0.0025038314051926136,-0.0044715977273881435,-0.8521209955215454,0.023863421753048897,-0.050595443695783615 +1769682160,445960704,0.0,0.0,0.0,1.0,-7.296803232748061e-06,0.0037596458569169044,-0.0045762332156300545,-0.9017573595046997,0.0940549373626709,-0.013158350251615047 +1769682160,475555328,0.0,0.0,0.0,1.0,-0.00011016292410204187,0.002665627747774124,-0.004681784193962812,-0.8150132894515991,0.03024834394454956,0.0019778963178396225 +1769682160,509000448,0.0,0.0,0.0,1.0,-0.00016073213191702962,0.0012967641232535243,-0.0047861491329967976,-0.8528231382369995,0.02451973222196102,0.009939347393810749 +1769682160,561395456,0.0,0.0,0.0,1.0,-0.00024597340961918235,-0.00028305078740231693,-0.0049091181717813015,-0.8150928616523743,0.030076688155531883,0.007885012775659561 +1769682160,570458880,0.0,0.0,0.0,1.0,-0.0002727308601606637,-0.0009194439626298845,-0.00496825622394681,-0.8788912296295166,-0.05708910524845123,0.0003138883039355278 +1769682160,609808128,0.0,0.0,0.0,1.0,-0.00030935631366446614,-0.0016664261929690838,-0.005082380957901478,-0.852779746055603,0.02401638776063919,0.005223967134952545 +1769682160,658258432,0.0,0.0,0.0,1.0,-0.00031209434382617474,-0.0019334391690790653,-0.005162723828107119,-0.9019538760185242,0.09338024258613586,-0.003645949997007847 +1769682160,675191040,0.0,0.0,0.0,1.0,-0.0003382741706445813,-0.0018290200969204307,-0.005262169986963272,-0.8757854700088501,0.17429670691490173,-0.009442710317671299 +1769682160,709888512,0.0,0.0,0.0,1.0,-0.0002629139053169638,-0.00011806774273281917,-0.005292815156280994,-0.9277747869491577,0.011343782767653465,-0.032253384590148926 +1769682160,741781504,0.0,0.0,0.0,1.0,-0.00022536788310389966,0.0009915694827213883,-0.005316098220646381,-0.8901695609092712,0.017140869051218033,-0.023597709834575653 +1769682160,775559936,0.0,0.0,0.0,1.0,-0.00022823522158432752,0.0006200323114171624,-0.005378296133130789,-0.8642265796661377,0.09837760031223297,-0.011610706336796284 +1769682160,808869376,0.0,0.0,0.0,1.0,-0.000247974821832031,0.0003677505301311612,-0.005414871498942375,-0.9047236442565918,-0.1396680474281311,-0.013960548676550388 +1769682160,842976000,0.0,0.0,0.0,1.0,-0.0002937201934400946,0.0001459850900573656,-0.005453683435916901,-0.8903555870056152,0.016927141696214676,-0.008147946558892727 +1769682160,875260672,0.0,0.0,0.0,1.0,-0.0003301002143416554,-0.00027209168183617294,-0.00549545232206583,-0.9280157089233398,0.010841131210327148,-0.012051643803715706 +1769682160,911083520,0.0,0.0,0.0,1.0,-0.0002904128050431609,-0.0004292679950594902,-0.005520960781723261,-0.9513469338417053,0.16147743165493011,-0.013703093864023685 +1769682160,960300032,0.0,0.0,0.0,1.0,-0.00031451639370061457,-0.0005990051431581378,-0.005546960514038801,-0.9397904872894287,0.08600743114948273,-0.005103202536702156 +1769682160,975266048,0.0,0.0,0.0,1.0,-0.0002999677381012589,-0.0005696850130334496,-0.005564387887716293,-0.9280904531478882,0.01042984426021576,-0.0060444725677371025 +1769682161,9311744,0.0,0.0,0.0,1.0,-0.0003312797052785754,-0.0003541542973835021,-0.005582755897194147,-0.94231778383255,-0.14644044637680054,-0.009474582970142365 +1769682161,55845888,0.0,0.0,0.0,1.0,-0.0003807934990618378,-0.00025754369562491775,-0.005621010437607765,-0.965786337852478,0.00425536185503006,-0.006355732679367065 +1769682161,77206016,0.0,0.0,0.0,1.0,-0.0003059371665585786,0.0018681911751627922,-0.0056495023891329765,-0.9654993414878845,0.00361010804772377,-0.0314294807612896 +1769682161,109273600,0.0,0.0,0.0,1.0,-0.0003604880184866488,0.0026762604247778654,-0.00570963928475976,-0.8030785322189331,-0.04829157516360283,-0.021583804860711098 +1769682161,146438912,0.0,0.0,0.0,1.0,-0.0003324845456518233,0.0032571619376540184,-0.005796147510409355,-0.8148938417434692,0.02699406072497368,-0.017144951969385147 +1769682161,175675648,0.0,0.0,0.0,1.0,-0.0003171993885189295,0.003034199820831418,-0.005857481621205807,-0.8410789966583252,-0.05402256175875664,0.006499013863503933 +1769682161,212539904,0.0,0.0,0.0,1.0,-0.0003937202855013311,0.0018947395728901029,-0.005931990221142769,-0.7161967754364014,-0.11187700182199478,0.006521248258650303 +1769682161,248733440,0.0,0.0,0.0,1.0,-0.0003455672413110733,0.000564818037673831,-0.005997642409056425,-0.8763828873634338,0.1715913712978363,-0.005012867972254753 +1769682161,275248896,0.0,0.0,0.0,1.0,-0.00034998165210708976,9.750631761562545e-06,-0.0060057612136006355,-0.902351438999176,0.09025920182466507,0.0020165052264928818 +1769682161,309103360,0.0,0.0,0.0,1.0,-0.00032779871253296733,-0.00021435762755572796,-0.00599388312548399,-0.8151143789291382,0.026503238826990128,-0.0006271004676818848 +1769682161,346891520,0.0,0.0,0.0,1.0,-0.00028681993717327714,-0.00041577289812266827,-0.005963329691439867,-0.7892314195632935,0.1075139045715332,-0.006454490590840578 +1769682161,377223424,0.0,0.0,0.0,1.0,-0.00026798242470249534,-0.0003836614778265357,-0.005933774635195732,-0.9517917633056641,0.15891218185424805,-0.012829971499741077 +1769682161,408680448,0.0,0.0,0.0,1.0,-0.00030097702983766794,-0.00038020862848497927,-0.005898165516555309,-0.8645290732383728,0.0952019914984703,-0.01547195389866829 +1769682161,456050944,0.0,0.0,0.0,1.0,-0.00031599338399246335,-0.00032255484256893396,-0.0058740428648889065,-0.8645884990692139,0.09511010348796844,-0.011886310763657093 +1769682161,477255424,0.0,0.0,0.0,1.0,-0.00034491639235056937,8.178906864486635e-05,-0.0058460598811507225,-0.8784179091453552,-0.06182508170604706,-0.014162839390337467 +1769682161,510514944,0.0,0.0,0.0,1.0,-0.0003992893034592271,0.0004047140828333795,-0.005836125463247299,-0.8407168388366699,-0.056031860411167145,-0.015015758574008942 +1769682161,543161088,0.0,0.0,0.0,1.0,-0.0005362048977985978,0.0007204705034382641,-0.005828275810927153,-0.9162268042564392,-0.06788437068462372,-0.0014261547476053238 +1769682161,575909888,0.0,0.0,0.0,1.0,-0.0006801960407756269,0.0011622527381405234,-0.005816520657390356,-0.864665150642395,0.09440436214208603,-0.011935198679566383 +1769682161,610450944,0.0,0.0,0.0,1.0,-0.0007092872983776033,0.0013082369696348906,-0.00581495463848114,-0.8646812438964844,0.09425371140241623,-0.01196637749671936 +1769682161,644038400,0.0,0.0,0.0,1.0,-0.0007472365978173912,0.0014062839327380061,-0.005806546658277512,-0.9143307209014893,0.1634226143360138,-0.014955669641494751 +1769682161,675553024,0.0,0.0,0.0,1.0,-0.0007580025121569633,0.001593131455592811,-0.005785898305475712,-0.8783257007598877,-0.06288418918848038,-0.016737796366214752 +1769682161,714278912,0.0,0.0,0.0,1.0,-0.0008157361298799515,0.0015534632839262486,-0.005776061210781336,-0.777389407157898,0.030445082113146782,-0.009965423494577408 +1769682161,747735808,0.0,0.0,0.0,1.0,-0.0014215308474376798,0.0015171511331573129,-0.006100723519921303,-0.8528034687042236,0.01832101121544838,-0.004772055894136429 +1769682161,775954432,0.0,0.0,0.0,1.0,-0.0013527884148061275,0.0014341046335175633,-0.006528783589601517,-0.8151845335960388,0.02424418181180954,-0.0008715726435184479 +1769682161,811521536,0.0,0.0,0.0,1.0,-0.0009951035026460886,0.001255142968147993,-0.006876485422253609,-0.8016039133071899,0.18071888387203217,-0.005724164191633463 +1769682161,856526592,0.0,0.0,0.0,1.0,-0.0007609731983393431,0.0011334255104884505,-0.007232035044580698,-0.8649762868881226,0.09315858781337738,-0.0003214208409190178 +1769682161,878107136,0.0,0.0,0.0,1.0,-0.0005431421450339258,0.0010194422211498022,-0.007426234427839518,-0.9146654009819031,0.16213367879390717,-0.008070550858974457 +1769682161,909550336,0.0,0.0,0.0,1.0,-0.0003477564314380288,0.001052785199135542,-0.007572769653052092,-0.8394253849983215,0.17411039769649506,-0.0037850700318813324 +1769682161,941739776,0.0,0.0,0.0,1.0,-0.00022238900419324636,0.0009456663392484188,-0.007668609265238047,-0.7653223872184753,-0.04608273506164551,-0.007591518573462963 +1769682161,979170304,0.0,0.0,0.0,1.0,-5.9740115830209106e-05,0.0009626414394006133,-0.007713249418884516,-0.8272494673728943,0.09819440543651581,-0.011977721937000751 +1769682162,10360576,0.0,0.0,0.0,1.0,-1.2158314348198473e-05,0.0010632907506078482,-0.007709328085184097,-0.7641273736953735,0.18548962473869324,-0.012655971571803093 +1769682162,53700352,0.0,0.0,0.0,1.0,5.274525028653443e-05,0.001285294070839882,-0.007666194811463356,-0.7896474599838257,0.1038513034582138,-0.011668921448290348 +1769682162,75665152,0.0,0.0,0.0,1.0,1.4435267075896263e-05,0.0014280390460044146,-0.0076310099102556705,-0.8771829009056091,0.1667458415031433,-0.013851266354322433 +1769682162,112307968,0.0,0.0,0.0,1.0,2.4833469069562852e-05,0.0014835592592135072,-0.0075952280312776566,-0.8781828880310059,-0.06547968089580536,-0.01126093603670597 +1769682162,149822464,0.0,0.0,0.0,1.0,-1.45820522448048e-05,0.0015119879972189665,-0.0075546507723629475,-0.9149191379547119,0.16014885902404785,-0.014322157017886639 +1769682162,176649216,0.0,0.0,0.0,1.0,-9.031332592712715e-05,0.0014589494094252586,-0.007545784115791321,-0.8659285306930542,-0.1411740481853485,-0.00637722946703434 +1769682162,209404160,0.0,0.0,0.0,1.0,-0.0001551439636386931,0.0014341569039970636,-0.007557877339422703,-0.8404697179794312,-0.060014642775058746,-0.012200389988720417 +1769682162,258108672,0.0,0.0,0.0,1.0,-0.00029339350294321775,0.0015238530468195677,-0.0076224119402468204,-0.8028526306152344,-0.05405121296644211,-0.008289564400911331 +1769682162,275353600,0.0,0.0,0.0,1.0,-0.00035086809657514095,0.001616929192095995,-0.007705167401582003,-0.8028861284255981,-0.05417707562446594,-0.004752928391098976 +1769682162,309299456,0.0,0.0,0.0,1.0,-0.00039430143078789115,0.0017577775288373232,-0.007792241405695677,-0.80274897813797,-0.05452105402946472,-0.014329960569739342 +1769682162,342826496,0.0,0.0,0.0,1.0,-0.00036362773971632123,0.001724769244901836,-0.007875461131334305,-0.7523083090782166,0.10838595032691956,-0.005664650350809097 +1769682162,377436672,0.0,0.0,0.0,1.0,-0.00031517507159151137,0.0017578614642843604,-0.007937795482575893,-0.7522956132888794,0.10809188336133957,-0.009291717782616615 +1769682162,409417984,0.0,0.0,0.0,1.0,-0.00025477143935859203,0.0016930015990510583,-0.007962573319673538,-0.7523361444473267,0.10792902857065201,-0.00813792273402214 +1769682162,442238208,0.0,0.0,0.0,1.0,2.2480337065644562e-05,0.0016685024602338672,-0.007904610596597195,-0.827726423740387,0.09543579816818237,-0.001818726770579815 +1769682162,476042496,0.0,0.0,0.0,1.0,0.0002709499094635248,0.0019085892708972096,-0.007764854468405247,-0.7148409485816956,0.11384013295173645,-0.001872178167104721 +1769682162,510500608,0.0,0.0,0.0,1.0,0.00035226071486249566,0.0020392832811921835,-0.007655438967049122,-0.7651533484458923,-0.04938994720578194,-0.004680939018726349 +1769682162,546671104,0.0,0.0,0.0,1.0,0.0004134011687710881,0.002235610270872712,-0.00750765623524785,-0.7272517085075378,0.1885554939508438,-0.012919225730001926 +1769682162,576454912,0.0,0.0,0.0,1.0,0.00048166769556701183,0.0023645395413041115,-0.007398384157568216,-0.7274496555328369,-0.043595027178525925,-0.00796589907258749 +1769682162,612176896,0.0,0.0,0.0,1.0,0.0003928050573449582,0.0024480235297232866,-0.007149655371904373,-0.7399678826332092,0.03151603788137436,-0.00823622290045023 +1769682162,655802112,0.0,0.0,0.0,1.0,-0.0004866388626396656,0.0023225615732371807,-0.00647300248965621,-0.7274962663650513,0.1881789267063141,-0.004750002175569534 +1769682162,675998976,0.0,0.0,0.0,1.0,-0.0002787906851153821,0.002238721353933215,-0.006118927616626024,-0.6271088123321533,0.050023287534713745,-0.007104816380888224 +1769682162,710652672,0.0,0.0,0.0,1.0,-4.4826309022028e-05,0.0022230870090425014,-0.005847890395671129,-0.6397000551223755,0.125147745013237,-0.0085563063621521 +1769682162,755264512,0.0,0.0,0.0,1.0,0.0001614447101019323,0.0021198911126703024,-0.005643147975206375,-0.7399905920028687,0.030921142548322678,-0.00845289509743452 +1769682162,776619520,0.0,0.0,0.0,1.0,9.434394451091066e-05,0.0018605772638693452,-0.00551575468853116,-0.6147647500038147,-0.02531563490629196,0.009667462669312954 +1769682162,811321856,0.0,0.0,0.0,1.0,6.975882570259273e-05,0.0016216833610087633,-0.0054674306884408,-0.6145930886268616,-0.025612428784370422,-0.0022816569544374943 +1769682162,844782080,0.0,0.0,0.0,1.0,-1.991372846532613e-05,0.0015228504780679941,-0.005426166113466024,-0.6146717071533203,-0.02564837411046028,0.0036398638039827347 +1769682162,875442176,0.0,0.0,0.0,1.0,-6.298333028098568e-05,0.0014407006092369556,-0.005418868735432625,-0.5771355032920837,-0.019327275454998016,0.010002480819821358 +1769682162,911482112,0.0,0.0,0.0,1.0,-0.00016587512800469995,0.0013589411973953247,-0.005422886461019516,-0.576928973197937,-0.019655855372548103,-0.004323073662817478 +1769682162,946858240,0.0,0.0,0.0,1.0,-0.0002794662432279438,0.0013837686274200678,-0.005450139287859201,-0.5894799828529358,0.055324748158454895,-0.01291903667151928 +1769682162,975545344,0.0,0.0,0.0,1.0,-0.00037178999627940357,0.0014667947543784976,-0.005494044162333012,-0.6271873712539673,0.048981837928295135,-0.007421172223985195 +1769682163,8795136,0.0,0.0,0.0,1.0,-0.0004008224350400269,0.001515862881205976,-0.005562473088502884,-0.6144611239433289,-0.026399999856948853,-0.009610050357878208 +1769682163,43649280,0.0,0.0,0.0,1.0,-0.0005311195272952318,0.0015186475357040763,-0.00564215611666441,-0.5393372178077698,-0.013673773035407066,-0.0016083726659417152 +1769682163,77342208,0.0,0.0,0.0,1.0,-0.00057290616678074,0.0017152511281892657,-0.005761381238698959,-0.6022471189498901,0.13013030588626862,-0.013255033642053604 +1769682163,110965760,0.0,0.0,0.0,1.0,-0.0005599395371973515,0.0016744142631068826,-0.005857476033270359,-0.6398429870605469,0.12361494451761246,-0.016111299395561218 +1769682163,153979136,0.0,0.0,0.0,1.0,-0.0005877145449630916,0.0016832815017551184,-0.005947848781943321,-0.57667475938797,-0.020656203851103783,-0.020023465156555176 +1769682163,176257280,0.0,0.0,0.0,1.0,-0.0005633727414533496,0.0016348038334399462,-0.006054189056158066,-0.5392378568649292,-0.014213517308235168,-0.007695662789046764 +1769682163,209610496,0.0,0.0,0.0,1.0,-0.0002546348259784281,0.0014571479987353086,-0.0060841417871415615,-0.614303469657898,-0.027254652231931686,-0.01815684512257576 +1769682163,243628032,0.0,0.0,0.0,1.0,-0.000410643988288939,0.0008375300676561892,-0.006130750756710768,-0.5390558242797852,-0.014604141935706139,-0.019656043499708176 +1769682163,276455936,0.0,0.0,0.0,1.0,-0.001062421128153801,0.0004695880925282836,-0.006171675864607096,-0.5015558004379272,-0.008210280910134315,-0.012065542861819267 +1769682163,309186560,0.0,0.0,0.0,1.0,-0.0012944991467520595,0.00024128436052706093,-0.006187403108924627,-0.5648760795593262,0.13576962053775787,-0.009374682791531086 +1769682163,342603264,0.0,0.0,0.0,1.0,-0.0014447165885940194,0.0003444249741733074,-0.0061923181638121605,-0.5393111109733582,-0.014646753668785095,-0.0018036412075161934 +1769682163,375701504,0.0,0.0,0.0,1.0,-0.0016138864448294044,0.0005243952036835253,-0.006214323453605175,-0.6143968105316162,-0.027761992067098618,-0.009876308962702751 +1769682163,411350528,0.0,0.0,0.0,1.0,-0.001778070698492229,0.0005738787003792822,-0.006247655022889376,-0.526405930519104,-0.09010837227106094,-0.00281454436480999 +1769682163,447958272,0.0,0.0,0.0,1.0,-0.0015569370007142425,0.00044903988600708544,-0.006317235995084047,-0.46414628624916077,-0.002079365774989128,0.001462956890463829 +1769682163,476761600,0.0,0.0,0.0,1.0,-0.0015040229773148894,0.0002865884162019938,-0.006376965902745724,-0.5275856852531433,0.14179861545562744,0.0018040603026747704 +1769682163,510808320,0.0,0.0,0.0,1.0,-0.0014359810156747699,9.482588211540133e-05,-0.0064263660460710526,-0.5768340826034546,-0.02174408733844757,-0.005879205651581287 +1769682163,555416832,0.0,0.0,0.0,1.0,-0.0014061152469366789,-7.715322863077745e-05,-0.0064777652733027935,-0.5392208695411682,-0.01540299691259861,-0.006612725555896759 +1769682163,577616384,0.0,0.0,0.0,1.0,-0.0013068746775388718,-0.00012892359518446028,-0.0065137348137795925,-0.5781227946281433,0.21005764603614807,-0.005969801917672157 +1769682163,610949632,0.0,0.0,0.0,1.0,-0.0012544175842776895,-3.911772000719793e-05,-0.006533897016197443,-0.5145851373672485,0.06601300835609436,-0.0075238426215946674 +1769682163,643593472,0.0,0.0,0.0,1.0,-0.0012070519151166081,2.8242509870324284e-05,-0.006541495211422443,-0.5391751527786255,-0.01579107530415058,-0.008995387703180313 +1769682163,675608064,0.0,0.0,0.0,1.0,-0.0011706540826708078,0.0001243729202542454,-0.006552832201123238,-0.42655736207962036,0.003733946941792965,0.001916572917252779 +1769682163,712371200,0.0,0.0,0.0,1.0,-0.0011724622454494238,8.118122059386224e-05,-0.006567355245351791,-0.5015836954116821,-0.009524606168270111,-0.008539799600839615 +1769682163,753704192,0.0,0.0,0.0,1.0,-0.0011585257016122341,0.00010276269313180819,-0.006596648134291172,-0.45250949263572693,0.15374861657619476,-0.00795633252710104 +1769682163,775596544,0.0,0.0,0.0,1.0,-0.0011852442985400558,8.485859871143475e-05,-0.006636333651840687,-0.6028107404708862,0.12748195230960846,-0.013372072950005531 +1769682163,809041664,0.0,0.0,0.0,1.0,-0.0011892432812601328,2.4242148356279358e-05,-0.006688780151307583,-0.49018609523773193,0.14706751704216003,-0.006025045644491911 +1769682163,856577024,0.0,0.0,0.0,1.0,-0.0010771648958325386,-4.278882988728583e-05,-0.006731611676514149,-0.47709333896636963,0.07172849029302597,-0.00824166089296341 +1769682163,876927488,0.0,0.0,0.0,1.0,-0.00044805766083300114,0.00024283073435071856,-0.006690955255180597,-0.46413862705230713,-0.0033890996128320694,0.0014500156976282597 +1769682163,911387392,0.0,0.0,0.0,1.0,-0.0002528082113713026,0.0005290094413794577,-0.006671932991594076,-0.53923499584198,-0.0166630856692791,-0.0030565056949853897 +1769682163,942848768,0.0,0.0,0.0,1.0,-8.267927478300408e-05,0.0007808717782609165,-0.006665165536105633,-0.3890250623226166,0.009602900594472885,0.004744383972138166 +1769682163,979561984,0.0,0.0,0.0,1.0,8.298175816889852e-05,0.0008768460829742253,-0.006654265336692333,-0.3889201879501343,0.009389678947627544,-0.002419534604996443 +1769682164,9308928,0.0,0.0,0.0,1.0,0.00024962436873465776,0.000925998785533011,-0.006644933018833399,-0.4773305058479309,0.0713840052485466,0.00243908679112792 +1769682164,43095296,0.0,0.0,0.0,1.0,0.00031285645673051476,0.0009045096230693161,-0.0066205356270074844,-0.47723671793937683,0.07117940485477448,-0.004725465551018715 +1769682164,76694016,0.0,0.0,0.0,1.0,0.0007686585304327309,0.001256820047274232,-0.006532786879688501,-0.4767133891582489,0.07050482928752899,-0.04050110653042793 +1769682164,110758400,0.0,0.0,0.0,1.0,0.0003036504494957626,0.0017704092897474766,-0.006584209389984608,-0.46369823813438416,-0.004536069929599762,-0.027251994237303734 +1769682164,155156736,0.0,0.0,0.0,1.0,-0.00028644141275435686,0.0019730564672499895,-0.006694176234304905,-0.4637860655784607,-0.004567814990878105,-0.02132834494113922 +1769682164,175862528,0.0,0.0,0.0,1.0,-0.0005907425074838102,0.0020025111734867096,-0.00676204776391387,-0.36448338627815247,0.09049998223781586,-0.011753003112971783 +1769682164,212357632,0.0,0.0,0.0,1.0,-0.0008494466310366988,0.0019784746691584587,-0.0068247136659920216,-0.3512977957725525,0.015359691344201565,-0.006842303555458784 +1769682164,262918400,0.0,0.0,0.0,1.0,-0.0011364953825250268,0.0019819794688373804,-0.006879067048430443,-0.375619500875473,-0.06646578758955002,-0.003613571636378765 +1769682164,270338048,0.0,0.0,0.0,1.0,-0.0011924866121262312,0.0019523182418197393,-0.006897089537233114,-0.38888099789619446,0.008579862304031849,-0.006173359230160713 +1769682164,309353472,0.0,0.0,0.0,1.0,-0.0013084992533549666,0.0018643002258613706,-0.006901775952428579,-0.4023975133895874,0.08378387987613678,0.005558814853429794 +1769682164,356066048,0.0,0.0,0.0,1.0,-0.001389218377880752,0.0017273545963689685,-0.006909836083650589,-0.38894030451774597,0.00844663381576538,-0.0026473423931747675 +1769682164,377538816,0.0,0.0,0.0,1.0,-0.001468057045713067,0.001614249194972217,-0.006926367059350014,-0.40232613682746887,0.08348070830106735,-0.0016318331472575665 +1769682164,409995008,0.0,0.0,0.0,1.0,-0.0008569895289838314,0.0013077298644930124,-0.006915834732353687,-0.30267083644866943,0.17821089923381805,-0.025346368551254272 +1769682164,442960640,0.0,0.0,0.0,1.0,-0.0007792902179062366,-0.000654428091365844,-0.006951992865651846,-0.27510592341423035,0.027142208069562912,-0.07629681378602982 +1769682164,476155648,0.0,0.0,0.0,1.0,-0.0013823258923366666,-0.003137111198157072,-0.00716059748083353,-0.2888374924659729,0.10246778279542923,-0.05734481289982796 +1769682164,511838464,0.0,0.0,0.0,1.0,-0.0029238914139568806,-0.003524068044498563,-0.007307406049221754,-0.38874563574790955,0.007787960581481457,-0.015723956748843193 +1769682164,544265472,0.0,0.0,0.0,1.0,-0.003681435016915202,-0.0035554049536585808,-0.007467878982424736,-0.4023658037185669,0.08297013491392136,-0.00508234603330493 +1769682164,575891968,0.0,0.0,0.0,1.0,-0.004358806647360325,-0.003193847369402647,-0.007658978458493948,-0.35146552324295044,0.014567623846232891,0.0015363171696662903 +1769682164,610269440,0.0,0.0,0.0,1.0,-0.0046604895032942295,-0.0029052793979644775,-0.007765389047563076,-0.41311874985694885,-0.07405272126197815,0.004293815698474646 +1769682164,654122240,0.0,0.0,0.0,1.0,-0.004618215840309858,-0.0026362547650933266,-0.007833384908735752,-0.3412863314151764,0.17163236439228058,0.023366328328847885 +1769682164,676713472,0.0,0.0,0.0,1.0,-0.0041054654866456985,-0.0027484025340527296,-0.007814913056790829,-0.38930389285087585,0.007797899655997753,0.020238976925611496 +1769682164,709171968,0.0,0.0,0.0,1.0,-0.003935021813958883,-0.0028243325650691986,-0.007758596912026405,-0.300625205039978,-0.053888797760009766,0.01770024374127388 +1769682164,759457280,0.0,0.0,0.0,1.0,-0.003780794097110629,-0.0029389928095042706,-0.007646163925528526,-0.32748478651046753,0.09594101458787918,-0.0002540759742259979 +1769682164,775676928,0.0,0.0,0.0,1.0,-0.003749309340491891,-0.002993649570271373,-0.0075743068009614944,-0.37873655557632446,0.16425441205501556,0.006431973539292812 +1769682164,809622272,0.0,0.0,0.0,1.0,-0.0037293084897100925,-0.003040374955162406,-0.007560060825198889,-0.2763890326023102,0.0275138970464468,0.0003193402662873268 +1769682164,842489600,0.0,0.0,0.0,1.0,-0.003826239611953497,-0.0030810039024800062,-0.007610963191837072,-0.28998398780822754,0.10249593108892441,-0.0020582969300448895 +1769682164,878385152,0.0,0.0,0.0,1.0,-0.003925622440874577,-0.0030616282019764185,-0.007810284849256277,-0.3376592993736267,-0.06149525195360184,-0.011240663938224316 +1769682164,911522560,0.0,0.0,0.0,1.0,-0.003888135775923729,-0.0030795475468039513,-0.007993103004992008,-0.3649752736091614,0.08856519311666489,-0.01121489517390728 +1769682164,943884800,0.0,0.0,0.0,1.0,-0.0037148213014006615,-0.0030872044153511524,-0.008121584542095661,-0.37522628903388977,-0.06843255460262299,-0.00687397550791502 +1769682164,976642816,0.0,0.0,0.0,1.0,-0.0032626113388687372,-0.0030444436706602573,-0.008059676736593246,-0.3411942720413208,0.17025983333587646,-0.011838099919259548 +1769682165,9591808,0.0,0.0,0.0,1.0,-0.0030958240386098623,-0.0030356207862496376,-0.007902717217803001,-0.3378252685070038,-0.061662521213293076,0.003167350310832262 +1769682165,44208640,0.0,0.0,0.0,1.0,-0.0013792896643280983,-0.0024085708428174257,-0.007469911593943834,-0.2667207419872284,0.1842847764492035,0.023691197857260704 +1769682165,76607488,0.0,0.0,0.0,1.0,-0.0007443787762895226,-0.001531506422907114,-0.007202445063740015,-0.2905104458332062,0.10225902497768402,0.022047685459256172 +1769682165,110890752,0.0,0.0,0.0,1.0,-0.0005486602894961834,-0.0010360132437199354,-0.007268731482326984,-0.3654998540878296,0.0883573591709137,0.01641997881233692 +1769682165,162347264,0.0,0.0,0.0,1.0,-0.0005063547869212925,-0.0004940153448842466,-0.007583539932966232,-0.3040321469306946,0.17684930562973022,-0.0017229632940143347 +1769682165,170248960,0.0,0.0,0.0,1.0,0.0013234992511570454,0.000570921169128269,-0.007777785882353783,-0.27916219830513,0.2576560080051422,-0.08706586807966232 +1769682165,210109696,0.0,0.0,0.0,1.0,0.0005543706938624382,0.003769758390262723,-0.008350932970643044,-0.3635079860687256,0.08620043098926544,-0.13021396100521088 +1769682165,255856128,0.0,0.0,0.0,1.0,-7.254682714119554e-05,0.004924653563648462,-0.008899158798158169,-0.31327831745147705,0.01901843398809433,-0.05000215396285057 +1769682165,276459008,0.0,0.0,0.0,1.0,-0.0010055641178041697,0.005107959732413292,-0.009414002299308777,-0.31351566314697266,0.0191165953874588,-0.03337925300002098 +1769682165,309561600,0.0,0.0,0.0,1.0,-0.001405032817274332,0.004867939744144678,-0.009522601962089539,-0.24854280054569244,-0.12376667559146881,-0.009202747605741024 +1769682165,342290688,0.0,0.0,0.0,1.0,-0.0016991740558296442,0.004426772706210613,-0.009450332261621952,-0.27669745683670044,0.026491854339838028,0.0134792011231184 +1769682165,378989568,0.0,0.0,0.0,1.0,-0.002193617634475231,0.0038745494093745947,-0.00918230414390564,-0.2905600070953369,0.10131402313709259,0.006327054928988218 +1769682165,410054400,0.0,0.0,0.0,1.0,-0.002548744436353445,0.003555646166205406,-0.008926316164433956,-0.23921941220760345,0.0332990437746048,0.013882705941796303 +1769682165,442748928,0.0,0.0,0.0,1.0,-0.002959056757390499,0.003233501221984625,-0.008690424263477325,-0.28630122542381287,-0.130716472864151,0.0175684355199337 +1769682165,475763712,0.0,0.0,0.0,1.0,-0.002227810909971595,0.00238381652161479,-0.008381756953895092,-0.1919722855091095,0.1969148814678192,-0.006531083956360817 +1769682165,509173504,0.0,0.0,0.0,1.0,-0.003078098176047206,0.0007156070787459612,-0.008303440175950527,-0.17273083329200745,-0.11064644902944565,-0.047786083072423935 +1769682165,547447552,0.0,0.0,0.0,1.0,-0.0036819877568632364,-0.001087127486243844,-0.008283407427370548,-0.2150929868221283,0.11444772034883499,-0.03446507453918457 +1769682165,577341184,0.0,0.0,0.0,1.0,-0.0038732204120606184,-0.001954005565494299,-0.00828783493489027,-0.0887901559472084,0.06069795787334442,-0.018765587359666824 +1769682165,611275008,0.0,0.0,0.0,1.0,-0.005307525862008333,-0.0016167826252058148,-0.008208706974983215,-0.187650665640831,-0.0350792296230793,0.011880803853273392 +1769682165,657730816,0.0,0.0,0.0,1.0,-0.006624779663980007,-0.0005154252285137773,-0.00810975395143032,-0.2908990979194641,0.10072866082191467,0.013521015644073486 +1769682165,676894720,0.0,0.0,0.0,1.0,-0.007117425557225943,0.00027130296803079545,-0.007987791672348976,-0.22531120479106903,-0.042113229632377625,0.024496031925082207 +1769682165,712371712,0.0,0.0,0.0,1.0,-0.007464882917702198,0.0008990527130663395,-0.007811825256794691,-0.2717929780483246,-0.20639070868492126,0.013678174465894699 +1769682165,742850560,0.0,0.0,0.0,1.0,-0.007125025615096092,0.0011411166051402688,-0.007613632827997208,-0.17882178723812103,0.12198491394519806,0.0341150127351284 +1769682165,777608192,0.0,0.0,0.0,1.0,-0.005509723909199238,0.0001716955448500812,-0.007273080758750439,-0.2307562530040741,0.18994663655757904,0.048128388822078705 +1769682165,809892352,0.0,0.0,0.0,1.0,-0.00513392174616456,-0.0004177790542598814,-0.006990405265241861,-0.1788662075996399,0.12186800688505173,0.032968536019325256 +1769682165,843491072,0.0,0.0,0.0,1.0,-0.004866827744990587,-0.0009310319437645376,-0.006697865668684244,-0.2769891619682312,0.02545858733355999,0.02534361556172371 +1769682165,876230144,0.0,0.0,0.0,1.0,-0.004605609457939863,-0.0013499900233000517,-0.006360653322190046,-0.173307865858078,-0.11044681072235107,0.010421141982078552 +1769682165,911861248,0.0,0.0,0.0,1.0,-0.004468039143830538,-0.0014903368428349495,-0.006156382616609335,-0.3050479292869568,0.1749197244644165,-0.006347373127937317 +1769682165,951873024,0.0,0.0,0.0,1.0,-0.004340853542089462,-0.001521546975709498,-0.005949776154011488,-0.18711544573307037,-0.03585111349821091,-0.01795838586986065 +1769682165,976180224,0.0,0.0,0.0,1.0,-0.004276338964700699,-0.0014232967514544725,-0.005828479304909706,-0.1640295386314392,0.046273473650217056,-0.011250724084675312 +1769682166,12111104,0.0,0.0,0.0,1.0,-0.004190846346318722,-0.0013185404241085052,-0.005728582385927439,-0.11231253296136856,-0.021515201777219772,-0.00743375439196825 +1769682166,57573376,0.0,0.0,0.0,1.0,-0.004096346907317638,-0.0011362789664417505,-0.005612263455986977,-0.17839539051055908,0.12116783857345581,-0.009755030274391174 +1769682166,76644608,0.0,0.0,0.0,1.0,-0.004088306799530983,-0.0010495830792933702,-0.005535869859158993,-0.20153918862342834,0.03902895748615265,-0.010510105639696121 +1769682166,109432576,0.0,0.0,0.0,1.0,-0.0024330243468284607,-0.00044371423427946866,-0.0052162641659379005,-0.28256380558013916,0.2569516599178314,0.023260965943336487 +1769682166,142842880,0.0,0.0,0.0,1.0,-0.0010167966829612851,0.0005980697460472584,-0.0048118093982338905,-0.2395268827676773,0.032104238867759705,0.023573026061058044 +1769682166,178259968,0.0,0.0,0.0,1.0,0.0013470925623551011,0.002351425588130951,-0.004246612545102835,-0.20111329853534698,0.038660384714603424,-0.040312476456165314 +1769682166,210165504,0.0,0.0,0.0,1.0,0.0010513520101085305,0.004655926022678614,-0.003998953849077225,-0.20046821236610413,0.0382419191300869,-0.08324620127677917 +1769682166,244194560,0.0,0.0,0.0,1.0,0.0011722285998985171,0.006278160959482193,-0.0038159366231411695,-0.14883914589881897,-0.02937990427017212,-0.06756936758756638 +1769682166,275887360,0.0,0.0,0.0,1.0,0.0013528093695640564,0.0075757806189358234,-0.0036128368228673935,-0.09722784161567688,-0.09697066992521286,-0.049495477229356766 +1769682166,315855872,0.0,0.0,0.0,1.0,-0.00038147770101204515,0.006909905467182398,-0.003850232344120741,-0.11291845887899399,-0.02130931243300438,0.03180672600865364 +1769682166,351070976,0.0,0.0,0.0,1.0,-0.0017984252190217376,0.005736333318054676,-0.0040663150139153,-0.14164011180400848,0.12846270203590393,0.02517530880868435 +1769682166,376494080,0.0,0.0,0.0,1.0,-0.0025888823438435793,0.00483636325225234,-0.004168617073446512,-0.029392065480351448,0.15014231204986572,0.03273569419980049 +1769682166,410078464,0.0,0.0,0.0,1.0,-0.0032611428759992123,0.004046821966767311,-0.004231714177876711,-0.03801518306136131,-0.006908045150339603,0.03402135521173477 +1769682166,464984064,0.0,0.0,0.0,1.0,-0.003981377929449081,0.003409869270399213,-0.004288132302463055,-0.08965679258108139,0.060626909136772156,0.017070021480321884 +1769682166,474541312,0.0,0.0,0.0,1.0,-0.004130843561142683,0.0031549890991300344,-0.004301147535443306,-0.023182310163974762,-0.08204344660043716,0.011069314554333687 +1769682166,512136960,0.0,0.0,0.0,1.0,-0.004518859554082155,0.0027528521604835987,-0.004316735081374645,-0.12680983543395996,0.05319993197917938,-0.0025593785103410482 +1769682166,542514688,0.0,0.0,0.0,1.0,-0.0047194622457027435,0.002517831977456808,-0.004300288390368223,-0.11232831329107285,-0.021730640903115273,-0.0028791804797947407 +1769682166,576350464,0.0,0.0,0.0,1.0,-0.004787826910614967,0.00245875446125865,-0.004243103321641684,-0.023046931251883507,-0.08210922032594681,0.0050616804510355 +1769682166,609650176,0.0,0.0,0.0,1.0,-0.004805244039744139,0.0024744272232055664,-0.004171764478087425,-0.13509760797023773,-0.10400162637233734,-0.013352228328585625 +1769682166,656708352,0.0,0.0,0.0,1.0,-0.005526945926249027,0.0030300936195999384,-0.004019086714833975,-0.20223671197891235,0.03884858638048172,0.026074806228280067 +1769682166,676175872,0.0,0.0,0.0,1.0,-0.006664360407739878,0.004076065495610237,-0.00391496904194355,-0.18750937283039093,-0.036178283393383026,0.013774657621979713 +1769682166,709392128,0.0,0.0,0.0,1.0,-0.007220033556222916,0.004855610430240631,-0.003821380203589797,-0.07509297877550125,-0.01444176584482193,0.010740713216364384 +1769682166,758537216,0.0,0.0,0.0,1.0,-0.007726337295025587,0.0055871400982141495,-0.003704652888700366,-0.09790127724409103,-0.09666352719068527,0.004954133648425341 +1769682166,779422976,0.0,0.0,0.0,1.0,-0.007340569980442524,0.0056134182959795,-0.0036234380677342415,-0.052504636347293854,0.06782454252243042,0.028411991894245148 +1769682166,809553920,0.0,0.0,0.0,1.0,-0.0055124182254076,0.004496837500482798,-0.003508550813421607,-0.015666360035538673,0.07531949132680893,0.0624031126499176 +1769682166,854607616,0.0,0.0,0.0,1.0,-0.00486297532916069,0.0034973390866070986,-0.00337401544675231,-0.0008716502343304455,0.0003244361432734877,0.04886699095368385 +1769682166,877079040,0.0,0.0,0.0,1.0,-0.004349110182374716,0.0025321238208562136,-0.0032029615249484777,-0.06708110123872757,0.14267177879810333,0.0264902226626873 +1769682166,911685120,0.0,0.0,0.0,1.0,-0.004067393019795418,0.0020273143891245127,-0.0030853995122015476,-0.0003221451479475945,0.00011315470328554511,0.01787814311683178 +1769682166,943845632,0.0,0.0,0.0,1.0,-0.003793917130678892,0.0017660618759691715,-0.002983746351674199,-0.20181001722812653,0.0384286604821682,-0.001501716673374176 +1769682166,975826688,0.0,0.0,0.0,1.0,-0.00357620557770133,0.001689854427240789,-0.0028851255774497986,-0.07463596761226654,-0.01467641070485115,-0.014380590058863163 +1769682167,11520256,0.0,0.0,0.0,1.0,-0.0034340268466621637,0.0017342400969937444,-0.0028331985231488943,-0.0746990293264389,-0.014659985899925232,-0.010810328647494316 +1769682167,46946816,0.0,0.0,0.0,1.0,-0.0032944672275334597,0.001914431806653738,-0.0027734648901969194,-0.014383482746779919,0.07481108605861664,-0.012621347792446613 +1769682167,77246976,0.0,0.0,0.0,1.0,-0.0032126714941114187,0.0020486919675022364,-0.002722674049437046,-0.0893457755446434,0.060221005231142044,-0.009136153385043144 +1769682167,109429248,0.0,0.0,0.0,1.0,-0.0031827047932893038,0.00217655161395669,-0.0026667332276701927,-0.07464902102947235,-0.014690348878502846,-0.013213624246418476 +1769682167,217231872,0.0,0.0,0.0,1.0,-0.0013654838548973203,0.0028792640659958124,-0.0023633583914488554,-0.19377215206623077,0.19542157649993896,0.00487535772845149 +1769682167,220579840,0.0,0.0,0.0,1.0,-0.00045204622438177466,0.0038915425539016724,-0.002051328308880329,-0.25402525067329407,0.10589753091335297,0.0042307013645768166 +1769682167,226676992,0.0,0.0,0.0,1.0,7.517868652939796e-05,0.004739917349070311,-0.0018191785784438252,0.04556039720773697,0.1644030213356018,0.0023340131156146526 +1769682167,254429184,0.0,0.0,0.0,1.0,0.0005333846202120185,0.005614612251520157,-0.0015773222548887134,-0.014612008817493916,0.07486749440431595,-0.0018819349352270365 +1769682167,273146624,0.0,0.0,0.0,1.0,0.0006889168871566653,0.005839545279741287,-0.0014726393856108189,-0.10415894538164139,0.13510675728321075,-0.0015398970572277904 +1769682167,310509312,0.0,0.0,0.0,1.0,0.0008799507631920278,0.005803621374070644,-0.0014080816181376576,0.014295713976025581,-0.07477343082427979,0.018576467409729958 +1769682167,359696128,0.0,0.0,0.0,1.0,-0.0010711848735809326,0.004473377019166946,-0.0016315956600010395,-0.015458681620657444,0.07510283589363098,0.04101461544632912 +1769682167,377048320,0.0,0.0,0.0,1.0,-0.001855578157119453,0.0036442074924707413,-0.0017549627227708697,0.01390089001506567,-0.07466187328100204,0.03883732482790947 +1769682167,410203648,0.0,0.0,0.0,1.0,-0.0024382115807384253,0.003000362543389201,-0.0018619340844452381,-0.06079280748963356,-0.0893726721405983,0.029094483703374863 +1769682167,467393792,0.0,0.0,0.0,1.0,-0.003583241254091263,0.0027587024960666895,-0.002000966342166066,-0.1354336440563202,-0.10410720854997635,0.016943534836173058 +1769682167,477257472,0.0,0.0,0.0,1.0,-0.0036876623053103685,0.0030664587393403053,-0.0020796076860278845,-0.0605488158762455,-0.08944973349571228,0.017142916098237038 +1769682167,509556480,0.0,0.0,0.0,1.0,-0.0038713624235242605,0.0034191987942904234,-0.0021383774001151323,-0.08961862325668335,0.060213398188352585,0.002670829650014639 +1769682167,547389696,0.0,0.0,0.0,1.0,-0.00404520146548748,0.003884057281538844,-0.0021958330180495977,-0.04543253779411316,-0.1644352525472641,-0.0036866015288978815 +1769682167,576566528,0.0,0.0,0.0,1.0,-0.004064346197992563,0.004097500815987587,-0.00221582711674273,-0.134928897023201,-0.1042674109339714,-0.007007707841694355 +1769682167,610753536,0.0,0.0,0.0,1.0,-0.004068632144480944,0.00423116609454155,-0.002221789676696062,-0.08926805108785629,0.06010933965444565,-0.015217777341604233 +1769682167,648685824,0.0,0.0,0.0,1.0,-0.004053088836371899,0.004375915974378586,-0.0022026814986020327,-0.07465352863073349,-0.014743542298674583,-0.011009180918335915 +1769682167,676137216,0.0,0.0,0.0,1.0,-0.004632193129509687,0.004814072512090206,-0.0021512929815799,0.0746016576886177,0.01475737988948822,0.013405018486082554 +1769682167,710792448,0.0,0.0,0.0,1.0,-0.005033342633396387,0.005329201463609934,-0.0021128992084413767,0.0,-0.0,0.0 +1769682167,768858624,0.0,0.0,0.0,1.0,-0.005315232556313276,0.005723831243813038,-0.002052894327789545,-0.14981751143932343,-0.029407808557152748,0.0029184133745729923 +1769682167,778128128,0.0,0.0,0.0,1.0,-0.005437388084828854,0.005817799363285303,-0.002006582682952285,-0.014837566763162613,0.07488280534744263,0.005358502268791199 +1769682167,811493120,0.0,0.0,0.0,1.0,-0.004189607687294483,0.005275044124573469,-0.0019602584652602673,0.11908143013715744,0.1793694645166397,0.05673987790942192 +1769682167,856103424,0.0,0.0,0.0,1.0,-0.0031401782762259245,0.004315107595175505,-0.00189235620200634,0.08850739896297455,-0.05995434522628784,0.05101286992430687 +1769682167,877506816,0.0,0.0,0.0,1.0,-0.0025349583011120558,0.003303953679278493,-0.001806387910619378,0.0887891948223114,-0.059999044984579086,0.0379093773663044 +1769682167,910877952,0.0,0.0,0.0,1.0,-0.0022124131210148335,0.0027831990737468004,-0.001741168787702918,0.0595916211605072,0.08967553079128265,0.024842126294970512 +1769682167,943047168,0.0,0.0,0.0,1.0,-0.001955921994522214,0.0025089909322559834,-0.001684508053585887,-0.0002609193907119334,3.988791286246851e-05,0.011918014846742153 +1769682167,976777728,0.0,0.0,0.0,1.0,-0.00169181649107486,0.002392765134572983,-0.0016024847282096744,-0.16444014012813568,0.04536650329828262,-0.002572131110355258 +1769682168,11204608,0.0,0.0,0.0,1.0,-0.0015406985767185688,0.0024050301872193813,-0.001543649472296238,0.1497538983821869,0.029487665742635727,-0.00036833365447819233 +1769682168,56020736,0.0,0.0,0.0,1.0,-0.00147635443136096,0.002591513330116868,-0.0014756628079339862,0.07488928735256195,0.014746449887752533,-0.0007716465042904019 +1769682168,77156096,0.0,0.0,0.0,1.0,-0.0014240427408367395,0.0027133666444569826,-0.001437220722436905,0.15001600980758667,0.029465997591614723,-0.012256192043423653 +1769682168,109890048,0.0,0.0,0.0,1.0,-0.0018721269443631172,0.0025696614757180214,-0.0014444445259869099,-0.07496794313192368,-0.0147420484572649,0.004333753604441881 +1769682168,157134592,0.0,0.0,0.0,1.0,-0.0014699354069307446,0.002049172529950738,-0.0013608734589070082,-0.00048076806706376374,6.436922558350489e-05,0.021452205255627632 +1769682168,179077888,0.0,0.0,0.0,1.0,-0.0005064751021564007,0.002198742935433984,-0.001191921648569405,-0.0007232292555272579,9.582030907040462e-05,0.03217826038599014 +1769682168,209529344,0.0,0.0,0.0,1.0,-0.00014849923900328577,0.0023468341678380966,-0.0010620483662933111,-0.0005373714375309646,7.078428461682051e-05,0.023835713043808937 +1769682168,257170944,0.0,0.0,0.0,1.0,8.85290646692738e-05,0.002511049620807171,-0.000970628927461803,-0.08999963849782944,0.06013111025094986,0.01567184366285801 +1769682168,293576704,0.0,0.0,0.0,1.0,0.00030598966986872256,0.0026635651011019945,-0.0008741183555684984,0.014603341929614544,-0.07482810318470001,0.007709109224379063 +1769682168,303684096,0.0,0.0,0.0,1.0,0.0003563108912203461,0.002706172876060009,-0.0008391740266233683,-0.07485821843147278,-0.014772357419133186,-0.00046857341658324003 +1769682168,346374400,0.0,0.0,0.0,1.0,-0.0003694793558679521,0.002260560402646661,-0.0009354682406410575,-0.10486200451850891,0.13498196005821228,0.018658239394426346 +1769682168,376543488,0.0,0.0,0.0,1.0,-0.001314275898039341,0.002026849891990423,-0.001072343555279076,0.08889048546552658,-0.059974901378154755,0.03322191536426544 +1769682168,409907456,0.0,0.0,0.0,1.0,-0.0024143022019416094,0.0029234071262180805,-0.0012309896992519498,0.162840336561203,-0.04508000984787941,0.07304264605045319 +1769682168,443264000,0.0,0.0,0.0,1.0,-0.0019626934081315994,0.004328414332121611,-0.001264229416847229,0.013453022576868534,-0.07468539476394653,0.05775870755314827 +1769682168,477034240,0.0,0.0,0.0,1.0,-0.001946854405105114,0.00563841313123703,-0.0013008293462917209,-0.15040621161460876,-0.029492352157831192,0.028761843219399452 +1769682168,510838016,0.0,0.0,0.0,1.0,-0.0019659865647554398,0.006237643305212259,-0.0013140568044036627,-0.015205411240458488,0.07489383220672607,0.017327124252915382 +1769682168,546617088,0.0,0.0,0.0,1.0,-0.0019395059207454324,0.00667197722941637,-0.0013252191711217165,-0.1497635543346405,-0.029581625014543533,0.0012807666789740324 +1769682168,577454336,0.0,0.0,0.0,1.0,-0.0019413980189710855,0.006777158938348293,-0.0013238932006061077,-0.1643247753381729,0.045232582837343216,-0.008831118233501911 +1769682168,609519104,0.0,0.0,0.0,1.0,-0.0018993673147633672,0.006759797688573599,-0.001311499159783125,-0.10415125638246536,0.13485848903656006,-0.013589870184659958 +1769682168,655577856,0.0,0.0,0.0,1.0,-0.0018571612890809774,0.006660859100520611,-0.0012989984825253487,-0.01450574491173029,0.07481443136930466,-0.01246060710400343 +1769682168,676672000,0.0,0.0,0.0,1.0,-0.0016516975592821836,0.006414311472326517,-0.001267155515961349,-0.059549953788518906,-0.08969689160585403,-0.020337572321295738 +1769682168,710137856,0.0,0.0,0.0,1.0,-0.0012639890192076564,0.006068528164178133,-0.0012456398690119386,0.07529420405626297,0.01476784236729145,-0.017241399735212326 +1769682168,743074816,0.0,0.0,0.0,1.0,-0.0010611185571178794,0.005801459774374962,-0.0012072102399542928,0.015163909643888474,-0.07487424463033676,-0.013759144581854343 +1769682168,777195008,0.0,0.0,0.0,1.0,-0.0008288930403068662,0.005523722618818283,-0.0011479404056444764,-0.014688733965158463,0.07483026385307312,-0.005308912601321936 +1769682168,810241792,0.0,0.0,0.0,1.0,-0.0006244897958822548,0.005399668123573065,-0.001111739780753851,-0.014963138848543167,0.07485369592905045,0.005415656603872776 +1769682168,842937344,0.0,0.0,0.0,1.0,0.00043726543663069606,0.004833881743252277,-0.001066129538230598,-0.07545671612024307,-0.01476732362061739,0.023144833743572235 +1769682168,876920064,0.0,0.0,0.0,1.0,0.0009439803543500602,0.004198871087282896,-0.0010028869146481156,0.07410959154367447,0.014888008125126362,0.029302630573511124 +1769682168,910087680,0.0,0.0,0.0,1.0,0.0011678248411044478,0.003989317920058966,-0.0009615203598514199,0.13440987467765808,0.1045311763882637,0.01874164119362831 +1769682168,959227648,0.0,0.0,0.0,1.0,0.0013579399092122912,0.0038757645525038242,-0.0009307434665970504,0.01451151818037033,-0.0748104602098465,0.012477755546569824 +1769682168,976321024,0.0,0.0,0.0,1.0,0.0013903226936236024,0.003778945654630661,-0.0009295697673223913,0.08954375237226486,-0.05999589338898659,0.00606184359639883 +1769682169,10137088,0.0,0.0,0.0,1.0,0.001416108338162303,0.0038211732171475887,-0.0009403029107488692,-0.04528629779815674,-0.16449902951717377,0.0039787860587239265 +1769682169,44687104,0.0,0.0,0.0,1.0,0.0002631771203596145,0.0035226100590080023,-0.0010764304315671325,-0.061557088047266006,-0.08952893316745758,0.05821993947029114 +1769682169,76969984,0.0,0.0,0.0,1.0,0.00035305414348840714,0.002068607835099101,-0.0011689977254718542,0.05748559534549713,0.08990931510925293,0.09551061689853668 +1769682169,110578432,0.0,0.0,0.0,1.0,0.0006436845869757235,0.0005930803599767387,-0.0012015711981803179,-0.002212779363617301,0.0002066650486085564,0.08341696858406067 +1769682169,155267072,0.0,0.0,0.0,1.0,0.0007571160094812512,-0.0007277927361428738,-0.001242071040906012,-0.016385916620492935,0.07498133927583694,0.0578109510242939 +1769682169,176632832,0.0,0.0,0.0,1.0,0.0003406075411476195,-0.0014829738065600395,-0.0013421953190118074,0.014335733838379383,-0.07478638738393784,0.019648294895887375 +1769682169,210090752,0.0,0.0,0.0,1.0,0.0001874240697361529,-0.0019596978090703487,-0.0014215904520824552,0.01456036139279604,-0.07480670511722565,0.011306343600153923 +1769682169,247745536,0.0,0.0,0.0,1.0,8.667960355523974e-05,-0.0021595871075987816,-0.0014805082464590669,-0.014502931386232376,0.0747997835278511,-0.013688812963664532 +1769682169,276593920,0.0,0.0,0.0,1.0,0.00010987000860041007,-0.0020083808340132236,-0.001483044121414423,0.07524606585502625,0.014819378033280373,-0.01475540455430746 +1769682169,309911040,0.0,0.0,0.0,1.0,8.912704652175307e-05,-0.0017658623401075602,-0.001454278128221631,-0.08925580233335495,0.05992747098207474,-0.017994748428463936 +1769682169,361544960,0.0,0.0,0.0,1.0,-0.0025836401619017124,0.0005310585256665945,-0.0014737441670149565,-0.1500808596611023,-0.02969423681497574,0.014029519632458687 +1769682169,370972928,0.0,0.0,0.0,1.0,-0.0008902574772946537,0.0030279578641057014,-0.0013531575677916408,-0.15105023980140686,-0.02960829809308052,0.05096360296010971 +1769682169,409719296,0.0,0.0,0.0,1.0,0.0002294660807820037,0.006925718393176794,-0.0011067544110119343,0.013792406767606735,-0.07473069429397583,0.04109310358762741 +1769682169,457537536,0.0,0.0,0.0,1.0,0.0007019922486506402,0.009268475696444511,-0.0009209210984408855,-0.1801086813211441,0.11997293680906296,0.023496638983488083 +1769682169,476245248,0.0,0.0,0.0,1.0,0.0009384892764501274,0.009991019032895565,-0.0008349494310095906,-0.17969882488250732,0.11993034183979034,0.007949123159050941 +1769682169,510532864,0.0,0.0,0.0,1.0,0.0010862975614145398,0.010194547474384308,-0.0007898716139607131,0.05983252450823784,0.08971896022558212,0.004991532769054174 +1769682169,543004160,0.0,0.0,0.0,1.0,0.0012453144881874323,0.009980258531868458,-0.0007725837058387697,0.07503165304660797,0.01486215740442276,-0.006306638941168785 +1769682169,578462464,0.0,0.0,0.0,1.0,0.0013249145122244954,0.009332308545708656,-0.0007875835872255266,-0.14929719269275665,-0.029799753800034523,-0.01485040970146656 +1769682169,610601472,0.0,0.0,0.0,1.0,0.0013936248142272234,0.008795837871730328,-0.0008152606314979494,0.0002704001381061971,-2.522240174585022e-05,-0.009532882831990719 +1769682169,658249472,0.0,0.0,0.0,1.0,0.001418262254446745,0.008348100818693638,-0.0008368761627934873,0.08974360674619675,-0.0599432997405529,0.0003443891182541847 +1769682169,671581184,0.0,0.0,0.0,1.0,0.0014282335760071874,0.007918767631053925,-0.0008557515102438629,0.06022634357213974,0.08968871831893921,-0.009239980950951576 +1769682169,712993280,0.0,0.0,0.0,1.0,0.0028100900817662477,0.006729878485202789,-0.000888952927198261,0.06064273416996002,0.0896497443318367,-0.023529356345534325 +1769682169,749838336,0.0,0.0,0.0,1.0,0.003665565513074398,0.0057119145058095455,-0.0008723408100195229,0.0006654997705481946,-6.680264777969569e-05,-0.02263990230858326 +1769682169,779448320,0.0,0.0,0.0,1.0,0.004061036743223667,0.005287343170493841,-0.0008231911342591047,-0.029314979910850525,0.14960165321826935,-0.0168295968323946 +1769682169,810822400,0.0,0.0,0.0,1.0,0.004420613870024681,0.00508617190644145,-0.0007529299473389983,-0.014711042866110802,0.07480510324239731,-0.006639431696385145 +1769682169,862137344,0.0,0.0,0.0,1.0,0.004188194405287504,0.005328403785824776,-0.0006375217344611883,0.1350150853395462,0.10459566116333008,-0.007046586833894253 +1769682169,869885184,0.0,0.0,0.0,1.0,0.00412225816398859,0.005542040802538395,-0.0005869626183994114,-0.014640308916568756,0.07479460537433624,-0.009046332910656929 +1769682169,909811712,0.0,0.0,0.0,1.0,0.004051303490996361,0.005925416015088558,-0.00047661582357250154,0.015000339597463608,-0.0748358964920044,-0.0028534485027194023 +1769682169,943474944,0.0,0.0,0.0,1.0,0.003995171282440424,0.006165366154164076,-0.00041327407234348357,0.045004233717918396,0.164553701877594,0.0007554678013548255 +1769682169,976860672,0.0,0.0,0.0,1.0,0.003850708482787013,0.006353511940687895,-0.0003537751908879727,0.06011498346924782,0.08970431238412857,-0.005659664515405893 +1769682170,10596864,0.0,0.0,0.0,1.0,0.0006774709327146411,0.0050156912766397,-0.0005936870002187788,0.02670089341700077,-0.1492493599653244,0.1015971302986145 +1769682170,47559936,0.0,0.0,0.0,1.0,0.0021531658712774515,0.0008363767410628498,-0.0005552704096771777,0.17420554161071777,-0.11914825439453125,0.17284569144248962 +1769682170,76537344,0.0,0.0,0.0,1.0,0.0023296279832720757,-0.0015898029087111354,-0.0005174407851882279,0.07066000252962112,0.015458771958947182,0.1357021927833557 +1769682170,110156032,0.0,0.0,0.0,1.0,0.002414716174826026,-0.0031990897841751575,-0.00047457884647883475,0.1466720551252365,0.030221790075302124,0.09862076491117477 +1769682170,146303232,0.0,0.0,0.0,1.0,0.0025870443787425756,-0.004321044776588678,-0.0003963633789680898,-0.0014994514640420675,0.0002076981181744486,0.04885239526629448 +1769682170,177305856,0.0,0.0,0.0,1.0,0.001819494180381298,-0.004812199156731367,-0.0004696545365732163,0.1945357769727707,-0.1946614682674408,-0.001563261728733778 +1769682170,210503424,0.0,0.0,0.0,1.0,0.0008895985083654523,-0.0053868661634624004,-0.0005674431449733675,0.10539081692695618,-0.13483531773090363,-0.02244751900434494 +1769682170,257304064,0.0,0.0,0.0,1.0,0.0005210506496950984,-0.005529292393475771,-0.000590756069868803,0.0011887908913195133,-0.00017195948748849332,-0.039320752024650574 +1769682170,276989184,0.0,0.0,0.0,1.0,-0.0011286389781162143,-0.004778048489242792,-0.0006089358357712626,-0.030428055673837662,-0.23932936787605286,0.012059439904987812 +1769682170,312843776,0.0,0.0,0.0,1.0,-0.002646109787747264,-0.0014169934438541532,-0.0006051367381587625,-0.2569633424282074,0.10526540130376816,0.0848822221159935 +1769682170,343513600,0.0,0.0,0.0,1.0,-0.0013119098730385303,0.002829981967806816,-0.00043310673208907247,-0.2713414430618286,0.18000110983848572,0.06623920798301697 +1769682170,376404736,0.0,0.0,0.0,1.0,0.0006607327959500253,0.007754624355584383,8.539114060113207e-05,-0.06009490042924881,-0.08971402794122696,0.005718688480556011 +1769682170,410059520,0.0,0.0,0.0,1.0,0.0015069091459736228,0.01015725452452898,0.00037850067019462585,0.06016999110579491,0.08970313519239426,-0.00808804389089346 +1769682170,445616128,0.0,0.0,0.0,1.0,0.0023701570462435484,0.01172644179314375,0.000655328156426549,-0.07438070327043533,-0.014979934319853783,-0.015357007272541523 +1769682170,477491200,0.0,0.0,0.0,1.0,0.0028180070221424103,0.012049585580825806,0.0007840557373128831,-0.08901827782392502,0.059803422540426254,-0.024520965293049812 +1769682170,511491840,0.0,0.0,0.0,1.0,0.003178634913638234,0.011871098540723324,0.0008631066884845495,-0.0146375996991992,0.07478245347738266,-0.009150521829724312 +1769682170,558972672,0.0,0.0,0.0,1.0,0.003498730482533574,0.011184826493263245,0.0009095020359382033,0.0605754591524601,0.08963818103075027,-0.019939696416258812 +1769682170,579174656,0.0,0.0,0.0,1.0,0.003684437368065119,0.010597091168165207,0.0009328412124887109,0.1498013734817505,0.02979719638824463,-0.002435927512124181 +1769682170,610140672,0.0,0.0,0.0,1.0,0.003853463800624013,0.010017978958785534,0.000950329122133553,0.07505763322114944,0.014873082749545574,-0.005962497554719448 +1769682170,646668544,0.0,0.0,0.0,1.0,0.003951926715672016,0.009329580701887608,0.0010093816090375185,0.059932783246040344,0.08972688019275665,0.0003418907872401178 +1769682170,678131712,0.0,0.0,0.0,1.0,0.004064695909619331,0.008920791558921337,0.0011134558590129018,-0.00011945421283598989,1.844632060965523e-05,0.0035742379259318113 +1769682170,710675456,0.0,0.0,0.0,1.0,0.005144210997968912,0.008149229921400547,0.0012100852327421308,0.09099303185939789,-0.060123953968286514,-0.03597905486822128 +1769682170,745226496,0.0,0.0,0.0,1.0,0.006774422246962786,0.0065933708101511,0.0014140618732199073,0.06067168340086937,0.08960078656673431,-0.021099932491779327 +1769682170,776603904,0.0,0.0,0.0,1.0,0.007387167774140835,0.00582757405936718,0.001587667386047542,0.2098817229270935,0.11945626139640808,-0.005450839176774025 +1769682170,809958400,0.0,0.0,0.0,1.0,0.007792653515934944,0.005365479271858931,0.0017608031630516052,0.00024524779291823506,-4.288608761271462e-05,-0.007148227654397488 +1769682170,850232064,0.0,0.0,0.0,1.0,0.007034172769635916,0.005594139453023672,0.0019546516705304384,0.09100982546806335,-0.060180485248565674,-0.03584178164601326 +1769682170,877055488,0.0,0.0,0.0,1.0,0.006233781110495329,0.00636997539550066,0.0020566913299262524,0.0012404345907270908,-0.00023240801237989217,-0.035740531980991364 +1769682170,910302208,0.0,0.0,0.0,1.0,0.00587294390425086,0.007067777682095766,0.002118473406881094,-0.0736629068851471,-0.015099041163921356,-0.034677665680646896 +1769682170,950524416,0.0,0.0,0.0,1.0,0.003280461532995105,0.00692317821085453,0.001949226832948625,0.13037535548210144,-0.28368431329727173,0.11509448289871216 +1769682170,977113088,0.0,0.0,0.0,1.0,0.002526381751522422,0.003862750018015504,0.001833758084103465,0.2163149118423462,0.04620452970266342,0.23516514897346497 +1769682171,11291392,0.0,0.0,0.0,1.0,0.0032379142940044403,0.00020089070312678814,0.0018652635626494884,0.08246127516031265,-0.05853145569562912,0.2061193436384201 +1769682171,56182784,0.0,0.0,0.0,1.0,0.003323749639093876,-0.0025826366618275642,0.0018773800693452358,0.0989496186375618,-0.13367721438407898,0.16071876883506775 +1769682171,77270016,0.0,0.0,0.0,1.0,0.003375817323103547,-0.004876978695392609,0.0018654639134183526,-0.13793213665485382,-0.10389348119497299,0.08656178414821625 +1769682171,110921984,0.0,0.0,0.0,1.0,0.0035328688099980354,-0.0057256994768977165,0.0018795871874317527,0.027781320735812187,-0.1492663323879242,0.055754415690898895 +1769682171,143167744,0.0,0.0,0.0,1.0,0.0037912495899945498,-0.005975660867989063,0.001982602756470442,-0.07566417008638382,-0.014665487222373486,0.02252398245036602 +1769682171,177149952,0.0,0.0,0.0,1.0,0.004208291415125132,-0.005657627247273922,0.0022674857173115015,-0.13419288396835327,-0.10465537011623383,-0.02054077759385109 +1769682171,210341632,0.0,0.0,0.0,1.0,0.002220640191808343,-0.006004542112350464,0.002184601966291666,-0.028097590431571007,-0.2398526966571808,-0.06471268832683563 +1769682171,244705280,0.0,0.0,0.0,1.0,0.0004172767512500286,-0.005981673952192068,0.002122723264619708,0.06029877811670303,-0.2995811402797699,-0.026613086462020874 +1769682171,276617216,0.0,0.0,0.0,1.0,-6.26456894678995e-05,-0.004227244760841131,0.0022373381070792675,-0.2243971973657608,-0.04449360817670822,-0.007292372174561024 +1769682171,311672320,0.0,0.0,0.0,1.0,-0.00013677416427526623,-0.0027736134361475706,0.0024098888970911503,-0.05992140248417854,-0.0896817147731781,-0.003721023676916957 +1769682171,358126080,0.0,0.0,0.0,1.0,-0.0003883632889483124,-0.0013527319533750415,0.002633803291246295,-0.0894714966416359,0.05999269708991051,-0.007075679022818804 +1769682171,376616448,0.0,0.0,0.0,1.0,0.0007009042310528457,1.0640129403327592e-05,0.002997621428221464,-0.17667442560195923,0.11948106437921524,-0.08086580038070679 +1769682171,410272768,0.0,0.0,0.0,1.0,0.0018799913814291358,0.0013804992195218801,0.0033901433926075697,0.0768633559346199,0.014328519813716412,-0.058341581374406815 +1769682171,459639040,0.0,0.0,0.0,1.0,0.002637461293488741,0.0022725313901901245,0.0036836161743849516,-0.05842006579041481,-0.09001677483320236,-0.04898330941796303 +1769682171,476803072,0.0,0.0,0.0,1.0,0.00339810224249959,0.002825726754963398,0.0039461697451770306,0.16514407098293304,-0.045456018298864365,-0.016675475984811783 +1769682171,511735040,0.0,0.0,0.0,1.0,0.0038691656664013863,0.00288582406938076,0.004084479995071888,0.09008623659610748,-0.06019633263349533,-0.01194083970040083 +1769682171,551371776,0.0,0.0,0.0,1.0,0.00434227054938674,0.002677807817235589,0.004229881800711155,-0.08975113928318024,0.06013397499918938,0.0023899758234620094 +1769682171,576996096,0.0,0.0,0.0,1.0,0.004677336663007736,0.002417071256786585,0.004339242819696665,0.05967940762639046,0.08970703184604645,0.013216414488852024 +1769682171,610731008,0.0,0.0,0.0,1.0,0.004878124687820673,0.002123713493347168,0.004459311254322529,0.07448779046535492,0.014827927574515343,0.011975995264947414 +1769682171,647626752,0.0,0.0,0.0,1.0,0.005085646640509367,0.0017376235919073224,0.004651129245758057,-0.00045154168037697673,0.00011567992623895407,0.01310474332422018 +1769682171,676631808,0.0,0.0,0.0,1.0,0.005226664245128632,0.0015325432177633047,0.00486593134701252,-0.0753132551908493,-0.014593704603612423,0.011846841312944889 +1769682171,710298112,0.0,0.0,0.0,1.0,0.0053535266779363155,0.0013658495154231787,0.005117088556289673,-0.015173347666859627,0.07498981058597565,0.013103749603033066 +1769682171,743765504,0.0,0.0,0.0,1.0,0.006839996203780174,0.00031097125611267984,0.005360893905162811,0.07548321038484573,0.014521684497594833,-0.016612600535154343 +1769682171,776829696,0.0,0.0,0.0,1.0,0.007680139504373074,-0.0007589053129777312,0.005688011646270752,0.0004938514903187752,-0.00013803178444504738,-0.014295930974185467 +1769682171,810947584,0.0,0.0,0.0,1.0,0.007998309098184109,-0.0012559817405417562,0.0058948504738509655,-0.05969908833503723,-0.08967921137809753,-0.015486860647797585 +1769682171,857324800,0.0,0.0,0.0,1.0,0.008192609995603561,-0.0015359995886683464,0.00605238601565361,0.07516156882047653,0.014561863616108894,-0.0071003008633852005 +1769682171,876931840,0.0,0.0,0.0,1.0,0.005826897453516722,-0.00026651512598618865,0.006187923718243837,-0.057933930307626724,-0.0902082696557045,-0.06785430759191513 +1769682171,910135296,0.0,0.0,0.0,1.0,0.003897795919328928,0.00029740747413598,0.006114359945058823,-0.12049447745084763,-0.17900331318378448,-0.002255825325846672 +1769682171,947141888,0.0,0.0,0.0,1.0,0.003719017142429948,-0.0007364056073129177,0.00607491098344326,0.17698904871940613,-0.11996126174926758,0.06105790659785271 +1769682171,977600256,0.0,0.0,0.0,1.0,0.0035067296121269464,-0.0015213247388601303,0.006042173132300377,0.08768616616725922,-0.05974151939153671,0.053762760013341904 +1769682172,2202880,0.0,0.0,0.0,1.0,0.003372387494891882,-0.0019515070598572493,0.006022575777024031,-0.07632041722536087,-0.014119112864136696,0.04047650471329689 +1769682172,43498240,0.0,0.0,0.0,1.0,0.0032583221327513456,-0.002570702228695154,0.0060310885310173035,-0.000979056116193533,0.00031608797144144773,0.028591744601726532 +1769682172,77263104,0.0,0.0,0.0,1.0,0.0032353189308196306,-0.0028806908521801233,0.006096202414482832,0.14914117753505707,0.029290050268173218,0.021462222561240196 +1769682172,110396928,0.0,0.0,0.0,1.0,0.0032620287965983152,-0.002952752634882927,0.00620763935148716,-0.08964378386735916,0.060447219759225845,0.004615907557308674 +1769682172,154693376,0.0,0.0,0.0,1.0,0.0033526024781167507,-0.0029076016508042812,0.006437384523451328,-0.22454579174518585,-0.043571799993515015,-0.008310586214065552 +1769682172,177227008,0.0,0.0,0.0,1.0,0.0034737265668809414,-0.0028215248603373766,0.006672307383269072,0.1352217048406601,0.10392075031995773,0.004567387048155069 +1769682172,210182912,0.0,0.0,0.0,1.0,0.0037391288205981255,-0.004150658845901489,0.0068221441470086575,0.0629461482167244,0.08851370960474014,-0.07406045496463776 +1769682172,244799232,0.0,0.0,0.0,1.0,0.0012879673158749938,-0.007454401347786188,0.006802957039326429,-0.011921296827495098,0.07402119040489197,-0.0764186903834343 +1769682172,276602624,0.0,0.0,0.0,1.0,0.0005201075691729784,-0.009189378470182419,0.006834214087575674,0.16634662449359894,-0.04677082970738411,-0.05953110754489899 +1769682172,313088768,0.0,0.0,0.0,1.0,-2.7762311219703406e-05,-0.010296273976564407,0.006873649079352617,-0.05910511314868927,-0.08984093368053436,-0.04263373464345932 +1769682172,348312320,0.0,0.0,0.0,1.0,-0.0005968931363895535,-0.010924625210464,0.006916997022926807,-0.045345522463321686,-0.16452693939208984,-0.023387543857097626 +1769682172,376895232,0.0,0.0,0.0,1.0,-0.0006734253838658333,-0.010780120268464088,0.007029132451862097,0.09025208652019501,-0.06087924540042877,-0.027394916862249374 +1769682172,410200576,0.0,0.0,0.0,1.0,0.0006559414323419333,-0.009702106937766075,0.007284428458660841,-0.012986650690436363,0.07441401481628418,-0.04423128440976143 +1769682172,446122752,0.0,0.0,0.0,1.0,0.001562945544719696,-0.008366623893380165,0.007527884561568499,0.000600005907472223,-0.00022597756469622254,-0.019062718376517296 +1769682172,477812224,0.0,0.0,0.0,1.0,0.001758837141096592,-0.0074843307957053185,0.007356575224548578,-0.04601322486996651,-0.16430148482322693,-0.007830030284821987 +1769682172,510468608,0.0,0.0,0.0,1.0,0.0023887446150183678,-0.006881603971123695,0.007257403340190649,0.06075509637594223,0.08920461684465408,-0.003954804502427578 +1769682172,546476800,0.0,0.0,0.0,1.0,0.0031572163570672274,-0.006448692176491022,0.0072548165917396545,-0.028845885768532753,0.1499839425086975,0.006839153356850147 +1769682172,579821824,0.0,0.0,0.0,1.0,0.0036581112071871758,-0.006357870530337095,0.007355428300797939,-0.08953754603862762,0.060789112001657486,0.008448072709143162 +1769682172,611317760,0.0,0.0,0.0,1.0,0.004044102970510721,-0.006410779897123575,0.00751373590901494,-0.06107116490602493,-0.08905578404664993,0.012364464811980724 +1769682172,646398720,0.0,0.0,0.0,1.0,0.004372835159301758,-0.00660440931096673,0.007794039789587259,0.0280833188444376,-0.14973969757556915,0.01464768499135971 +1769682172,677383680,0.0,0.0,0.0,1.0,0.0045098308473825455,-0.006790971849113703,0.008036904968321323,0.08891520649194717,-0.06062016636133194,0.010582503862679005 +1769682172,711909632,0.0,0.0,0.0,1.0,0.004511883482336998,-0.006988425273448229,0.008289700374007225,0.014079108834266663,-0.07490517944097519,0.00495539978146553 +1769682172,745733632,0.0,0.0,0.0,1.0,0.00484868697822094,-0.007406722754240036,0.008594506420195103,0.08937527239322662,-0.060885701328516006,-0.0061227018013596535 +1769682172,777087488,0.0,0.0,0.0,1.0,0.0049094646237790585,-0.007689653430134058,0.008798668161034584,-0.046553052961826324,-0.1641394942998886,-0.002775734756141901 +1769682172,810515968,0.0,0.0,0.0,1.0,0.004846529103815556,-0.007867014035582542,0.008964741602540016,0.23902007937431335,-0.032530274242162704,0.004961272235959768 +1769682172,847384320,0.0,0.0,0.0,1.0,0.0049309819005429745,-0.007884575985372066,0.009164524264633656,-0.1496255248785019,-0.02838451974093914,-0.01343756914138794 +1769682172,880148224,0.0,0.0,0.0,1.0,0.004024236463010311,-0.005534481257200241,0.00931078102439642,0.04699322581291199,-0.22720980644226074,-0.1637282818555832 +1769682172,911634944,0.0,0.0,0.0,1.0,0.0026879096403717995,-0.002783197211101651,0.00932567659765482,-0.19275544583797455,-0.1941613256931305,-0.14470933377742767 +1769682172,955712256,0.0,0.0,0.0,1.0,0.0019661616533994675,-0.00015318088117055595,0.009335190057754517,-0.13297298550605774,-0.10453466325998306,-0.1060696542263031 +1769682172,977419776,0.0,0.0,0.0,1.0,0.001690705306828022,0.0010346926283091307,0.009417307563126087,0.016024213284254074,-0.0759795531630516,-0.07005012035369873 +1769682173,10523136,0.0,0.0,0.0,1.0,0.0014488472370430827,0.001667300472036004,0.009566779248416424,-0.13481250405311584,-0.10358688235282898,-0.04291844367980957 +1769682173,56152832,0.0,0.0,0.0,1.0,0.001298608724027872,0.001847992418333888,0.00978076085448265,0.014399662613868713,-0.07520919293165207,-0.014041529968380928 +1769682173,77882880,0.0,0.0,0.0,1.0,0.001241441466845572,0.001633751904591918,0.010195421054959297,0.1636197865009308,-0.04693390429019928,0.014852331951260567 +1769682173,111926016,0.0,0.0,0.0,1.0,0.001193534699268639,0.0012632169527933002,0.010563439689576626,-0.061925213783979416,-0.08852177858352661,0.029306842014193535 +1769682173,147741696,0.0,0.0,0.0,1.0,0.0023446236737072468,0.0010816326830536127,0.011363902129232883,-0.10392588376998901,0.1366998255252838,0.036841195076704025 +1769682173,177225472,0.0,0.0,0.0,1.0,0.0015923883765935898,5.107234028400853e-05,0.011797046288847923,-0.1500585824251175,-0.027730172500014305,-0.0014954560901969671 +1769682173,210246912,0.0,0.0,0.0,1.0,0.0010854231659322977,-0.00131698208861053,0.012143809348344803,0.10274282097816467,-0.13623099029064178,0.001299083000048995 +1769682173,245047552,0.0,0.0,0.0,1.0,0.0009826498571783304,-0.0024064304307103157,0.012448750436306,-0.027720626443624496,0.15011349320411682,0.0018264846876263618 +1769682173,276867072,0.0,0.0,0.0,1.0,0.0009152116253972054,-0.003352697938680649,0.012849261052906513,0.08856546133756638,-0.06113702058792114,0.010541802272200584 +1769682173,310064896,0.0,0.0,0.0,1.0,0.0008749976404942572,-0.0036953932140022516,0.01311939675360918,-0.07498493045568466,-0.013777299784123898,-0.0031050792895257473 +1769682173,344660224,0.0,0.0,0.0,1.0,0.0007507550762966275,-0.0038064438849687576,0.01335025206208229,0.00013364199548959732,-6.906825001351535e-05,-0.004766001831740141 +1769682173,376781568,0.0,0.0,0.0,1.0,0.0006413217633962631,-0.0037160792853683233,0.013577303849160671,-0.04765436053276062,-0.1638195514678955,-0.0013331035152077675 +1769682173,411399936,0.0,0.0,0.0,1.0,0.0008750458946451545,-0.003385017393156886,0.013762195594608784,-0.06104886904358864,-0.08890305459499359,-0.013519645668566227 +1769682173,457789440,0.0,0.0,0.0,1.0,0.0009971336694434285,-0.003024097066372633,0.013923460617661476,-0.07464790344238281,-0.013836700469255447,-0.01617550477385521 +1769682173,479351296,0.0,0.0,0.0,1.0,0.0011794435558840632,-0.0026256106793880463,0.014120065607130527,-0.12260536104440689,-0.17751385271549225,-0.015085927210748196 +1769682173,511676672,0.0,0.0,0.0,1.0,0.0013079707277938724,-0.0024304301477968693,0.014272447675466537,0.040690429508686066,-0.22528621554374695,-0.0003369490150362253 +1769682173,543621888,0.0,0.0,0.0,1.0,0.0014191356021910906,-0.002297820057719946,0.014450062066316605,-9.79202231974341e-05,5.2803472499363124e-05,0.003574550151824951 +1769682173,577765376,0.0,0.0,0.0,1.0,0.0014925135765224695,-0.0022116375621408224,0.014707439579069614,-0.048313867300748825,-0.1635780930519104,0.005880555137991905 +1769682173,610213376,0.0,0.0,0.0,1.0,0.0015425572637468576,-0.0021854829974472523,0.014897504821419716,-0.08848791569471359,0.06164708733558655,-0.0033277247566729784 +1769682173,646571520,0.0,0.0,0.0,1.0,0.001471738563850522,-0.00222206418402493,0.015120538882911205,0.11518192291259766,-0.2118990123271942,0.006298772059381008 +1769682173,677068544,0.0,0.0,0.0,1.0,0.0014666272327303886,-0.002262794179841876,0.015284075401723385,-0.07518862187862396,-0.013311349786818027,0.001744224689900875 +1769682173,711431424,0.0,0.0,0.0,1.0,0.0014210360823199153,-0.0023093633353710175,0.015418026596307755,0.0750017911195755,0.01338448841124773,0.00539919501170516 +1769682173,757745408,0.0,0.0,0.0,1.0,0.001415651640854776,-0.0024535127449780703,0.015558150596916676,0.00016008253442123532,-9.03477193787694e-05,-0.0059576332569122314 +1769682173,777156608,0.0,0.0,0.0,1.0,0.0013417123118415475,-0.0025161339435726404,0.015623992308974266,-0.062025513499975204,-0.08830227702856064,0.004452880937606096 +1769682173,809988352,0.0,0.0,0.0,1.0,0.0022664740681648254,-0.0031354122329503298,0.01586035266518593,0.14874373376369476,0.027283042669296265,0.0596088245511055 +1769682173,853947392,0.0,0.0,0.0,1.0,0.0018791698385030031,-0.002448965096846223,0.01603495143353939,-0.14876826107501984,-0.027193771675229073,-0.059588439762592316 +1769682173,877635072,0.0,0.0,0.0,1.0,0.0013408917002379894,-0.0014543727738782763,0.016038989648222923,0.089619942009449,-0.06282733380794525,-0.04913008585572243 +1769682173,910694912,0.0,0.0,0.0,1.0,0.0011872545583173633,-0.000649216934107244,0.01603369228541851,0.08943067491054535,-0.06277987360954285,-0.04317248985171318 +1769682173,943449856,0.0,0.0,0.0,1.0,0.0010954496683552861,-9.59962053457275e-05,0.016035504639148712,-0.07420139014720917,-0.013613423332571983,-0.03753107413649559 +1769682173,980856576,0.0,0.0,0.0,1.0,0.0009843670995905995,0.000312342366669327,0.01607494242489338,0.1637590378522873,-0.049427833408117294,-0.012785965576767921 +1769682174,11594240,0.0,0.0,0.0,1.0,0.0009597702301107347,0.00044441784848459065,0.01613047532737255,0.13763681054115295,0.10097016394138336,-0.00748000293970108 +1769682174,44588288,0.0,0.0,0.0,1.0,0.0012079470325261354,0.0005986327887512743,0.01618647389113903,-0.02624628134071827,0.150621235370636,0.013638267293572426 +1769682174,77313280,0.0,0.0,0.0,1.0,0.003215103643015027,0.001785457250662148,0.01629030331969261,0.07448133081197739,0.013302548788487911,0.028003111481666565 +1769682175,12707840,0.0,0.0,0.0,1.0,0.004811104387044907,0.004609519150108099,0.013687617145478725,0.03519948571920395,-0.22599567472934723,0.00983106717467308 +1769682175,82028288,0.0,0.0,0.0,1.0,0.0030421442352235317,0.008799281902611256,0.013342550955712795,0.024446113035082817,-0.15133532881736755,-0.02995387092232704 +1769682175,84824832,0.0,0.0,0.0,1.0,0.002445749007165432,0.01082986406981945,0.013153179548680782,0.174829363822937,-0.12767285108566284,-0.016400078311562538 +1769682175,127728640,0.0,0.0,0.0,1.0,0.0019447660306468606,0.012395569123327732,0.013014043681323528,0.32607385516166687,-0.10464697331190109,-0.03133785352110863 +1769682175,158953472,0.0,0.0,0.0,1.0,0.0013506913091987371,0.013576088473200798,0.01288351509720087,0.31403833627700806,-0.02921813726425171,-0.020977240055799484 +1769682175,168944384,0.0,0.0,0.0,1.0,0.0011277158046141267,0.01363843772560358,0.012839442119002342,0.337053507566452,-0.17993679642677307,-0.010268916375935078 +1769682175,211115008,0.0,0.0,0.0,1.0,0.000731694046407938,0.014221007004380226,0.012787895277142525,0.2499418407678604,-0.1163005381822586,-0.011565079912543297 +1769682175,243354624,0.0,0.0,0.0,1.0,0.0004896500613540411,0.013715742155909538,0.012756314128637314,0.5625820159912109,-0.14518821239471436,0.01084837131202221 +1769682175,278623232,0.0,0.0,0.0,1.0,0.00029081915272399783,0.013159438036382198,0.012734843418002129,0.4234008491039276,-0.24407799541950226,0.0037449400406330824 +1769682175,311846912,0.0,0.0,0.0,1.0,0.000174427725141868,0.012271372601389885,0.012716218829154968,0.5849382281303406,-0.29623496532440186,0.029189717024564743 +1769682175,347150336,0.0,0.0,0.0,1.0,0.0008228321094065905,0.012220349162817001,0.012840807437896729,0.6157327890396118,0.015849951654672623,-0.015847962349653244 +1769682175,377105920,0.0,0.0,0.0,1.0,0.001365568838082254,0.012728861533105373,0.012945203110575676,0.6912965774536133,0.02698354423046112,-0.018089650198817253 +1769682175,410735872,0.0,0.0,0.0,1.0,0.0016915348824113607,0.012702392414212227,0.013010927475988865,0.8637873530387878,-0.10066324472427368,0.022551434114575386 +1769682175,453473536,0.0,0.0,0.0,1.0,0.0020670671947300434,0.01290967594832182,0.01306141261011362,0.7887682914733887,-0.11274988204240799,0.007540734484791756 +1769682175,478650624,0.0,0.0,0.0,1.0,0.0022203640546649694,0.013105185702443123,0.01306874305009842,0.8641262650489807,-0.10169532895088196,0.010241576470434666 +1769682175,511781632,0.0,0.0,0.0,1.0,0.0024058492854237556,0.013493295758962631,0.01306801289319992,0.9395740032196045,-0.09074448049068451,0.010628682561218739 +1769682175,548351488,0.0,0.0,0.0,1.0,0.002547206822782755,0.013337933458387852,0.013036293908953667,1.0145964622497559,-0.07975807785987854,0.02312704548239708 +1769682175,578380544,0.0,0.0,0.0,1.0,0.0029116610530763865,0.012972062453627586,0.012985331006348133,1.0040721893310547,-0.005094666033983231,0.0014426149427890778 +1769682175,610217984,0.0,0.0,0.0,1.0,0.004185427445918322,0.012027253396809101,0.01293336134403944,1.0265134572982788,-0.1564258337020874,0.003137631341814995 +1769682175,655438848,0.0,0.0,0.0,1.0,0.006730027962476015,0.009535083547234535,0.013247506693005562,1.0540227890014648,0.15791787207126617,0.08786863088607788 +1769682175,678093312,0.0,0.0,0.0,1.0,0.008647286333143711,0.0077784801833331585,0.013544336892664433,1.077212929725647,0.005970768630504608,0.06695666164159775 +1769682175,712687872,0.0,0.0,0.0,1.0,0.00722965644672513,0.006574214436113834,0.013502741232514381,1.1099454164505005,-0.22057269513607025,0.0860380083322525 +1769682175,750454784,0.0,0.0,0.0,1.0,0.005760854575783014,0.005138504784554243,0.01326600182801485,1.2501368522644043,-0.12374761700630188,0.07646338641643524 +1769682175,778627840,0.0,0.0,0.0,1.0,0.0052919466979801655,0.00473939860239625,0.013104984536767006,1.2731108665466309,-0.2757302522659302,0.05317552387714386 +1769682175,804359936,0.0,0.0,0.0,1.0,0.004999938886612654,0.004727077670395374,0.013008983805775642,1.3044471740722656,0.036934904754161835,0.050452448427677155 +1769682175,849614592,0.0,0.0,0.0,1.0,0.004587073810398579,0.00505072483792901,0.01276277843862772,1.3157541751861572,-0.039571020752191544,0.04320792853832245 +1769682175,878240000,0.0,0.0,0.0,1.0,0.006438060197979212,0.006645675748586655,0.012617647647857666,1.3906457424163818,-0.02878987230360508,0.060369834303855896 +1769682175,910589440,0.0,0.0,0.0,1.0,0.007239062339067459,0.008063488639891148,0.012507411651313305,1.391164779663086,-0.02960383892059326,0.046399857848882675 +1769682175,946522624,0.0,0.0,0.0,1.0,0.006530736107379198,0.009275882504880428,0.012242562137544155,1.348649263381958,-0.2679215669631958,0.038454242050647736 +1769682175,978408704,0.0,0.0,0.0,1.0,0.0037366333417594433,0.010203784331679344,0.01177509967237711,1.4245147705078125,-0.257801353931427,0.028469786047935486 +1769682176,11283456,0.0,0.0,0.0,1.0,0.0024717217311263084,0.010585635900497437,0.01137456577271223,1.4996073246002197,-0.24727892875671387,0.03879468888044357 +1769682176,61358848,0.0,0.0,0.0,1.0,0.0013395852874964476,0.011002044193446636,0.010948389768600464,1.705286979675293,-0.06496110558509827,0.020901799201965332 +1769682176,71933440,0.0,0.0,0.0,1.0,0.0009384100558236241,0.01088720839470625,0.010772242210805416,1.8016465902328491,-0.20522275567054749,0.0424804612994194 +1769682176,110642688,0.0,0.0,0.0,1.0,0.00016654074715916067,0.010577697306871414,0.010460606776177883,1.7259684801101685,-0.2167123705148697,0.04286311939358711 +1769682176,144887808,0.0,0.0,0.0,1.0,-0.00020145719463471323,0.010050778277218342,0.010263392701745033,1.866169810295105,-0.1202251985669136,0.0469193235039711 +1769682176,177707008,0.0,0.0,0.0,1.0,-0.0009476428385823965,0.004237186163663864,0.009863615967333317,1.9383032321929932,-0.10847850143909454,0.13123677670955658 +1769682176,210710784,0.0,0.0,0.0,1.0,-0.0015191129641607404,-0.0038902645464986563,0.009411598555743694,1.7105578184127808,-0.14045841991901398,0.15365003049373627 +1769682176,245229056,0.0,0.0,0.0,1.0,-0.0019396755378693342,-0.012041286565363407,0.008939438499510288,1.5594362020492554,-0.16221173107624054,0.1511249542236328 +1769682176,278544640,0.0,0.0,0.0,1.0,-0.0021132617257535458,-0.020780153572559357,0.008370605297386646,1.150780439376831,0.010280657559633255,0.11692625284194946 +1769682176,311672320,0.0,0.0,0.0,1.0,-0.0021387808956205845,-0.024852395057678223,0.008005058392882347,1.0968624353408813,-0.15191030502319336,0.10799380391836166 +1769682176,348464128,0.0,0.0,0.0,1.0,-0.002055578865110874,-0.02945072390139103,0.00757897412404418,0.7732787132263184,-0.04331904649734497,0.10651174187660217 +1769682176,377780480,0.0,0.0,0.0,1.0,-0.001977090025320649,-0.031390633434057236,0.007286889012902975,0.6885561347007751,0.020723536610603333,0.06787201017141342 +1769682176,409986048,0.0,0.0,0.0,1.0,-0.0017647178610786796,-0.0300393495708704,0.007051997818052769,0.4645109474658966,-0.012619024142622948,-0.008104080334305763 +1769682176,446029568,0.0,0.0,0.0,1.0,-0.0004767138743773103,-0.02839936874806881,0.006998601369559765,0.1522444784641266,0.020366698503494263,-0.02974974550306797 +1769682176,477354496,0.0,0.0,0.0,1.0,0.0001753883552737534,-0.027104880660772324,0.00689811771735549,0.06553028523921967,0.08577630668878555,-0.013942423276603222 +1769682176,512697344,0.0,0.0,0.0,1.0,0.0006883692112751305,-0.02622847817838192,0.006747488863766193,-0.09599106013774872,0.1402609944343567,-0.020520299673080444 +1769682176,554151424,0.0,0.0,0.0,1.0,0.0010983155807480216,-0.024235662072896957,0.0065710050985217094,-0.22490665316581726,-0.032660044729709625,-0.05906359851360321 +1769682176,579113216,0.0,0.0,0.0,1.0,0.0013939245836809278,-0.025048067793250084,0.006249959114938974,-0.3665872812271118,-0.12846660614013672,-0.030177239328622818 +1769682176,611174144,0.0,0.0,0.0,1.0,0.0016858996823430061,-0.02411426417529583,0.006026852875947952,-0.614508867263794,-0.00843936949968338,-0.026973549276590347 +1769682176,643749120,0.0,0.0,0.0,1.0,0.0018988624215126038,-0.02376832254230976,0.005804114509373903,-0.8517923951148987,0.035988397896289825,-0.02743520773947239 +1769682176,677217536,0.0,0.0,0.0,1.0,0.0020278883166611195,-0.02423437498509884,0.005525280721485615,-0.8621044754981995,0.11165662109851837,-0.03212222456932068 +1769682176,712551168,0.0,0.0,0.0,1.0,0.0021634213626384735,-0.02253546752035618,0.005372379906475544,-1.1540021896362305,-0.005448352545499802,-0.034810781478881836 +1769682176,744382976,0.0,0.0,0.0,1.0,0.002530446043238044,-0.019114339724183083,0.00523989787325263,-1.2492787837982178,0.1345915049314499,-0.07797983288764954 +1769682176,777055744,0.0,0.0,0.0,1.0,0.00564887560904026,-0.014421399682760239,0.005440751556307077,-1.1096010208129883,0.2320891171693802,-0.03623037412762642 +1769682176,810198784,0.0,0.0,0.0,1.0,0.007591647561639547,-0.011012433096766472,0.005740716587752104,-1.1091949939727783,0.23194953799247742,-0.05017075315117836 +1769682176,843740160,0.0,0.0,0.0,1.0,0.009026614017784595,-0.007728228345513344,0.005906100384891033,-1.1640602350234985,0.07062088698148727,-0.047722600400447845 +1769682176,878867712,0.0,0.0,0.0,1.0,0.00989948958158493,-0.004072662442922592,0.005837657488882542,-1.2291784286499023,-0.015162520110607147,-0.05198615416884422 +1769682176,911025920,0.0,0.0,0.0,1.0,0.007295397110283375,-0.002291633514687419,0.005449275020509958,-1.0682686567306519,-0.0693608969449997,-0.026150759309530258 +1769682176,959403776,0.0,0.0,0.0,1.0,0.006167261395603418,-0.0010288241319358349,0.005024902988225222,-1.0136642456054688,0.09266537427902222,-0.014154010452330112 +1769682176,977113344,0.0,0.0,0.0,1.0,0.00560845248401165,-0.0006803490687161684,0.0047801039181649685,-0.992969274520874,-0.058443110436201096,-0.0147919412702322 +1769682177,11261184,0.0,0.0,0.0,1.0,0.005183124449104071,-0.0006994091672822833,0.004594781436026096,-1.0791903734207153,0.0072904229164123535,-0.004247636534273624 +1769682177,44366336,0.0,0.0,0.0,1.0,0.004715846385806799,-0.0009352811612188816,0.004441382363438606,-1.0687154531478882,-0.0683378279209137,-0.010478019714355469 +1769682177,78913792,0.0,0.0,0.0,1.0,0.006915355566889048,0.00016253595822490752,0.0042213560082018375,-0.9189270734786987,-0.046296365559101105,0.04537617415189743 +1769682177,111414272,0.0,0.0,0.0,1.0,0.00782365445047617,0.0008414709009230137,0.004086409229785204,-1.0801727771759033,0.008687583729624748,0.03389093279838562 +1769682177,163009024,0.0,0.0,0.0,1.0,0.008580450899899006,0.0012929632794111967,0.00388599606230855,-1.0040993690490723,0.018669109791517258,0.01647847145795822 +1769682177,169649408,0.0,0.0,0.0,1.0,0.005413845181465149,0.001063937321305275,0.0035259800497442484,-1.1137683391571045,-0.30469053983688354,-0.0021620718762278557 +1769682177,211987456,0.0,0.0,0.0,1.0,0.0026771274860948324,0.0007407134398818016,0.0028886785730719566,-1.1646040678024292,0.07309269905090332,-0.022510668262839317 +1769682177,247353600,0.0,0.0,0.0,1.0,0.0013239601394161582,0.00033020612318068743,0.0024003353901207447,-1.0684870481491089,-0.06781397759914398,-0.021259348839521408 +1769682177,277944064,0.0,0.0,0.0,1.0,0.0005800612270832062,0.00010242091957479715,0.002099012490361929,-1.0990183353424072,0.1589309275150299,-0.030160803347826004 +1769682177,310702336,0.0,0.0,0.0,1.0,-1.0361956810811535e-05,-2.5091561838053167e-05,0.0018647611141204834,-0.9827501177787781,-0.1329895555973053,-0.016195880249142647 +1769682177,347891200,0.0,0.0,0.0,1.0,-0.00044438333134166896,-0.00011248777445871383,0.0016496507450938225,-1.078995943069458,0.008272020146250725,-0.011519024148583412 +1769682177,378763008,0.0,0.0,0.0,1.0,-0.0006953692063689232,-0.00015156084555201232,0.0015637276228517294,-1.0789337158203125,0.008263498544692993,-0.013897099532186985 +1769682177,410801920,0.0,0.0,0.0,1.0,-0.0007784661720506847,-0.0001382755726808682,0.0015216454630717635,-0.9931678771972656,-0.05703829228878021,-0.010020589455962181 +1769682177,456728832,0.0,0.0,0.0,1.0,-0.0008097804966382682,1.7955728253582492e-05,0.0015259092906489968,-1.2401574850082397,0.0633917897939682,-0.024227028712630272 +1769682177,478070272,0.0,0.0,0.0,1.0,-0.0007448082324117422,0.0004971256712451577,0.001560078701004386,-1.0032216310501099,0.01853080838918686,-0.01695805788040161 +1769682177,513233664,0.0,0.0,0.0,1.0,-0.000687257619574666,0.0015055951662361622,0.0016090160934254527,-1.0031583309173584,0.018519235774874687,-0.019374314695596695 +1769682177,544104448,0.0,0.0,0.0,1.0,-0.0005465279682539403,0.002612255048006773,0.001651286380365491,-0.9273200035095215,0.028543224558234215,-0.02725827880203724 +1769682177,579446784,0.0,0.0,0.0,1.0,0.0007695131353102624,0.004861122462898493,0.001930823316797614,-0.9358488321304321,0.10263793915510178,-0.09151359647512436 +1769682177,610501888,0.0,0.0,0.0,1.0,0.0022403430193662643,0.0064989677630364895,0.00222983886487782,-1.0772271156311035,0.007061373442411423,-0.07869909703731537 +1769682177,644050688,0.0,0.0,0.0,1.0,0.0031948480755090714,0.007633813191205263,0.0024466640315949917,-0.8511394262313843,0.03838770464062691,-0.04746843874454498 +1769682177,677493248,0.0,0.0,0.0,1.0,0.00419535581022501,0.008630335330963135,0.0026422312948852777,-0.7756264805793762,0.04874959588050842,-0.04240652173757553 +1769682177,712551680,0.0,0.0,0.0,1.0,0.004677869379520416,0.00891448650509119,0.0027403023559600115,-0.7004101872444153,0.05935674160718918,-0.026527658104896545 +1769682177,748028928,0.0,0.0,0.0,1.0,0.005210425704717636,0.008706732653081417,0.002815661486238241,-0.8723450899124146,0.1907401978969574,-0.015815554186701775 +1769682177,777541376,0.0,0.0,0.0,1.0,0.005477245897054672,0.008626934140920639,0.0028344481252133846,-0.7666850686073303,-0.025501718744635582,0.0032049668952822685 +1769682177,811856384,0.0,0.0,0.0,1.0,0.007355919573456049,0.0074302745051681995,0.002994533395394683,-0.5614013075828552,0.15741506218910217,0.04934083670377731 +1769682177,855596032,0.0,0.0,0.0,1.0,0.012098661623895168,0.003375878557562828,0.0036200217436999083,-0.7129769921302795,0.13758185505867004,0.059732839465141296 +1769682177,878224640,0.0,0.0,0.0,1.0,0.013981635682284832,0.0011735993903130293,0.003920612391084433,-0.6274169087409973,0.07237473130226135,0.06858878582715988 +1769682177,911161856,0.0,0.0,0.0,1.0,0.011730162426829338,0.0002385156403761357,0.00381236569955945,-0.746504008769989,-0.17635871469974518,0.006369061768054962 +1769682177,943769344,0.0,0.0,0.0,1.0,0.00934296753257513,-0.0003635278553701937,0.00348201347514987,-0.6052693128585815,-0.08055652678012848,0.0030025355517864227 +1769682177,981044224,0.0,0.0,0.0,1.0,0.00794870126992464,-0.00047955330228433013,0.0031084921211004257,-0.6805735230445862,-0.0908990129828453,-0.009532899595797062 +1769682178,11592960,0.0,0.0,0.0,1.0,0.007110929582268,-0.0003339307149872184,0.002878190716728568,-0.700289249420166,0.05993572250008583,-0.0286293663084507 +1769682178,47387648,0.0,0.0,0.0,1.0,0.00826476514339447,0.0012112893164157867,0.0025652600452303886,-0.7018644213676453,0.061597589403390884,0.0273258239030838 +1769682178,77965568,0.0,0.0,0.0,1.0,0.009343741461634636,0.002926544053480029,0.00238628382794559,-0.615916907787323,-0.0041390471160411835,0.02084960788488388 +1769682178,113029120,0.0,0.0,0.0,1.0,0.009932443499565125,0.004244738724082708,0.002226807177066803,-0.6258212327957153,0.0713668018579483,0.013533261604607105 +1769682178,144526592,0.0,0.0,0.0,1.0,0.00588035024702549,0.004155006259679794,0.0017622375162318349,-0.4426170885562897,-0.13713501393795013,-0.04203406348824501 +1769682178,177300480,0.0,0.0,0.0,1.0,0.002948691602796316,0.003684902796521783,0.0011800214415416121,-0.5184923410415649,-0.1469270884990692,-0.03442757576704025 +1769682178,210264064,0.0,0.0,0.0,1.0,0.0017103246646001935,0.0029566625598818064,0.0008517231908626854,-0.5185274481773376,-0.14687927067279816,-0.03327827900648117 +1769682178,261403648,0.0,0.0,0.0,1.0,0.0005023950943723321,0.002184792421758175,0.0005609440268017352,-0.443512886762619,-0.13618172705173492,-0.011186777614057064 +1769682178,278037248,0.0,0.0,0.0,1.0,-0.00016138955834321678,0.0017360191559419036,0.0004204532306175679,-0.32223841547966003,0.11062760651111603,-0.01976328156888485 +1769682178,313156608,0.0,0.0,0.0,1.0,-0.0005948844482190907,0.0014041526010259986,0.00033579254522919655,-0.2924518287181854,-0.1158602386713028,-0.002677137963473797 +1769682178,344268032,0.0,0.0,0.0,1.0,-0.0009584834333509207,0.0010584724368527532,0.0002880291431210935,-0.3027145564556122,-0.04002032056450844,0.0031250184401869774 +1769682178,379144704,0.0,0.0,0.0,1.0,-0.0011085050646215677,0.0011042465921491385,0.0002792263694573194,-0.3025765120983124,-0.04015747085213661,-0.0016542801167815924 +1769682178,410813440,0.0,0.0,0.0,1.0,-0.001152513548731804,0.0010278363479301333,0.00029309658566489816,-0.3682638704776764,-0.1257237046957016,0.00251973420381546 +1769682178,445065984,0.0,0.0,0.0,1.0,-0.0011524069122970104,0.0009919449221342802,0.00031077308813109994,-0.3127686679363251,0.03562072664499283,0.001765361987054348 +1769682178,480842752,0.0,0.0,0.0,1.0,0.00025636295322328806,0.0017420158255845308,0.0005530095659196377,-0.32083505392074585,0.10925265401601791,-0.06746330857276917 +1769682178,512627712,0.0,0.0,0.0,1.0,0.0018177087185904384,0.002694658702239394,0.0008338931947946548,-0.311232328414917,0.03408543020486832,-0.050680872052907944 +1769682178,545368320,0.0,0.0,0.0,1.0,0.0031172772869467735,0.0036351487506181,0.0010955912293866277,-0.31104907393455505,0.033916719257831573,-0.05668120086193085 +1769682178,577430272,0.0,0.0,0.0,1.0,0.003893554210662842,0.003989464603364468,0.0012199687771499157,-0.150358647108078,-0.02099420502781868,-0.032452456653118134 +1769682178,612472064,0.0,0.0,0.0,1.0,0.004480467643588781,0.003998494241386652,0.001302082440815866,-0.1709996610879898,0.13083018362522125,-0.016122249886393547 +1769682178,646024192,0.0,0.0,0.0,1.0,0.005083792842924595,0.004219502676278353,0.001380615751259029,-0.3023357689380646,-0.040340110659599304,-0.010190043598413467 +1769682178,678875904,0.0,0.0,0.0,1.0,0.005900311283767223,0.0036613272968679667,0.001567060244269669,-0.1930776685476303,0.2841429114341736,0.04889926686882973 +1769682178,710417408,0.0,0.0,0.0,1.0,0.009776018559932709,0.0008796800393611193,0.00200466625392437,-0.03236791118979454,0.229201540350914,0.07200828194618225 +1769682178,745614592,0.0,0.0,0.0,1.0,0.012490748427808285,-0.0022002358455210924,0.002426957478746772,-0.09756982326507568,0.14318712055683136,0.059480905532836914 +1769682178,770136320,0.0,0.0,0.0,1.0,0.011187806725502014,-0.0026682971511036158,0.002426762832328677,-0.12996402382850647,-0.17261935770511627,-0.04147079586982727 +1769682178,812277504,0.0,0.0,0.0,1.0,0.00763186439871788,-0.0022864043712615967,0.002042909385636449,-0.16036953032016754,0.05463999882340431,-0.0339367650449276 +1769682178,846485760,0.0,0.0,0.0,1.0,0.006274218671023846,-0.0017322328640148044,0.0017061291728168726,-0.1404286026954651,-0.09654106199741364,-0.02855265513062477 +1769682178,878590464,0.0,0.0,0.0,1.0,0.005471454467624426,-0.0013007137458771467,0.001487214583903551,-0.1503654420375824,-0.02098555862903595,-0.032426632940769196 +1769682178,910144768,0.0,0.0,0.0,1.0,0.0052704219706356525,-0.0007584769045934081,0.001282937591895461,-0.24695922434329987,0.12130960822105408,-0.0040422724559903145 +1769682178,946124032,0.0,0.0,0.0,1.0,0.006323520094156265,0.001075545558705926,0.001055461005307734,-0.15174411237239838,-0.019485970959067345,0.014030723832547665 +1769682178,977535488,0.0,0.0,0.0,1.0,0.00656279269605875,0.0019662517588585615,0.0008958057733252645,-0.2374519407749176,0.04623761773109436,0.014121013693511486 +1769682179,10652160,0.0,0.0,0.0,1.0,0.0034825927577912807,0.00016737982514314353,0.0004950167494826019,0.154188334941864,0.016793575137853622,-0.09619887918233871 +1769682179,45197056,0.0,0.0,0.0,1.0,0.0014527239836752415,-0.003309652442112565,6.457161362050101e-05,0.08753997832536697,-0.06774421781301498,-0.06201252341270447 +1769682179,78119680,0.0,0.0,0.0,1.0,0.0005463161505758762,-0.005326861049979925,-0.0001679055130807683,0.07701314240694046,0.008469044230878353,-0.045735809952020645 +1769682179,112744192,0.0,0.0,0.0,1.0,-0.00012814003275707364,-0.006680251099169254,-0.00033337707282043993,-0.00880575180053711,0.07430442422628403,-0.04206719994544983 +1769682179,155695872,0.0,0.0,0.0,1.0,-0.0006223865202628076,-0.00748121552169323,-0.00043896451825276017,0.020264388993382454,-0.1515711098909378,-0.0063839745707809925 +1769682179,177418240,0.0,0.0,0.0,1.0,-0.0010683384025469422,-0.00787278264760971,-0.000521527137607336,-0.07595181465148926,-0.009641975164413452,0.01006167009472847 +1769682179,212012032,0.0,0.0,0.0,1.0,-0.0012434703530743718,-0.0078001925721764565,-0.000557239050976932,-0.00013597047654911876,0.00015550745592918247,0.004763898439705372 +1769682179,247679744,0.0,0.0,0.0,1.0,-0.0013418091693893075,-0.007507083937525749,-0.0005708531243726611,-0.15172383189201355,-0.01948571763932705,0.014248869381844997 +1769682179,279182336,0.0,0.0,0.0,1.0,-0.0013004245702177286,-0.0072691296227276325,-0.0005696844309568405,-0.010101144202053547,0.07574549317359924,0.002024367218837142 +1769682179,311966976,0.0,0.0,0.0,1.0,-0.0012597094755619764,-0.007088740821927786,-0.0005661810282617807,-0.0660710483789444,-0.08512341976165771,0.016441751271486282 +1769682179,347335680,0.0,0.0,0.0,1.0,0.0003582608769647777,-0.0060461778193712234,-0.0002945964806713164,-0.019188430160284042,0.15029041469097137,-0.03285494074225426 +1769682179,378141952,0.0,0.0,0.0,1.0,0.0011844115797430277,-0.005337085109204054,-0.0001505016116425395,-0.009124631062150002,0.07458304613828659,-0.033697761595249176 +1769682179,410171648,0.0,0.0,0.0,1.0,0.0018228834960609674,-0.004866356961429119,-5.5036216508597136e-05,0.0006485152989625931,-0.000775836524553597,-0.0238204225897789 +1769682179,458592000,0.0,0.0,0.0,1.0,0.002401274163275957,-0.004480957053601742,9.70444489212241e-06,0.05608295276761055,0.16071227192878723,-0.01924324966967106 +1769682179,479586816,0.0,0.0,0.0,1.0,0.002791578182950616,-0.004397863056510687,2.0267592844902538e-05,0.08580958843231201,-0.06582386046648026,-0.0038880775682628155 +1769682179,511378944,0.0,0.0,0.0,1.0,0.003028683830052614,-0.004436098039150238,7.718954293522984e-06,0.009974123910069466,-0.07558926194906235,0.0027485063765197992 +1769682179,557864448,0.0,0.0,0.0,1.0,0.0041709220968186855,-0.005144957918673754,0.0001811425609048456,0.2907288074493408,0.11790115386247635,0.06948406994342804 +1769682179,577918720,0.0,0.0,0.0,1.0,0.006422866135835648,-0.007099725306034088,0.0004581421671900898,0.05447081848978996,0.16271580755710602,0.04138132184743881 +1769682179,612946432,0.0,0.0,0.0,1.0,0.007400590926408768,-0.008283962495625019,0.0005940645933151245,0.06464345753192902,0.08689714223146439,0.03697098046541214 +1769682179,646919680,0.0,0.0,0.0,1.0,0.004830846097320318,-0.006046747788786888,0.00037890911335125566,-0.21288368105888367,-0.11084991693496704,-0.15572090446949005 +1769682179,677808896,0.0,0.0,0.0,1.0,0.0036543291062116623,-0.0027531322557479143,0.0001483889645896852,-0.14766691625118256,-0.024727797135710716,-0.14137986302375793 +1769682179,711164928,0.0,0.0,0.0,1.0,0.0030548020731657743,-0.0009300763485953212,2.5085902962018736e-05,-0.04284627363085747,-0.24054107069969177,-0.10393743962049484 +1769682179,744339200,0.0,0.0,0.0,1.0,0.002409700071439147,0.0006291713798418641,-8.628839714219794e-05,0.0020535015501081944,-0.002705558203160763,-0.07979802042245865 +1769682179,777596928,0.0,0.0,0.0,1.0,0.002476135501638055,0.0014210343360900879,-0.00014566679601557553,-0.0850650817155838,0.06486211717128754,-0.024679535999894142 +1769682179,846876928,0.0,0.0,0.0,1.0,0.0028961743228137493,0.0021794787608087063,-0.00019627201254479587,-0.07579827308654785,-0.00979376770555973,0.005535043776035309 +1769682179,864898560,0.0,0.0,0.0,1.0,0.0031137990299612284,0.0025297733955085278,-0.0002404476108495146,-0.08608107268810272,0.06619919836521149,0.014596652239561081 +1769682179,889543424,0.0,0.0,0.0,1.0,0.0008421821985393763,-0.0016938888002187014,-0.0004911435535177588,0.31607210636138916,-0.040237970650196075,-0.13122384250164032 +1769682179,903178752,0.0,0.0,0.0,1.0,0.0003880323492921889,-0.005204866174608469,-0.000601902196649462,0.23980140686035156,-0.049419667571783066,-0.10785050690174103 +1769682179,944479232,0.0,0.0,0.0,1.0,-0.000400530087063089,-0.010664120316505432,-0.0008092127391137183,0.2487114667892456,-0.12361160665750504,-0.06459983438253403 +1769682179,977839616,0.0,0.0,0.0,1.0,-0.0009883928578346968,-0.013965184800326824,-0.0010017654858529568,0.24761174619197845,-0.12213443219661713,-0.021855076774954796 +1769682180,13137152,0.0,0.0,0.0,1.0,-0.0011916172225028276,-0.01520752813667059,-0.001116137020289898,0.21703167259693146,0.10548266023397446,-0.0054368432611227036 +1769682180,48877312,0.0,0.0,0.0,1.0,-0.0013720059068873525,-0.01565086469054222,-0.0012328044977039099,0.08503750711679459,-0.06472128629684448,0.028102677315473557 +1769682180,78032128,0.0,0.0,0.0,1.0,-0.0014014557236805558,-0.015375963412225246,-0.0012876157416030765,-0.07620164006948471,-0.009201932698488235,0.02358195185661316 +1769682180,110929152,0.0,0.0,0.0,1.0,-0.0013137011555954814,-0.014858536422252655,-0.001314813387580216,-0.0006026285700500011,0.0008912477642297745,0.026203982532024384 +1769682180,154291200,0.0,0.0,0.0,1.0,-0.0011552302166819572,-0.014077828265726566,-0.001308515900745988,0.08500757068395615,-0.06459256261587143,0.031540725380182266 +1769682180,179201536,0.0,0.0,0.0,1.0,-0.0010486620012670755,-0.0135834701359272,-0.0012740767560899258,-0.01045606192201376,0.07627014815807343,0.01746436022222042 +1769682180,213317376,0.0,0.0,0.0,1.0,-0.0004097677010577172,-0.012907223775982857,-0.00114103511441499,0.07561597228050232,0.010066060349345207,0.0012935253325849771 +1769682180,245264896,0.0,0.0,0.0,1.0,0.00012122298358008265,-0.012233695015311241,-0.0009824695298448205,0.08573547005653381,-0.06567476689815521,-0.0007346040802076459 +1769682180,278142208,0.0,0.0,0.0,1.0,0.00034030259121209383,-0.011949067004024982,-0.0008846513228490949,0.06571830809116364,0.08545146882534027,-0.007498369552195072 +1769682180,310755584,0.0,0.0,0.0,1.0,0.0005411037127487361,-0.011780548840761185,-0.0008102878928184509,0.17147673666477203,-0.13134056329727173,-0.0015889580827206373 +1769682180,347814912,0.0,0.0,0.0,1.0,0.0006636325852014124,-0.01172435563057661,-0.0007728206692263484,4.750467269332148e-05,-8.087703463388607e-05,-0.0023823417723178864 +1769682180,377898496,0.0,0.0,0.0,1.0,0.000718095398042351,-0.011784958653151989,-0.0007728249183855951,0.07582695037126541,0.00971319992095232,-0.009581727907061577 +1769682180,413083904,0.0,0.0,0.0,1.0,0.0012658146442845464,-0.012175658717751503,-0.0006901998422108591,0.15047834813594818,0.0214945487678051,0.0415319949388504 +1769682180,448822528,0.0,0.0,0.0,1.0,0.0018121183384209871,-0.012938796542584896,-0.0005768054979853332,0.05480775237083435,0.16258104145526886,0.03485612943768501 +1769682180,477817600,0.0,0.0,0.0,1.0,0.0020012652967125177,-0.013236966915428638,-0.000566903327126056,0.15066777169704437,0.021221593022346497,0.033054810017347336 +1769682180,511630080,0.0,0.0,0.0,1.0,0.00015509975492022932,-0.009243365377187729,-0.0008327045943588018,-0.06049531698226929,-0.09530238807201385,-0.28057152032852173 +1769682180,562055936,0.0,0.0,0.0,1.0,-0.00010722107253968716,-0.0028974786400794983,-0.0010195407085120678,-0.15699924528598785,0.04719046503305435,-0.2453860193490982 +1769682180,568776960,0.0,0.0,0.0,1.0,-0.00026290485402569175,-0.0004790444509126246,-0.001091843587346375,0.0793011412024498,0.0030133428517729044,-0.20627152919769287 +1769682180,610711808,0.0,0.0,0.0,1.0,-0.0005391773884184659,0.0027750071603804827,-0.001184194115921855,0.07793355733156204,0.005662316456437111,-0.1288372427225113 +1769682180,644104704,0.0,0.0,0.0,1.0,-0.0007720674620941281,0.003951811231672764,-0.0012167462846264243,0.31405818462371826,-0.03812345489859581,-0.07895658165216446 +1769682180,679825664,0.0,0.0,0.0,1.0,-0.0003862146404571831,0.00646199518814683,-0.001207819557748735,0.15188080072402954,0.018979497253894806,-0.033676113933324814 +1769682180,712359424,0.0,0.0,0.0,1.0,-9.366836457047611e-05,0.007919189520180225,-0.0011630412191152573,0.0,-0.0,0.0 +1769682180,745765632,0.0,0.0,0.0,1.0,-0.0007131251040846109,0.007756324019283056,-0.001137814950197935,0.31160175800323486,-0.03349611163139343,0.05589614063501358 +1769682180,777909248,0.0,0.0,0.0,1.0,-0.0005047241575084627,0.0017776534659788013,-0.0012264649849385023,0.3978350758552551,-0.0999692752957344,0.029994502663612366 +1769682180,811394816,0.0,0.0,0.0,1.0,-0.0006206444813869894,-0.0027916976250708103,-0.001308166771195829,0.23648013174533844,-0.044476468116045,0.028631065040826797 +1769682180,844426752,0.0,0.0,0.0,1.0,-0.0007347814389504492,-0.00669656228274107,-0.0014197365380823612,0.16067616641521454,-0.05421408638358116,0.03823617845773697 +1769682180,877831680,0.0,0.0,0.0,1.0,-0.000799360394012183,-0.008157799020409584,-0.001499520381912589,0.009680486284196377,-0.07484755665063858,0.02419375069439411 +1769682180,911016960,0.0,0.0,0.0,1.0,-0.0007733625825494528,-0.00863452535122633,-0.0015790247125551105,0.07531051337718964,0.01068706251680851,0.01770368218421936 +1769682180,959517184,0.0,0.0,0.0,1.0,-0.0007285423926077783,-0.008296934887766838,-0.0016846751095727086,-0.00021184644720051438,0.0004039415216539055,0.011912301182746887 +1769682180,977607168,0.0,0.0,0.0,1.0,-0.0006254788604564965,-0.007645928766578436,-0.0017543755238875747,0.07546577602624893,0.010412461124360561,0.009322221390902996 +1769682181,11758848,0.0,0.0,0.0,1.0,-0.0005697101005353034,-0.006858225911855698,-0.0018192770658060908,0.08551976084709167,-0.0650768131017685,0.014423404820263386 +1769682181,47821056,0.0,0.0,0.0,1.0,-0.00042658508755266666,-0.005889450665563345,-0.0018710207659751177,0.15148720145225525,0.019754862412810326,-0.013588111847639084 +1769682181,80742400,0.0,0.0,0.0,1.0,-0.0004340485611464828,-0.005286562722176313,-0.0018938713474199176,-0.15130235254764557,-0.02012632042169571,0.0028915421571582556 +1769682181,113374720,0.0,0.0,0.0,1.0,-0.0007351434323936701,-0.005029705353081226,-0.0019446766236796975,0.1612505167722702,-0.05511471629142761,0.009340684860944748 +1769682181,152300288,0.0,0.0,0.0,1.0,-0.000947769614867866,-0.004874572157859802,-0.0019638463854789734,0.0755307674407959,0.010314974933862686,0.005675872787833214 +1769682181,177933568,0.0,0.0,0.0,1.0,-0.001074329949915409,-0.004803260322660208,-0.0019409173401072621,0.09590991586446762,-0.14110398292541504,0.002759433351457119 +1769682181,215306752,0.0,0.0,0.0,1.0,-0.0011792462319135666,-0.004803566727787256,-0.0019067743560299277,0.0,-0.0,0.0 +1769682181,248352768,0.0,0.0,0.0,1.0,-0.0013184298295527697,-0.004865662194788456,-0.0018734491895884275,0.07564664632081985,0.010088209062814713,-0.0015069725923240185 +1769682181,278119424,0.0,0.0,0.0,1.0,-0.0014086241135373712,-0.004906503949314356,-0.0018852788489311934,0.07566487789154053,0.01005249097943306,-0.0027089270297437906 +1769682181,311062272,0.0,0.0,0.0,1.0,-0.0012938036816194654,-0.005158115644007921,-0.0018764834385365248,0.15095102787017822,0.02091364748775959,0.018385693430900574 +1769682181,358104576,0.0,0.0,0.0,1.0,-0.001851107575930655,-0.00511948810890317,-0.0018902972806245089,0.0851966068148613,-0.06418796628713608,0.03926793485879898 +1769682181,378497536,0.0,0.0,0.0,1.0,-0.0023268545046448708,-0.0047066956758499146,-0.001971596386283636,0.009728646837174892,-0.07465136796236038,0.0300841573625803 +1769682181,413217024,0.0,0.0,0.0,1.0,-0.003085133619606495,-0.00277676316909492,-0.002147969091311097,0.06707625836133957,0.08222203701734543,-0.10788092017173767 +1769682181,445828864,0.0,0.0,0.0,1.0,-0.003089037723839283,0.0002735104935709387,-0.0022949757985770702,-0.063907191157341,-0.0890909731388092,-0.09822123497724533 +1769682181,480269824,0.0,0.0,0.0,1.0,-0.0030941301956772804,0.0018733597826212645,-0.0023662897292524576,0.06671633571386337,0.08300609141588211,-0.08522791415452957 +1769682181,510652416,0.0,0.0,0.0,1.0,-0.003112438600510359,0.0029023224487900734,-0.002381866332143545,0.0764867290854454,0.008319022133946419,-0.0563519187271595 +1769682181,545316864,0.0,0.0,0.0,1.0,-0.0029515817295759916,0.003529055044054985,-0.0022957928013056517,-0.01987984962761402,0.15011069178581238,-0.036267492920160294 +1769682181,578261760,0.0,0.0,0.0,1.0,-0.0029986975714564323,0.003523988416418433,-0.0021533267572522163,0.010391691699624062,-0.07599513232707977,-0.010463236831128597 +1769682181,613222912,0.0,0.0,0.0,1.0,-0.0031814021058380604,0.003212588606402278,-0.001990435877814889,0.07556314766407013,0.010303279384970665,0.003242078935727477 +1769682181,645344000,0.0,0.0,0.0,1.0,-0.0034420646261423826,0.002683475846424699,-0.0018216596217826009,-0.0655747801065445,-0.08544525504112244,0.012478500604629517 +1769682181,678342400,0.0,0.0,0.0,1.0,-0.0020246380008757114,0.003099327441304922,-0.0016424694331362844,-0.0007435396546497941,0.0015115472488105297,0.04646117612719536 +1769682181,711657216,0.0,0.0,0.0,1.0,-0.001410913304425776,0.0035864384844899178,-0.001563797239214182,0.08512980490922928,-0.06397069245576859,0.04520008713006973 +1769682181,763956992,0.0,0.0,0.0,1.0,-0.0009990022517740726,0.004008132498711348,-0.0016246199375018477,-0.06589468568563461,-0.08480100333690643,0.03269390016794205 +1769682181,773145344,0.0,0.0,0.0,1.0,-0.0008593577076680958,0.004113790579140186,-0.0017256269929930568,0.06492066383361816,0.08673494309186935,0.026878487318754196 +1769682181,810800384,0.0,0.0,0.0,1.0,-0.0005904138670302927,0.004192742519080639,-0.0020118062384426594,-0.010490251705050468,0.07610205560922623,0.014061965979635715 +1769682181,846095616,0.0,0.0,0.0,1.0,-0.00036884372821077704,0.004116255324333906,-0.0023843736853450537,0.055053938180208206,0.1615726798772812,0.001652450766414404 +1769682181,880597504,0.0,0.0,0.0,1.0,-0.00017945138097275048,0.004052004311233759,-0.002664396073669195,-0.09600778669118881,0.14077943563461304,-0.008556166663765907 +1769682181,912683520,0.0,0.0,0.0,1.0,1.997037179535255e-05,0.003960067871958017,-0.002900068648159504,0.0,-0.0,0.0 +1769682181,951052544,0.0,0.0,0.0,1.0,0.0002993257367052138,0.0038610256742686033,-0.003098325105383992,0.17172855138778687,-0.13067297637462616,0.0035866000689566135 +1769682181,978164992,0.0,0.0,0.0,1.0,0.0005188895156607032,0.003819667734205723,-0.0031344385351985693,0.0757347047328949,0.010016469284892082,-0.007371059153228998 +1769682182,15655680,0.0,0.0,0.0,1.0,-0.0005503940628841519,0.0031609132420271635,-0.003303193487226963,0.020118772983551025,-0.15037931501865387,0.027881978079676628 +1769682182,49987328,0.0,0.0,0.0,1.0,-0.0013464903458952904,0.002358220284804702,-0.0033579599112272263,0.06478359550237656,0.08686015754938126,0.02933601848781109 +1769682182,77963008,0.0,0.0,0.0,1.0,-0.0017797263571992517,0.0019574447069317102,-0.003315796609967947,0.08544335514307022,-0.06447330862283707,0.02743380516767502 +1769682182,110877440,0.0,0.0,0.0,1.0,-0.0022470266558229923,0.001700322492979467,-0.003264378057792783,0.1407465934753418,0.09645938873291016,0.007712622173130512 +1769682182,163701248,0.0,0.0,0.0,1.0,-0.0027577949222177267,0.0016188420122489333,-0.0032386225648224354,-0.08583257347345352,0.06514692306518555,-0.005989940371364355 +1769682182,170761472,0.0,0.0,0.0,1.0,-0.0029966826550662518,0.001639399561099708,-0.0032625538296997547,-0.08581558614969254,0.06510350853204727,-0.0071802097372710705 +1769682182,212899072,0.0,0.0,0.0,1.0,-0.0034002189058810472,0.001757744001224637,-0.003389133373275399,0.0859927088022232,-0.06539719551801682,-0.0023527792654931545 +1769682182,244773632,0.0,0.0,0.0,1.0,-0.004432597663253546,0.0023793107829988003,-0.003625419456511736,0.010187418200075626,-0.07532232254743576,0.009731253609061241 +1769682182,283875584,0.0,0.0,0.0,1.0,-0.0063511403277516365,0.0038580968976020813,-0.0038435827009379864,0.16131235659122467,-0.054523125290870667,0.014155345968902111 +1769682182,311256576,0.0,0.0,0.0,1.0,-0.006950422190129757,0.00481422059237957,-0.004015012644231319,-0.06578479707241058,-0.08498448133468628,0.03130057081580162 +1769682182,346972160,0.0,0.0,0.0,1.0,-0.00604492099955678,0.004348698537796736,-0.0041014645248651505,-0.0012822819408029318,0.002187692327424884,0.0702878013253212 +1769682182,378061568,0.0,0.0,0.0,1.0,-0.00585634121671319,0.00393233448266983,-0.004171410575509071,0.08518391102552414,-0.06390030682086945,0.04409964010119438 +1769682182,412907008,0.0,0.0,0.0,1.0,-0.005631681997328997,0.003507888177409768,-0.004219294060021639,0.07495740056037903,0.011428145691752434,0.03443387150764465 +1769682182,447930112,0.0,0.0,0.0,1.0,-0.005229269154369831,0.003088385798037052,-0.004235217347741127,0.07552767544984818,0.010487010702490807,0.003471449948847294 +1769682182,477929728,0.0,0.0,0.0,1.0,-0.005063674878329039,0.002842099405825138,-0.004197207745164633,0.010294487699866295,-0.07539819180965424,0.007255807053297758 +1769682182,511987456,0.0,0.0,0.0,1.0,-0.005956469569355249,0.0021287668496370316,-0.0041016219183802605,0.08638735115528107,-0.06579360365867615,-0.01905245892703533 +1769682182,562764288,0.0,0.0,0.0,1.0,-0.00702047860249877,0.0010372839169576764,-0.003915797919034958,0.021438274532556534,-0.1520816534757614,-0.028439387679100037 +1769682182,570880256,0.0,0.0,0.0,1.0,-0.007305367849767208,0.0006308761658146977,-0.0037941255141049623,0.06571804732084274,0.08510301262140274,-0.031118223443627357 +1769682182,611119104,0.0,0.0,0.0,1.0,-0.0031310953199863434,0.0026426345575600863,-0.0031470591202378273,-0.07644522190093994,-0.009083401411771774,0.045341674238443375 +1769682182,648583680,0.0,0.0,0.0,1.0,-0.0014410328585654497,0.004614310804754496,-0.0026561529375612736,-0.01104310154914856,0.07648930698633194,0.02973521314561367 +1769682182,680379904,0.0,0.0,0.0,1.0,-0.000813163467682898,0.0056550148874521255,-0.0024446379393339157,-0.096775121986866,0.141129270195961,0.01186250988394022 +1769682182,711170304,0.0,0.0,0.0,1.0,-0.0003399732813704759,0.006306705065071583,-0.00238225981593132,-0.09671790897846222,0.14101672172546387,0.008272719569504261 +1769682182,745210624,0.0,0.0,0.0,1.0,0.0001298926945310086,0.006752265617251396,-0.0024683258961886168,-0.17210642993450165,0.13023914396762848,-0.0024639989715069532 +1769682182,778194944,0.0,0.0,0.0,1.0,0.00041381572373211384,0.006796426139771938,-0.002639457816258073,-0.07555953413248062,-0.0104928994551301,-0.001195696066133678 +1769682182,813406976,0.0,0.0,0.0,1.0,0.0005685166106559336,0.006658308207988739,-0.002864172914996743,-0.09628024697303772,0.1402886062860489,-0.015621902421116829 +1769682182,849250304,0.0,0.0,0.0,1.0,0.0007206090958788991,0.00647440692409873,-0.003179736901074648,0.021100925281643867,-0.15131284296512604,-0.0034495654981583357 +1769682182,877591808,0.0,0.0,0.0,1.0,0.000911205483134836,0.006265922915190458,-0.0033547680359333754,0.07575172185897827,0.01023426279425621,-0.00828621257096529 +1769682182,910779136,0.0,0.0,0.0,1.0,0.0002234536368632689,0.0057220603339374065,-0.0035663016606122255,-0.14193987846374512,-0.09471090883016586,0.06307628750801086 +1769682182,958366720,0.0,0.0,0.0,1.0,-0.0016132195014506578,0.004126626532524824,-0.00391934160143137,0.009342290461063385,-0.0739106759428978,0.05725144222378731 +1769682182,978040320,0.0,0.0,0.0,1.0,-0.0023058983497321606,0.0032307414803653955,-0.003959484398365021,0.13979917764663696,0.09774068742990494,0.038236260414123535 +1769682183,11014912,0.0,0.0,0.0,1.0,-0.002940207486972213,0.0026799142360687256,-0.0039052043575793505,-0.12015403807163239,-0.2468828409910202,0.032150812447071075 +1769682183,44585472,0.0,0.0,0.0,1.0,-0.0037241133395582438,0.0023267243523150682,-0.0037883948534727097,-0.1513490378856659,-0.020780423656105995,0.009319236502051353 +1769682183,81070592,0.0,0.0,0.0,1.0,-0.004235519096255302,0.002290459116920829,-0.003750848351046443,0.1406160593032837,0.0966014564037323,-0.002200519433245063 +1769682183,111453440,0.0,0.0,0.0,1.0,-0.004790384788066149,0.00233808858320117,-0.0037909988313913345,0.16165253520011902,-0.054396502673625946,0.003843824379146099 +1769682183,146172928,0.0,0.0,0.0,1.0,-0.005887514445930719,0.003046529134735465,-0.004163210745900869,0.0122139323502779,-0.07775150239467621,-0.0750359445810318 +1769682183,178017280,0.0,0.0,0.0,1.0,-0.008364285342395306,0.004720669239759445,-0.004657129291445017,-0.4208557605743408,-0.2911358177661896,-0.0341951809823513 +1769682183,211712000,0.0,0.0,0.0,1.0,-0.009968558326363564,0.006391693372279406,-0.005117727909237146,-0.29088976979255676,-0.11888506263494492,-0.035193976014852524 +1769682183,252104448,0.0,0.0,0.0,1.0,-0.007767495233565569,0.0059040687046945095,-0.0053301015868783,-0.34667056798934937,0.26232102513313293,0.08403456956148148 +1769682183,278980608,0.0,0.0,0.0,1.0,-0.006340550258755684,0.004547544755041599,-0.005369139369577169,0.12786564230918884,0.1748262345790863,0.08865980058908463 +1769682183,311116544,0.0,0.0,0.0,1.0,-0.0054018497467041016,0.0033340686932206154,-0.0053880177438259125,0.13878165185451508,0.09888819605112076,0.07553107291460037 +1769682183,357858304,0.0,0.0,0.0,1.0,-0.00431695906445384,0.002157385228201747,-0.005330835003405809,-0.01174788549542427,0.07688244432210922,0.047735199332237244 +1769682183,377856000,0.0,0.0,0.0,1.0,-0.003593222238123417,0.0015664725797250867,-0.005201473366469145,-0.0005902435514144599,0.0007128643919713795,0.02621009759604931 +1769682183,411567872,0.0,0.0,0.0,1.0,-0.002944892505183816,0.0012105499627068639,-0.004987332504242659,-0.01094274315983057,0.07586796581745148,0.010818205773830414 +1769682183,446922752,0.0,0.0,0.0,1.0,-0.005185260437428951,-0.0006598361069336534,-0.00458071893081069,-0.13920728862285614,-0.09833411127328873,-0.052979495376348495 +1769682183,479557888,0.0,0.0,0.0,1.0,-0.005886925850063562,-0.0016303674783557653,-0.0042237224988639355,0.15206894278526306,0.02022077888250351,-0.04244174063205719 +1769682183,512032256,0.0,0.0,0.0,1.0,-0.0033972603268921375,-0.0002621131425257772,-0.003667488694190979,-0.4762422740459442,0.08873254805803299,0.06445827335119247 +1769682183,547097600,0.0,0.0,0.0,1.0,-0.0012046616757288575,0.0038520253729075193,-0.002928379690274596,-0.012412508949637413,0.07753011584281921,0.07400377839803696 +1769682183,578233600,0.0,0.0,0.0,1.0,-0.00047543770051561296,0.006217905320227146,-0.0025798147544264793,-0.011780058965086937,0.07676992565393448,0.04541059583425522 +1769682183,615292416,0.0,0.0,0.0,1.0,-2.414062328170985e-05,0.007822168990969658,-0.002401995239779353,-0.44337546825408936,-0.13887423276901245,0.03523634746670723 +1769682183,649936128,0.0,0.0,0.0,1.0,0.0003618259506765753,0.009022951126098633,-0.0023734949063509703,0.15036888420581818,0.022262675687670708,0.03154740482568741 +1769682183,677749504,0.0,0.0,0.0,1.0,0.0006612243596464396,0.009242872707545757,-0.002466561971232295,0.15075236558914185,0.021831979975104332,0.014909337274730206 +1769682183,712308480,0.0,0.0,0.0,1.0,0.0007364003686234355,0.009191918186843395,-0.002625751309096813,-0.1618049293756485,0.054039161652326584,-0.0029139439575374126 +1769682183,756403456,0.0,0.0,0.0,1.0,0.000915625540073961,0.008818906731903553,-0.0029102296102792025,-0.31243306398391724,0.0320330485701561,-0.022743243724107742 +1769682183,778220032,0.0,0.0,0.0,1.0,0.0009692883468233049,0.008502264507114887,-0.0031151901930570602,0.12997229397296906,0.17211812734603882,-0.0180908665060997 +1769682183,811082752,0.0,0.0,0.0,1.0,0.0010780716547742486,0.008175971917808056,-0.0032895973417907953,0.010885036550462246,-0.0756589025259018,-0.003680700436234474 +1769682183,844367872,0.0,0.0,0.0,1.0,-0.00015239507774822414,0.007069895509630442,-0.003685643896460533,-0.13020989298820496,-0.17186273634433746,0.028749510645866394 +1769682183,882293504,0.0,0.0,0.0,1.0,-0.0007208219612948596,0.006275065243244171,-0.0038200586568564177,-0.31344786286354065,0.03297097980976105,0.017445065081119537 +1769682183,911704320,0.0,0.0,0.0,1.0,-0.0010550286388024688,0.005708483513444662,-0.0038227008190006018,0.17202436923980713,-0.12882506847381592,0.028082264587283134 +1769682183,945933312,0.0,0.0,0.0,1.0,-0.0014065623981878161,0.005332753993570805,-0.0036675857845693827,-0.15131375193595886,-0.02133570797741413,0.008610520511865616 +1769682183,978624000,0.0,0.0,0.0,1.0,-0.0016924516530707479,0.005225545261055231,-0.0034576859325170517,0.15069738030433655,0.02198299765586853,0.015239899046719074 +1769682184,14724608,0.0,0.0,0.0,1.0,-0.001943667302839458,0.005267034284770489,-0.0032272383105009794,0.17255046963691711,-0.12927207350730896,0.009092938154935837 +1769682184,50726912,0.0,0.0,0.0,1.0,-0.0022325932513922453,0.005395027343183756,-0.0029508720617741346,0.010860658250749111,-0.07555456459522247,-0.00011197877756785601 +1769682184,78807040,0.0,0.0,0.0,1.0,-0.004459402058273554,0.006813358515501022,-0.0031977647449821234,0.17490176856517792,-0.131548210978508,-0.07901650667190552 +1769682184,111357696,0.0,0.0,0.0,1.0,-0.005192469339817762,0.007810321170836687,-0.003423101268708706,0.0022204318083822727,-0.0021737865172326565,-0.08338868618011475 +1769682184,159827200,0.0,0.0,0.0,1.0,-0.004776004236191511,0.008035171777009964,-0.0035110902972519398,-0.022414498031139374,0.15171757340431213,0.024104153737425804 +1769682184,167794688,0.0,0.0,0.0,1.0,-0.002594619058072567,0.005554221570491791,-0.003390805795788765,-0.17693211138248444,0.13330329954624176,0.15042957663536072 +1769682184,212857600,0.0,0.0,0.0,1.0,-0.0008187074563466012,0.001464197994209826,-0.003223160747438669,0.006979743950068951,-0.07184035331010818,0.14399665594100952 +1769682184,244878336,0.0,0.0,0.0,1.0,0.00032862284570001066,-0.0013606990687549114,-0.0031425629276782274,0.13705790042877197,0.10019487142562866,0.11447838693857193 +1769682184,286494464,0.0,0.0,0.0,1.0,0.0010510432766750455,-0.0026641455478966236,-0.003083288436755538,-0.013179858215153217,0.0776926800608635,0.0835334062576294 +1769682184,327664896,0.0,0.0,0.0,1.0,0.001784670283086598,-0.003382953582331538,-0.002970445901155472,-0.18471784889698029,0.20573106408119202,0.03264705091714859 +1769682184,349917952,0.0,0.0,0.0,1.0,0.00030193623388186097,-0.004791888874024153,-0.0026923236437141895,0.16290141642093658,-0.0546545535326004,-0.03357737138867378 +1769682184,378195456,0.0,0.0,0.0,1.0,-0.0006101603503338993,-0.0057999733835458755,-0.0024279814679175615,0.012020496651530266,-0.07658886164426804,-0.040646735578775406 +1769682184,413976320,0.0,0.0,0.0,1.0,-0.001277644420042634,-0.006309026386588812,-0.0021310653537511826,-0.28980377316474915,-0.12043912708759308,-0.05229801684617996 +1769682184,454022144,0.0,0.0,0.0,1.0,0.00027709297137334943,-0.0031416907440871,-0.0015634767478331923,-0.4648730754852295,0.010898318141698837,0.028029225766658783 +1769682184,478759936,0.0,0.0,0.0,1.0,0.0004150093882344663,-0.0007891713757999241,-0.001240528654307127,-0.16255129873752594,0.054274290800094604,0.02056843973696232 +1769682184,512066048,0.0,0.0,0.0,1.0,0.00039832768379710615,0.0010416670702397823,-0.0010333112441003323,-0.29130232334136963,-0.11900661885738373,0.004947696812450886 +1769682184,555194880,0.0,0.0,0.0,1.0,0.00043054501293227077,0.002556165447458625,-0.000888905837200582,-0.46405795216560364,0.010048472322523594,-0.002967705950140953 +1769682184,578429184,0.0,0.0,0.0,1.0,0.000350409623933956,0.003105703042820096,-0.0008779558120295405,-0.312583327293396,0.031440142542123795,-0.01863584853708744 +1769682184,610994688,0.0,0.0,0.0,1.0,0.00025262130657210946,0.0033391104079782963,-0.0009357804083265364,-0.17263838648796082,0.12893331050872803,-0.012693247757852077 +1769682184,647163392,0.0,0.0,0.0,1.0,0.00018620197079144418,0.0032406512182205915,-0.0010861626360565424,0.14025750756263733,0.09719978272914886,-0.005921425297856331 +1769682184,680471296,0.0,0.0,0.0,1.0,0.000266209157416597,0.0030162641778588295,-0.0012138637248426676,0.12922348082065582,0.17280538380146027,-0.0033874623477458954 +1769682184,711142400,0.0,0.0,0.0,1.0,0.0002709034306462854,0.0027613453567028046,-0.0013228515163064003,0.00012819832772947848,-0.00012320790847297758,-0.0047650584019720554 +1769682184,750648320,0.0,0.0,0.0,1.0,0.0008083308930508792,0.002639816841110587,-0.0013051169225946069,-0.02104763686656952,0.15021318197250366,-0.03308536484837532 +1769682184,778555392,0.0,0.0,0.0,1.0,0.0016952925361692905,0.0029178906697779894,-0.0011465915013104677,-0.13921086490154266,-0.09821023792028427,-0.03224301338195801 +1769682184,810897920,0.0,0.0,0.0,1.0,0.0022549391724169254,0.003114636056125164,-0.0009551113471388817,0.30263569951057434,0.04319196194410324,-0.01913844794034958 +1769682184,845110784,0.0,0.0,0.0,1.0,0.0027204633224755526,0.0033629536628723145,-0.0006642460357397795,0.011242074891924858,-0.07578559964895248,-0.009645743295550346 +1769682184,878930688,0.0,0.0,0.0,1.0,0.00297286594286561,0.003447770606726408,-0.0004446402017492801,-0.15069837868213654,-0.02219347096979618,-0.013095758855342865 +1769682184,911782144,0.0,0.0,0.0,1.0,0.003103413386270404,0.0034701682161539793,-0.0002498906687833369,-0.12905751168727875,-0.1729568988084793,-0.0013973963214084506 +1769682184,950171904,0.0,0.0,0.0,1.0,0.003093710634857416,0.003500770078971982,-3.825207386398688e-05,0.13984274864196777,0.09760942310094833,0.00845219288021326 +1769682184,980032512,0.0,0.0,0.0,1.0,0.0019378387369215488,0.004070088267326355,-8.581690781284124e-05,0.035136111080646515,-0.22869080305099487,-0.07886603474617004 +1769682185,10799872,0.0,0.0,0.0,1.0,0.0001293806853936985,0.005473950412124395,-0.0004544564289972186,-0.13804273307323456,-0.09931507706642151,-0.07280456274747849 +1769682185,64437504,0.0,0.0,0.0,1.0,0.00045073829824104905,0.0056985062547028065,-0.0008114277152344584,0.013133598491549492,-0.0775565430521965,-0.07631200551986694 +1769682185,71960064,0.0,0.0,0.0,1.0,0.0013319369172677398,0.0049737985245883465,-0.0008930564508773386,0.2897099554538727,0.12058493494987488,0.05032525211572647 +1769682185,115186688,0.0,0.0,0.0,1.0,0.0022236460354179144,0.0013499140040948987,-0.0008873086771927774,0.2987985610961914,0.046837396919727325,0.11698785424232483 +1769682185,144814848,0.0,0.0,0.0,1.0,0.0028074716683477163,-0.0013918253825977445,-0.0008410544833168387,0.008561499416828156,-0.07324588298797607,0.08570826798677444 +1769682185,178042880,0.0,0.0,0.0,1.0,0.003079516813158989,-0.0027246475219726562,-0.000766515382565558,0.2887542247772217,0.12151901423931122,0.08365140110254288 +1769682185,212009728,0.0,0.0,0.0,1.0,0.003372559556737542,-0.003580052638426423,-0.0006659523351117969,-0.023269742727279663,0.1522865742444992,0.04535653814673424 +1769682185,249141504,0.0,0.0,0.0,1.0,0.0023390850983560085,-0.004645941779017448,-0.00046855639084242284,-0.1286221146583557,-0.17336934804916382,-0.015625223517417908 +1769682185,279004416,0.0,0.0,0.0,1.0,0.001199680264107883,-0.005632334854453802,-0.0003150894190184772,-0.1395556926727295,-0.09790132939815521,-0.01794276013970375 +1769682185,310983936,0.0,0.0,0.0,1.0,0.0004320814332459122,-0.00623695645481348,-0.00017144459707196802,0.1627451628446579,-0.05432701110839844,-0.025042090564966202 +1769682185,350478336,0.0,0.0,0.0,1.0,0.00029727720539085567,-0.006108992733061314,0.0001046504476107657,-0.139693483710289,-0.09777381271123886,-0.013114603236317635 +1769682185,379672064,0.0,0.0,0.0,1.0,0.00034285092260688543,-0.00551921222358942,0.0003984282957389951,0.17308388650417328,-0.1292182207107544,-0.0013258091639727354 +1769682185,411182336,0.0,0.0,0.0,1.0,0.00028032163390889764,-0.004968433640897274,0.0007269311463460326,-0.14002330601215363,-0.09744749963283539,-0.0011549661867320538 +1769682185,455595776,0.0,0.0,0.0,1.0,0.00017413095338270068,-0.00432054977864027,0.0011934987269341946,0.15127874910831451,0.021648269146680832,-0.008443884551525116 +1769682185,478672640,0.0,0.0,0.0,1.0,0.00014668551739305258,-0.0039448244497179985,0.001511473092250526,-0.14003172516822815,-0.09743588417768478,-0.0011110615450888872 +1769682185,511415808,0.0,0.0,0.0,1.0,-3.6654055293183774e-05,-0.003718241583555937,0.0017603758024051785,0.16188505291938782,-0.05351453274488449,0.005770289339125156 +1769682185,546429440,0.0,0.0,0.0,1.0,-0.0002668657689355314,-0.0035736465360969305,0.001905490760691464,-0.3020525276660919,-0.04376253858208656,-0.0020570112392306328 +1769682185,582432256,0.0,0.0,0.0,1.0,-0.0004779541050083935,-0.003520710626617074,0.0018879681592807174,0.17279422283172607,-0.12900911271572113,0.008061856031417847 +1769682185,612080896,0.0,0.0,0.0,1.0,-0.0005199588485993445,-0.0035498610232025385,0.0018066754564642906,-0.011036291718482971,0.07560282200574875,0.002434143330901861 +1769682185,646096896,0.0,0.0,0.0,1.0,-0.0004968306748196483,-0.0036526808980852365,0.0016888167010620236,0.010843628086149693,-0.0754101425409317,0.0047101653181016445 +1769682185,678163456,0.0,0.0,0.0,1.0,0.0007845675572752953,-0.00319404574111104,0.0018171812407672405,-0.16062982380390167,0.0522751621901989,-0.053319547325372696 +1769682185,711651072,0.0,0.0,0.0,1.0,0.0019258095417171717,-0.0024666949175298214,0.002031161682680249,0.4540901482105255,0.06447778642177582,-0.03527986630797386 +1769682185,750999040,0.0,0.0,0.0,1.0,0.0029396137688308954,-0.0017652472015470266,0.0023199869319796562,0.0008023168775252998,-0.0008430004818364978,-0.03097257763147354 +1769682185,779922944,0.0,0.0,0.0,1.0,0.0035337810404598713,-0.0014717660378664732,0.0025407124776393175,0.0007391974795609713,-0.0007810805691406131,-0.02859002910554409 +1769682185,811439616,0.0,0.0,0.0,1.0,0.0039311358705163,-0.0013128208229318261,0.0027615635190159082,0.15116164088249207,0.021669942885637283,-0.0038503119722008705 +1769682185,855815424,0.0,0.0,0.0,1.0,0.004230204503983259,-0.001296886010095477,0.003027057508006692,-0.010871347971260548,0.07547847926616669,-0.0023636738769710064 +1769682185,878994944,0.0,0.0,0.0,1.0,0.00448996014893055,-0.0013745370088145137,0.003198821796104312,-0.1510433405637741,-0.021768998354673386,-0.0008943468565121293 +1769682185,912609792,0.0,0.0,0.0,1.0,0.0025002218317240477,-0.0001598841045051813,0.0029830974526703358,0.023367850109934807,-0.15275053679943085,-0.05956679582595825 +1769682185,945880064,0.0,0.0,0.0,1.0,0.0016640729736536741,0.0007797982543706894,0.002774721011519432,0.17415449023246765,-0.13075345754623413,-0.049133703112602234 +1769682185,982674176,0.0,0.0,0.0,1.0,0.0013677319511771202,0.0009740724926814437,0.0026940875686705112,-0.009922710247337818,0.07448261231184006,-0.03812653198838234 +1769682186,11603200,0.0,0.0,0.0,1.0,0.0014641163870692253,0.0005137366824783385,0.002653977135196328,-0.12931691110134125,-0.17274565994739532,0.0015067453496158123 +1769682186,51321088,0.0,0.0,0.0,1.0,0.0012563776690512896,-4.6807064791209996e-05,0.0026160439010709524,0.010521660558879375,-0.0751492902636528,0.014309505000710487 +1769682186,77724160,0.0,0.0,0.0,1.0,0.0012018663110211492,-0.0004711732908617705,0.0025798871647566557,0.15056446194648743,0.022221848368644714,0.019953977316617966 +1769682186,114795776,0.0,0.0,0.0,1.0,0.0010482108918949962,-0.0007914404268376529,0.002540785353630781,0.010387917049229145,-0.07501585781574249,0.019079282879829407 +1769682186,148741888,0.0,0.0,0.0,1.0,0.000667074229568243,-0.0012188294203951955,0.00252342876046896,0.02149650827050209,-0.15083789825439453,0.009574074298143387 +1769682186,178274816,0.0,0.0,0.0,1.0,-2.5434288545511663e-05,-0.0019461213378235698,0.00254729762673378,-0.1399516761302948,-0.09747063368558884,-0.010383588261902332 +1769682186,211140352,0.0,0.0,0.0,1.0,-0.0004984595580026507,-0.0024358376394957304,0.00257872068323195,0.010919974185526371,-0.07562199980020523,-0.0023621038999408484 +1769682186,263136000,0.0,0.0,0.0,1.0,-0.0005034119822084904,-0.002741999924182892,0.002713786670938134,0.15082243084907532,0.021888643503189087,0.010379675775766373 +1769682186,273630720,0.0,0.0,0.0,1.0,-0.000332717812852934,-0.0025211870670318604,0.002828374970704317,-0.00018151174299418926,0.0002011886826949194,0.007147427648305893 +1769682186,312374272,0.0,0.0,0.0,1.0,-0.00024461813154630363,-0.0019356890115886927,0.003079719375818968,-0.1513100117444992,-0.021325647830963135,0.008700558915734291 +1769682186,346065664,0.0,0.0,0.0,1.0,-0.00022009357053320855,-0.0014791953144595027,0.0033152890391647816,-0.3130315840244293,0.0324777327477932,0.0007298020645976067 +1769682186,379869440,0.0,0.0,0.0,1.0,-0.0001404077047482133,-0.001244989107362926,0.003473760327324271,0.010820308700203896,-0.07556043565273285,1.2385964510031044e-05 +1769682186,411340032,0.0,0.0,0.0,1.0,-0.0002484980795998126,-0.001097654108889401,0.0035922310780733824,0.30209261178970337,0.04315239563584328,0.004000292159616947 +1769682186,447377152,0.0,0.0,0.0,1.0,-0.00020267553918529302,-0.0010099249193444848,0.0037211121525615454,0.021542461588978767,-0.1510593444108963,0.0024032900109887123 +1769682186,478476288,0.0,0.0,0.0,1.0,-0.00017206513439305127,-0.001020770170725882,0.0037934514693915844,0.02158518135547638,-0.15112878382205963,1.937340130098164e-05 +1769682186,512043520,0.0,0.0,0.0,1.0,-0.0001716319820843637,-0.001051929546520114,0.0038580200634896755,0.010783891193568707,-0.0755656436085701,8.992195944301784e-06 +1769682186,550672640,0.0,0.0,0.0,1.0,-9.629621490603313e-05,-0.0011051557958126068,0.003908125218003988,-0.010653025470674038,0.07543334364891052,-0.004773076623678207 +1769682186,595102464,0.0,0.0,0.0,1.0,-6.337212107609957e-05,-0.0011852554744109511,0.003927500452846289,0.3235882520675659,-0.1081138402223587,0.006344199180603027 +1769682186,600774400,0.0,0.0,0.0,1.0,0.0001813458657125011,-0.0011031932663172483,0.003967210650444031,-0.010163242928683758,0.07489953190088272,-0.02383221872150898 +1769682186,649190400,0.0,0.0,0.0,1.0,0.0009140431648120284,-0.0005830927984789014,0.004107284359633923,-0.16130468249320984,0.053565770387649536,-0.02222413383424282 +1769682186,680381184,0.0,0.0,0.0,1.0,0.001177242142148316,-0.0003802192222792655,0.004154627211391926,0.17274199426174164,-0.12996402382850647,-0.0063547613099217415 +1769682186,710953216,0.0,0.0,0.0,1.0,0.0014104304136708379,-0.0002650090027600527,0.004198825918138027,-0.15080565214157104,-0.021700773388147354,-0.012679838575422764 +1769682186,746274560,0.0,0.0,0.0,1.0,0.0016524423845112324,-0.0002087415923597291,0.004282156005501747,0.15110543370246887,0.021338798105716705,0.0007646456360816956 +1769682186,778422272,0.0,0.0,0.0,1.0,0.0018107837531715631,-0.00020143685105722398,0.004375359043478966,0.30186137557029724,0.043043673038482666,0.015820102766156197 +1769682186,814015744,0.0,0.0,0.0,1.0,0.0014335684245452285,0.0001087150230887346,0.004345462191849947,0.022090818732976913,-0.15197010338306427,-0.028536096215248108 +1769682186,846355712,0.0,0.0,0.0,1.0,0.000460596609627828,0.0008461877005174756,0.004241136834025383,-0.1397266834974289,-0.09766754508018494,-0.02932444028556347 +1769682186,878167296,0.0,0.0,0.0,1.0,0.00030595928546972573,0.0010821610921993852,0.0041577173396945,-0.16107407212257385,0.05351388454437256,-0.029389282688498497 +1769682186,911330560,0.0,0.0,0.0,1.0,0.00024354123161174357,0.0010648096213117242,0.004099028185009956,0.14046119153499603,0.09681927412748337,0.0007423481438308954 +1769682186,949843456,0.0,0.0,0.0,1.0,0.00025049224495887756,0.0003242763632442802,0.00404608016833663,0.31223973631858826,-0.03241601213812828,0.02779393643140793 +1769682186,978990848,0.0,0.0,0.0,1.0,0.00021099133300594985,-7.982878014445305e-05,0.004012509249150753,0.1291981041431427,0.1731126308441162,0.026918426156044006 +1769682187,11431936,0.0,0.0,0.0,1.0,0.000236133360886015,-0.00041585470899008214,0.003983588423579931,-0.3028503358364105,-0.04167090356349945,0.022274039685726166 +1769682187,45978368,0.0,0.0,0.0,1.0,0.00030159071320667863,-0.0007843670318834484,0.003937614616006613,-0.00011855229968205094,0.0001358778972644359,0.004764963872730732 +1769682187,78776832,0.0,0.0,0.0,1.0,-0.0004400131874717772,-0.001224498264491558,0.003913856577128172,0.010844138450920582,-0.07586236298084259,-0.009496788494288921 +1769682187,111397888,0.0,0.0,0.0,1.0,-0.0010264203883707523,-0.001728940405882895,0.003867845982313156,-0.010421332903206348,0.07538820058107376,-0.007178178057074547 +1769682187,145334784,0.0,0.0,0.0,1.0,-0.0012733644107356668,-0.0021444791927933693,0.0038282466121017933,0.3023390769958496,0.042117003351449966,-0.0008848896250128746 +1769682187,179147520,0.0,0.0,0.0,1.0,-0.00034806234179995954,-0.0017716471338644624,0.00388111243955791,-0.16224929690361023,0.05512934923171997,0.020678460597991943 +1769682187,211876608,0.0,0.0,0.0,1.0,-0.0004873014986515045,-0.0005086290766485035,0.003932655788958073,-0.010921233333647251,0.07600213587284088,0.014272653497755527 +1769682187,247332864,0.0,0.0,0.0,1.0,-0.00027062027947977185,0.000820061017293483,0.004033912904560566,-0.15150047838687897,-0.020626945421099663,0.013556075282394886 +1769682187,278175744,0.0,0.0,0.0,1.0,-0.00018309359438717365,0.001456083613447845,0.0041353232227265835,0.15056341886520386,0.021691076457500458,0.024569910019636154 +1769682187,311123200,0.0,0.0,0.0,1.0,-2.5859691959340125e-05,0.0018821504199877381,0.004234627354890108,-0.17217159271240234,0.13013750314712524,-0.003179040504619479 +1769682187,348065792,0.0,0.0,0.0,1.0,1.0861956980079412e-05,0.002093595452606678,0.004339130595326424,-0.00011811262083938345,0.0001353569678030908,0.004764989484101534 +1769682187,378236416,0.0,0.0,0.0,1.0,-2.691574627533555e-05,0.002109964145347476,0.004361398052424192,-0.14070351421833038,-0.09648531675338745,0.0016308326739817858 +1769682187,412659712,0.0,0.0,0.0,1.0,-0.00010133533214684576,0.0020466367714107037,0.004344196990132332,-0.14053738117218018,-0.09667591005563736,-0.005525355227291584 +1769682187,457763072,0.0,0.0,0.0,1.0,-0.00015800399705767632,0.0018551863031461835,0.004281759262084961,0.14097099006175995,0.09617196023464203,-0.011140618473291397 +1769682187,478818560,0.0,0.0,0.0,1.0,-8.515903755323961e-05,0.0017272176919505,0.0042122965678572655,0.333667129278183,-0.18491940200328827,0.006446538958698511 +1769682187,511754240,0.0,0.0,0.0,1.0,-0.00014608771016355604,0.0016062805661931634,0.004141063429415226,5.973563384031877e-05,-6.768169987481087e-05,-0.002382477978244424 +1769682187,545292544,0.0,0.0,0.0,1.0,8.688194793649018e-05,0.0016728887567296624,0.004078955389559269,0.010580937378108501,-0.07574637234210968,-0.004739671479910612 +1769682187,579043072,0.0,0.0,0.0,1.0,0.0003561774792615324,0.001809396781027317,0.004047691822052002,-0.010211983695626259,0.07534139603376389,-0.009556307457387447 +1769682187,612193792,0.0,0.0,0.0,1.0,0.0003944534691981971,0.0019229432800784707,0.004031546879559755,0.16162239015102386,-0.05480930209159851,0.0008655756246298552 +1769682187,649303552,0.0,0.0,0.0,1.0,0.0006851960206404328,0.0020363954827189445,0.004101330880075693,-0.2918749451637268,-0.11724232137203217,-0.004050170071423054 +1769682187,678301952,0.0,0.0,0.0,1.0,0.0008931756019592285,0.002101543825119734,0.004223336465656757,-0.14082485437393188,-0.0963093489408493,0.0015573492273688316 +1769682187,711814144,0.0,0.0,0.0,1.0,0.000914997945073992,0.002197733148932457,0.004360667429864407,-6.058796134311706e-05,6.795654917368665e-05,0.00238244840875268 +1769682187,748490240,0.0,0.0,0.0,1.0,0.0001137163199018687,0.0028218745719641447,0.00434616394340992,0.13106442987918854,0.17120611667633057,-0.025400983169674873 +1769682187,778409984,0.0,0.0,0.0,1.0,-0.00048474103095941246,0.0032768698874861,0.0043267542496323586,0.2924273908138275,0.11653543263673782,-0.014922097325325012 +1769682187,811956224,0.0,0.0,0.0,1.0,-0.00047310261288657784,0.0033900532871484756,0.004297169391065836,-0.14014437794685364,-0.09704580157995224,-0.02708069235086441 +1769682187,848953600,0.0,0.0,0.0,1.0,0.0002453564666211605,0.002394620329141617,0.004338324535638094,0.019069315865635872,-0.149412602186203,0.06440537422895432 +1769682187,878656512,0.0,0.0,0.0,1.0,0.00011796712351497263,0.001100094523280859,0.004308372735977173,0.2802770137786865,0.1940750777721405,0.05658778175711632 +1769682187,911353856,0.0,0.0,0.0,1.0,7.632288179593161e-05,0.00011132210784126073,0.004240420181304216,0.18076352775096893,-0.20463736355304718,0.05824003741145134 +1769682187,946092800,0.0,0.0,0.0,1.0,0.0001863854704424739,-0.0007799710729159415,0.0041249413043260574,0.16049513220787048,-0.05388636887073517,0.04147794097661972 +1769682187,969774848,0.0,0.0,0.0,1.0,0.00021190552797634155,-0.0010189207969233394,0.0040625762194395065,-0.0005538943223655224,0.0006125649670138955,0.021441787481307983 +1769682188,12771840,0.0,0.0,0.0,1.0,-0.0010541274677962065,-0.0019398482982069254,0.00397489033639431,0.031313374638557434,-0.22730140388011932,-0.014175409451127052 +1769682188,45420288,0.0,0.0,0.0,1.0,-0.0019937604665756226,-0.0027630103286355734,0.003880060277879238,0.0006114179850555956,-0.0006788612809032202,-0.02382473647594452 +1769682188,78422016,0.0,0.0,0.0,1.0,-0.0024691526778042316,-0.0030472837388515472,0.0038074448239058256,0.1621234267950058,-0.05580354109406471,-0.02289925515651703 +1769682188,112635904,0.0,0.0,0.0,1.0,-0.0012478240532800555,-0.002314138924703002,0.003871307009831071,0.16114357113838196,-0.05473925173282623,0.015204830095171928 +1769682188,145570816,0.0,0.0,0.0,1.0,-0.0008480299147777259,-0.0011740241898223758,0.00399703299626708,0.010031553916633129,-0.07536652684211731,0.009549194946885109 +1769682188,178821376,0.0,0.0,0.0,1.0,-0.0005155939725227654,-0.0004362268664408475,0.004155060276389122,-0.15128852427005768,-0.020380083471536636,0.0015069656074047089 +1769682188,213282816,0.0,0.0,0.0,1.0,-0.0001732774544507265,3.7640165828634053e-05,0.004344519227743149,-0.1614854335784912,0.055211104452610016,-0.0008923497516661882 +1769682188,261636352,0.0,0.0,0.0,1.0,-5.200679152039811e-05,0.0004271690850146115,0.0046000853180885315,-0.010301666334271431,0.07570859044790268,0.0023655034601688385 +1769682188,270596864,0.0,0.0,0.0,1.0,2.146129554603249e-05,0.0005638924776576459,0.004706148989498615,0.010294604115188122,-0.07570955902338028,-0.0023654336109757423 +1769682188,311745280,0.0,0.0,0.0,1.0,8.993774827104062e-06,0.0005779579514637589,0.004857469350099564,0.15117953717708588,0.020425140857696533,0.0032647131010890007 +1769682188,352008704,0.0,0.0,0.0,1.0,1.3183504051994532e-05,0.0005529058980755508,0.004938286729156971,6.060964005882852e-05,-6.751748151145875e-05,-0.00238246051594615 +1769682188,373915648,0.0,0.0,0.0,1.0,-4.1288854845333844e-05,0.0005018365918658674,0.004940494894981384,0.1409882754087448,0.09602753818035126,0.003252242226153612 +1769682188,412870144,0.0,0.0,0.0,1.0,-0.00011287709639873356,0.00038465778925456107,0.0049159643240273,-0.01000030618160963,0.0754464864730835,-0.007164696231484413 +1769682188,447109120,0.0,0.0,0.0,1.0,-0.0001804815256036818,0.0003427108458708972,0.0048502665013074875,0.00012135178985772654,-0.00013503505033440888,-0.004764917306602001 +1769682188,478397952,0.0,0.0,0.0,1.0,0.00013948645209893584,0.00044945665285922587,0.004826754331588745,-0.1507713496685028,-0.020771969109773636,-0.019953716546297073 +1769682188,511364352,0.0,0.0,0.0,1.0,0.000357979501131922,0.0005927394959144294,0.004797069821506739,-0.02023056522011757,0.15124037861824036,-0.0024185744114220142 +1769682188,551355904,0.0,0.0,0.0,1.0,0.0004968398716300726,0.0007603769772686064,0.0047480822540819645,-6.0778125771321356e-05,6.761577969882637e-05,0.00238245353102684 +1769682188,579677952,0.0,0.0,0.0,1.0,0.0005923358839936554,0.0008425572887063026,0.004713045433163643,-0.2821703553199768,-0.19176937639713287,-0.006529383827000856 +1769682188,615031552,0.0,0.0,0.0,1.0,0.0007059078197926283,0.000844764756038785,0.004692947492003441,-0.1412203460931778,-0.09572941064834595,0.0014986651949584484 +1769682188,650803456,0.0,0.0,0.0,1.0,0.00040418520802631974,0.00112243986222893,0.004615945275872946,-0.16027167439460754,0.054330144077539444,-0.043821174651384354 +1769682188,678814464,0.0,0.0,0.0,1.0,-0.000701473152730614,0.0021385818254202604,0.004440908320248127,0.04131907597184181,-0.30373260378837585,-0.03801799193024635 +1769682188,712560128,0.0,0.0,0.0,1.0,-0.0012172608403488994,0.0028823153115808964,0.004353038035333157,0.16227255761623383,-0.056609272956848145,-0.03478005900979042 +1769682188,758314496,0.0,0.0,0.0,1.0,-0.001305907964706421,0.0032376088201999664,0.004330418072640896,-0.17103727161884308,0.13088102638721466,-0.015289082191884518 +1769682188,778153984,0.0,0.0,0.0,1.0,-0.0006846472970210016,0.0024900324642658234,0.004378082230687141,0.15054340660572052,0.020834237337112427,0.02955540083348751 +1769682188,811433472,0.0,0.0,0.0,1.0,-0.0006021794979460537,0.0018013641238212585,0.004347349517047405,0.17025841772556305,-0.13011644780635834,0.04389701038599014 +1769682188,846280448,0.0,0.0,0.0,1.0,-0.0006618669722229242,0.0010614660568535328,0.004187512211501598,0.16045212745666504,-0.05474699288606644,0.034355420619249344 +1769682188,882013184,0.0,0.0,0.0,1.0,-0.0005841453676111996,0.0006841428694315255,0.004017591010779142,0.15054816007614136,0.020768597722053528,0.029577404260635376 +1769682188,911660032,0.0,0.0,0.0,1.0,-0.0004919945495203137,0.0003443141176830977,0.003836133750155568,0.01934073492884636,-0.15060241520404816,0.02623693272471428 +1769682188,946583552,0.0,0.0,0.0,1.0,-0.0023183126468211412,-0.0010611191391944885,0.0036850625183433294,0.31315386295318604,-0.03644014522433281,-0.019454043358564377 +1769682188,979260928,0.0,0.0,0.0,1.0,-0.003106995252892375,-0.0019146361155435443,0.0035857846960425377,0.16197268664836884,-0.05650917813181877,-0.02522071823477745 +1769682189,15362304,0.0,0.0,0.0,1.0,-0.0031589181162416935,-0.0023337900638580322,0.003547870321199298,0.29268208146095276,0.1153816357254982,-0.00042788591235876083 +1769682189,47866368,0.0,0.0,0.0,1.0,-0.0018214249284937978,-0.0020769317634403706,0.003684221999719739,0.2926987409591675,0.11533928662538528,-0.0004421505145728588 +1769682189,78713088,0.0,0.0,0.0,1.0,-0.0012103035114705563,-0.0019013907294720411,0.003840565448626876,-0.15100079774856567,-0.020179780200123787,-0.012867806479334831 +1769682189,128368384,0.0,0.0,0.0,1.0,-0.0007470683776773512,-0.0017748859245330095,0.0040262662805616856,0.31263649463653564,-0.03608723729848862,-0.0005062571726739407 +1769682189,164241664,0.0,0.0,0.0,1.0,-0.00033095802064053714,-0.001532157650217414,0.0043108584359288216,0.17077161371707916,-0.1310930848121643,0.01757275126874447 +1769682189,172947712,0.0,0.0,0.0,1.0,-9.071662498172373e-05,-0.0013533525634557009,0.004469086416065693,0.4735125005245209,-0.09166030585765839,0.01467068213969469 +1769682189,211900160,0.0,0.0,0.0,1.0,0.00017108296742662787,-0.0011695546563714743,0.004796348977833986,0.1511971354484558,0.019894953817129135,0.0056915306486189365 +1769682189,249548288,0.0,0.0,0.0,1.0,0.00018374498176854104,-0.0010224509751424193,0.005032418295741081,0.15132276713848114,0.01973210833966732,0.0009198387851938605 +1769682189,278759168,0.0,0.0,0.0,1.0,0.00011446404096204787,-0.0009589367546141148,0.00508419144898653,-0.009895389899611473,0.07568711042404175,2.1887230104766786e-05 +1769682189,314056704,0.0,0.0,0.0,1.0,-2.125085302395746e-05,-0.0010063465451821685,0.0050608194433152676,0.00012110588431823999,-0.00013299980491865426,-0.004764981102198362 +1769682189,351264256,0.0,0.0,0.0,1.0,-0.00025775551330298185,-0.0010676352540031075,0.00487794354557991,0.29279667139053345,0.1150025874376297,0.0018322481773793697 +1769682189,378772736,0.0,0.0,0.0,1.0,-0.0002497760870028287,-0.0010426973458379507,0.004662760067731142,0.16137473285198212,-0.05625695735216141,-0.006271445658057928 +1769682189,414870528,0.0,0.0,0.0,1.0,-0.0002675468858797103,-0.0009981421753764153,0.004417282063513994,0.14173150062561035,0.0950414389371872,-0.008609794080257416 +1769682189,450635520,0.0,0.0,0.0,1.0,-0.0001896619505714625,-0.0009085565689019859,0.004062993917614222,0.17119240760803223,-0.13200068473815918,-0.006309111602604389 +1769682189,479181056,0.0,0.0,0.0,1.0,-5.437678919406608e-05,-0.0008753169095143676,0.0038276626728475094,0.3128145933151245,-0.036886632442474365,-0.010166849941015244 +1769682189,512443904,0.0,0.0,0.0,1.0,0.0001401766639901325,-0.0008737770840525627,0.0036382321268320084,0.1513460874557495,0.0195541400462389,0.000881821964867413 +1769682189,558027008,0.0,0.0,0.0,1.0,0.00036662674392573535,-0.0008523893775418401,0.0035202677827328444,0.17102311551570892,-0.13193105161190033,-0.0015573063865303993 +1769682189,578625792,0.0,0.0,0.0,1.0,0.0006983387283980846,-0.000882812135387212,0.0035776831209659576,0.1512911468744278,0.01958310976624489,0.003254591953009367 +1769682189,611581952,0.0,0.0,0.0,1.0,-0.000672589463647455,-5.308130494086072e-05,0.0033837887458503246,0.33321666717529297,-0.18936504423618317,-0.04360111430287361 +1769682189,646156544,0.0,0.0,0.0,1.0,-0.002133101923391223,0.0013507070252671838,0.003263290273025632,0.3039092421531677,0.03763318061828613,-0.04589694365859032 +1769682189,685717760,0.0,0.0,0.0,1.0,-0.002988931955769658,0.0021273810416460037,0.0032431993167847395,0.4549126923084259,0.05747097730636597,-0.030694629997015 +1769682189,712314624,0.0,0.0,0.0,1.0,-0.002512563019990921,0.0019772248342633247,0.003284007078036666,0.4730692207813263,-0.09245961904525757,0.024054918438196182 +1769682189,745963264,0.0,0.0,0.0,1.0,-0.0018958128057420254,0.0019166967831552029,0.003271052148193121,0.161118283867836,-0.0562739335000515,0.0008652908727526665 +1769682189,780475648,0.0,0.0,0.0,1.0,-0.0018372408812865615,0.0019559680949896574,0.0031634375918656588,0.31211352348327637,-0.036478400230407715,0.016087330877780914 +1769682189,812425728,0.0,0.0,0.0,1.0,-0.001744579174555838,0.001895525841973722,0.0029749993700534105,0.3026093542575836,0.03893670439720154,0.006626085378229618 +1769682189,851633408,0.0,0.0,0.0,1.0,-0.0015619004843756557,0.0016989109572023153,0.0026617376133799553,0.4634106159210205,-0.01709221489727497,0.019448168575763702 +1769682189,879987968,0.0,0.0,0.0,1.0,-0.0016752011142671108,0.001434995443560183,0.002465334953740239,0.17094703018665314,-0.13217388093471527,-0.003934761509299278 +1769682189,911592448,0.0,0.0,0.0,1.0,-0.003319271607324481,0.000170413579326123,0.0023181429132819176,0.4646861255168915,-0.01853114925324917,-0.03055701032280922 +1769682189,964670720,0.0,0.0,0.0,1.0,-0.004149359650909901,-0.0010641328990459442,0.0021927959751337767,0.47354790568351746,-0.09337081015110016,0.002705057617276907 +1769682189,972282368,0.0,0.0,0.0,1.0,-0.003610385349020362,-0.0010788504732772708,0.002213261555880308,0.4539358913898468,0.058223433792591095,0.010004397481679916 +1769682190,11847424,0.0,0.0,0.0,1.0,-0.0019382762257009745,-0.0014643990434706211,0.002444279845803976,0.31263700127601624,-0.03724675625562668,-0.005346739664673805 +1769682190,48937984,0.0,0.0,0.0,1.0,-0.0006657687481492758,-0.0020224922336637974,0.002865877700969577,0.010060486383736134,-0.07609827816486359,-0.014392559416592121 +1769682190,81521920,0.0,0.0,0.0,1.0,-0.00013079015479888767,-0.0022223598789423704,0.0032405152451246977,0.3221381902694702,-0.112830251455307,0.0016564344987273216 +1769682190,112289536,0.0,0.0,0.0,1.0,0.00012397860700730234,-0.0022853605914860964,0.0035941440146416426,0.31226348876953125,-0.0369565449655056,0.008881294168531895 +1769682190,154836992,0.0,0.0,0.0,1.0,0.0003754090575966984,-0.0022108247503638268,0.003964446950703859,0.009551056660711765,-0.07558745890855789,0.0046659731306135654 +1769682190,178361344,0.0,0.0,0.0,1.0,0.0002861497341655195,-0.0021818852983415127,0.004092338494956493,0.3216773569583893,-0.11250225454568863,0.018264273181557655 +1769682190,215500032,0.0,0.0,0.0,1.0,0.00019490608246997,-0.0021628979593515396,0.004099864512681961,0.7664164900779724,0.020586170256137848,0.01145988516509533 +1769682190,249787648,0.0,0.0,0.0,1.0,-2.833864709828049e-05,-0.002090835478156805,0.003920593298971653,0.30266469717025757,0.03852487727999687,0.00650374498218298 +1769682190,279828480,0.0,0.0,0.0,1.0,-0.00020198131096549332,-0.0019419826567173004,0.003673977917060256,0.17059804499149323,-0.13219678401947021,0.0030419628601521254 +1769682190,311578880,0.0,0.0,0.0,1.0,-0.00022110791178420186,-0.001910931197926402,0.00335500156506896,0.3028511106967926,0.038266152143478394,-0.0006790691986680031 +1769682190,362312448,0.0,0.0,0.0,1.0,-0.0003614319139160216,-0.0019260091939941049,0.0028953319415450096,0.33122795820236206,-0.18842600286006927,0.018049828708171844 +1769682190,369936384,0.0,0.0,0.0,1.0,-0.00047661270946264267,-0.002006281167268753,0.0026711297687143087,0.31217411160469055,-0.037189677357673645,0.01109546609222889 +1769682190,412788224,0.0,0.0,0.0,1.0,-0.00039561637095175683,-0.0019998482894152403,0.002294224686920643,0.5956509709358215,0.15260519087314606,0.01769310235977173 +1769682190,446608384,0.0,0.0,0.0,1.0,-0.00040092525887303054,-0.0020298033487051725,0.0020178919658064842,0.1609412580728531,-0.056550368666648865,0.00308520020917058 +1769682190,479571968,0.0,0.0,0.0,1.0,-0.00031677939114160836,-0.0020773583091795444,0.0018953593680635095,0.5958499908447266,0.15232715010643005,0.010464025661349297 +1769682190,511858176,0.0,0.0,0.0,1.0,-0.00018469130736775696,-0.0021498925052583218,0.0018518317956477404,0.3123405873775482,-0.037475116550922394,0.003856282914057374 +1769682190,547803904,0.0,0.0,0.0,1.0,-5.4667390941176564e-05,-0.0022539666388183832,0.001900196890346706,0.3122459948062897,-0.037367083132267,0.008594051003456116 +1769682190,580916992,0.0,0.0,0.0,1.0,-3.0275321478256956e-05,-0.0022260372061282396,0.002005724934861064,0.4543973207473755,0.05702734738588333,-0.004842262249439955 +1769682190,612194816,0.0,0.0,0.0,1.0,-0.0017354983137920499,-0.0009888468775898218,0.0017691184766590595,0.3231177031993866,-0.11461030691862106,-0.04635847359895706 +1769682190,648814080,0.0,0.0,0.0,1.0,-0.003748547751456499,0.0008316035964526236,0.0015284355031326413,0.313426673412323,-0.03876863047480583,-0.041480910032987595 +1769682190,679000320,0.0,0.0,0.0,1.0,-0.004298394080251455,0.0015197244938462973,0.0014285384677350521,0.31238773465156555,-0.03763262927532196,0.0014148098416626453 +1769682190,712092160,0.0,0.0,0.0,1.0,-0.004343403968960047,0.0014843330718576908,0.0013585538836196065,0.1512962430715561,0.019168537110090256,0.005548945628106594 +1769682190,759838464,0.0,0.0,0.0,1.0,-0.003264801809564233,0.0019455334404483438,0.0013179327361285686,0.6061734557151794,0.07556861639022827,-0.018256526440382004 +1769682190,780916736,0.0,0.0,0.0,1.0,-0.0029592099599540234,0.0021497556008398533,0.001205169945023954,0.15182052552700043,0.018589023500680923,-0.015870563685894012 +1769682190,812938496,0.0,0.0,0.0,1.0,-0.002725583966821432,0.0021945154294371605,0.0010467888787388802,0.15153071284294128,0.018897902220487595,-0.003945796750485897 +1769682190,846929152,0.0,0.0,0.0,1.0,-0.002306598937138915,0.002171624219045043,0.0008082757703959942,0.3028879463672638,0.03797253966331482,-0.000713348388671875 +1769682190,880115456,0.0,0.0,0.0,1.0,-0.001990671269595623,0.0020811003632843494,0.0006385599845089018,0.6244056224822998,-0.07503324747085571,0.017326386645436287 +1769682190,912455936,0.0,0.0,0.0,1.0,-0.0017127281753346324,0.00201333686709404,0.00048668222734704614,0.4824179410934448,-0.16966350376605988,0.021090570837259293 +1769682190,948278784,0.0,0.0,0.0,1.0,-0.0035355999134480953,0.0005468783201649785,0.0004177898808848113,0.4738101661205292,-0.0949305072426796,-0.01684391498565674 +1769682190,984675840,0.0,0.0,0.0,1.0,-0.0036541391164064407,-0.00014571619976777583,0.00040074135176837444,0.1610199213027954,-0.056786272674798965,-0.001712349010631442 +1769682191,12779776,0.0,0.0,0.0,1.0,-0.0036427383311092854,-0.00044490923755802214,0.00041143051930703223,0.46367478370666504,-0.01859430968761444,0.007161719258874655 +1769682191,46962432,0.0,0.0,0.0,1.0,-0.001539295306429267,-0.0018269428983330727,0.0006492176908068359,0.757317841053009,0.09476397931575775,-0.005224777385592461 +1769682191,79062784,0.0,0.0,0.0,1.0,-0.0009327696170657873,-0.002672410337254405,0.0007716190884821117,0.46408483386039734,-0.0190422423183918,-0.009576240554451942 +1769682191,115261952,0.0,0.0,0.0,1.0,-0.0004611989133991301,-0.0032109469175338745,0.0008608903735876083,0.46385008096694946,-0.018810251727700233,-8.802395313978195e-05 +1769682191,148716544,0.0,0.0,0.0,1.0,-1.3306108485267032e-05,-0.0034746932797133923,0.0009470792720094323,0.32185104489326477,-0.1134272962808609,0.0035781185142695904 +1769682191,179350528,0.0,0.0,0.0,1.0,0.0002799405774567276,-0.0034189128782600164,0.001014637527987361,0.6339888572692871,-0.15095791220664978,0.014458946883678436 +1769682191,211706368,0.0,0.0,0.0,1.0,0.0005224536871537566,-0.003351967316120863,0.0010665480513125658,0.30278196930885315,0.038020018488168716,0.003953711595386267 +1769682191,259422464,0.0,0.0,0.0,1.0,0.0006337331142276525,-0.0031190933659672737,0.0010968941496685147,0.6241093277931213,-0.07490531355142593,0.028834976255893707 +1769682191,278562304,0.0,0.0,0.0,1.0,0.0006806491874158382,-0.0029522825498133898,0.0010722674196586013,0.30284273624420166,0.03793613612651825,0.0015033334493637085 +1769682191,311617792,0.0,0.0,0.0,1.0,0.0005546837928704917,-0.0027379312086850405,0.0010010841069743037,0.3122536540031433,-0.037685576826334,0.006025024689733982 +1769682191,362011904,0.0,0.0,0.0,1.0,0.0004652848874684423,-0.002631671493873,0.0008238848531618714,0.4730265438556671,-0.09429018944501877,0.013645772822201252 +1769682191,387758592,0.0,0.0,0.0,1.0,0.00024222000502049923,-0.002666712272912264,0.0006231189472600818,0.6242234110832214,-0.07510055601596832,0.023850426077842712 +1769682191,403127296,0.0,0.0,0.0,1.0,-0.0001393557759001851,-0.002791577484458685,0.0004417201562318951,0.9078658819198608,0.11445379257202148,0.03280233219265938 +1769682191,446471168,0.0,0.0,0.0,1.0,-0.000622440769802779,-0.0031747817993164062,7.355141133302823e-05,0.4726913273334503,-0.09394331276416779,0.027805859223008156 +1769682191,479953152,0.0,0.0,0.0,1.0,-0.0007313871756196022,-0.0033458976540714502,-9.584064537193626e-05,0.6242848634719849,-0.07517452538013458,0.021272923797369003 +1769682191,514359040,0.0,0.0,0.0,1.0,-0.0009375240188091993,-0.003461203072220087,-0.0002358443452976644,0.766248881816864,0.019455445930361748,0.019699405878782272 +1769682191,551419136,0.0,0.0,0.0,1.0,-0.001050469116307795,-0.003456978825852275,-0.00038966815918684006,0.6149929165840149,0.0003274492919445038,0.01181676797568798 +1769682191,579179264,0.0,0.0,0.0,1.0,-0.0011279338505119085,-0.0034709349274635315,-0.0005123508744873106,0.7663078308105469,0.019414246082305908,0.017132224515080452 +1769682191,611521792,0.0,0.0,0.0,1.0,-0.0011950187617912889,-0.0034517114982008934,-0.0006308716256171465,0.4637358784675598,-0.01879543997347355,0.0039416151121258736 +1769682191,659773184,0.0,0.0,0.0,1.0,-0.001252377638593316,-0.0033836711663752794,-0.0007759295403957367,0.44463613629341125,0.13274729251861572,0.006744483485817909 +1769682191,669243392,0.0,0.0,0.0,1.0,-0.0012129262322559953,-0.003352049272507429,-0.0008472804329358041,0.9178965091705322,0.03824561834335327,0.010318216867744923 +1769682191,712596224,0.0,0.0,0.0,1.0,-0.0022414838895201683,-0.002488338388502598,-0.000976241601165384,0.46325430274009705,-0.018214445561170578,0.025237619876861572 +1769682191,745391872,0.0,0.0,0.0,1.0,-0.004033022094517946,-0.0007591426838189363,-0.0014652637764811516,0.4741833806037903,-0.0954895168542862,-0.03700864687561989 +1769682191,783191808,0.0,0.0,0.0,1.0,-0.005109442863613367,0.00046484963968396187,-0.0018185232765972614,0.5026320815086365,-0.32247939705848694,-0.03069162555038929 +1769682191,812822016,0.0,0.0,0.0,1.0,-0.005324019584804773,0.0008300026529468596,-0.0020173864904791117,0.454363614320755,0.056868962943553925,-0.003095912281423807 +1769682191,848068096,0.0,0.0,0.0,1.0,-0.00518486462533474,0.0011000511003658175,-0.002166410442441702,0.47377362847328186,-0.0949072614312172,-0.017966018989682198 +1769682191,878652672,0.0,0.0,0.0,1.0,-0.0039187646470963955,0.0018099856097251177,-0.0021422547288239002,0.6065804958343506,0.07507887482643127,-0.0382051020860672 +1769682191,912241408,0.0,0.0,0.0,1.0,-0.003267846303060651,0.002369451569393277,-0.0021335617639124393,0.6254189014434814,-0.07604728639125824,-0.026877805590629578 +1769682191,948102400,0.0,0.0,0.0,1.0,-0.0028332669753581285,0.002723420737311244,-0.0021478133276104927,0.6153767108917236,0.00026029348373413086,-0.005050518549978733 +1769682191,979258624,0.0,0.0,0.0,1.0,-0.002376534976065159,0.002829192904755473,-0.0021721485536545515,0.46385639905929565,-0.0186344925314188,-0.0008531310595571995 +1769682192,13441024,0.0,0.0,0.0,1.0,-0.002147453371435404,0.0027882561553269625,-0.0021972826216369867,0.7664280533790588,0.019808152690529823,0.01236813422292471 +1769682192,67093248,0.0,0.0,0.0,1.0,-0.0016669431934133172,0.0025443180929869413,-0.0022163332905620337,0.624351441860199,-0.07469919323921204,0.020990822464227676 +1769682192,75052288,0.0,0.0,0.0,1.0,-0.001614073757082224,0.0023948887828737497,-0.0022176457569003105,0.7757618427276611,-0.055594608187675476,0.021678384393453598 +1769682192,111588864,0.0,0.0,0.0,1.0,-0.0013216702500358224,0.002067866502329707,-0.002162722870707512,0.6245245933532715,-0.07479013502597809,0.01392051950097084 +1769682192,157732864,0.0,0.0,0.0,1.0,-0.0026485782582312822,0.0009019740391522646,-0.002070453716441989,0.6152123212814331,0.0007011592388153076,0.0023827310651540756 +1769682192,182136832,0.0,0.0,0.0,1.0,-0.003096171887591481,0.0004457723698578775,-0.002051610965281725,0.46380916237831116,-0.018376924097537994,0.0017057866789400578 +1769682192,212041472,0.0,0.0,0.0,1.0,-0.0032368493266403675,0.00015380946570076048,-0.001991030527278781,0.7472939491271973,0.1714615672826767,0.00858381763100624 +1769682192,246156288,0.0,0.0,0.0,1.0,-0.0011528629111126065,-0.0015636829193681479,-0.0017567561008036137,0.7476698756217957,0.1711212545633316,-0.008114228025078773 +1769682192,280134400,0.0,0.0,0.0,1.0,-0.0006189410341903567,-0.0023836172185838223,-0.0016493742587044835,0.47353726625442505,-0.09412656724452972,-0.0034808428026735783 +1769682192,312901120,0.0,0.0,0.0,1.0,-0.00023448264983016998,-0.002882951172068715,-0.0015929111978039145,0.6250505447387695,-0.0750652626156807,-0.007621907629072666 +1769682192,348914176,0.0,0.0,0.0,1.0,0.00011503659334266558,-0.003212848911061883,-0.0015567216323688626,0.463924765586853,-0.018352588638663292,-0.0032043559476733208 +1769682192,378974464,0.0,0.0,0.0,1.0,0.0003632660664152354,-0.0032380514312535524,-0.0015438959235325456,0.47316882014274597,-0.09365789592266083,0.013055559247732162 +1769682192,415116800,0.0,0.0,0.0,1.0,0.0005476935766637325,-0.003249439410865307,-0.001538692507892847,0.7757488489151001,-0.05506151169538498,0.023774530738592148 +1769682192,450559488,0.0,0.0,0.0,1.0,0.0006862735608592629,-0.003181226085871458,-0.001547582563944161,0.7661755681037903,0.020650522783398628,0.02166777290403843 +1769682192,479228160,0.0,0.0,0.0,1.0,0.0007180006359703839,-0.0030624617356806993,-0.0015530904056504369,0.46349626779556274,-0.017808102071285248,0.015667354688048363 +1769682192,511994112,0.0,0.0,0.0,1.0,0.0007835426367819309,-0.002905749250203371,-0.0015601558843627572,0.45391133427619934,0.057876452803611755,0.013616630807518959 +1769682192,560964096,0.0,0.0,0.0,1.0,0.0007217552629299462,-0.0026571338530629873,-0.0015704995021224022,0.6151602864265442,0.0011680275201797485,0.004211879801005125 +1769682192,578834688,0.0,0.0,0.0,1.0,0.000732834218069911,-0.0025529656559228897,-0.0015887253684923053,0.6149477362632751,0.0014237798750400543,0.013695579022169113 +1769682192,613125376,0.0,0.0,0.0,1.0,0.0006482164026238024,-0.0023992755450308323,-0.001620489521883428,0.927328884601593,-0.035763148218393326,0.016716228798031807 +1769682192,646133504,0.0,0.0,0.0,1.0,-0.00025922851637005806,-0.002794964239001274,-0.0018995276186615229,0.47269120812416077,-0.09288499504327774,0.03653451055288315 +1769682192,679258112,0.0,0.0,0.0,1.0,-0.0007241725688800216,-0.0031145925167948008,-0.002097197575494647,0.7660234570503235,0.021117068827152252,0.028326069936156273 +1769682192,713584128,0.0,0.0,0.0,1.0,-0.0010812358232215047,-0.0034659593366086483,-0.0022836264688521624,0.7850462198257446,-0.12992458045482635,0.041795115917921066 +1769682192,750086400,0.0,0.0,0.0,1.0,-0.001342040835879743,-0.0037444611079990864,-0.002501089358702302,0.7661830186843872,0.02107076905667782,0.020989425480365753 +1769682192,779542784,0.0,0.0,0.0,1.0,-0.0015128608793020248,-0.003725485410541296,-0.0026288642548024654,0.7759162783622742,-0.05464087426662445,0.018136143684387207 +1769682192,813151488,0.0,0.0,0.0,1.0,-0.0016004022909328341,-0.003601053263992071,-0.0027368837036192417,0.7568062543869019,0.0965663343667984,0.006914704106748104 +1769682192,847503616,0.0,0.0,0.0,1.0,-0.001689239637926221,-0.0035013954620808363,-0.002854268066585064,0.4638345241546631,-0.017788609489798546,0.0008316035382449627 +1769682192,879376384,0.0,0.0,0.0,1.0,-0.0017840139335021377,-0.0034383400343358517,-0.002946801483631134,0.46373432874679565,-0.017636286094784737,0.005548564251512289 +1769682192,912013312,0.0,0.0,0.0,1.0,-0.0017324587097391486,-0.003409259021282196,-0.00304845767095685,0.7859066724777222,-0.13034570217132568,0.005446839611977339 +1769682192,950059520,0.0,0.0,0.0,1.0,-0.0017592826625332236,-0.0035403536166995764,-0.003181066829711199,0.7858231067657471,-0.1301364302635193,0.010094148106873035 +1769682192,980860160,0.0,0.0,0.0,1.0,-0.001706936745904386,-0.0036283605732023716,-0.003296254901215434,0.6247392296791077,-0.0737205371260643,0.010075523518025875 +1769682193,11702784,0.0,0.0,0.0,1.0,-0.0016643929993733764,-0.0035668627824634314,-0.0034304119180887938,0.7566518187522888,0.09714001417160034,0.011181214824318886 +1769682193,47362560,0.0,0.0,0.0,1.0,-0.002684203675016761,-0.0030612775590270758,-0.0036461963318288326,0.605073869228363,0.07806191593408585,0.02031003311276436 +1769682193,79363328,0.0,0.0,0.0,1.0,-0.0031243006233125925,-0.002456242684274912,-0.0038496050983667374,0.9076492190361023,0.11713814735412598,0.028019297868013382 +1769682193,115243008,0.0,0.0,0.0,1.0,-0.003408127697184682,-0.0018837684765458107,-0.004068861715495586,0.32200294733047485,-0.11225210875272751,0.011607730761170387 +1769682193,147981312,0.0,0.0,0.0,1.0,-0.003525076899677515,-0.0013244753936305642,-0.004464710596948862,0.48310786485671997,-0.16837947070598602,0.013782765716314316 +1769682193,179280128,0.0,0.0,0.0,1.0,-0.004519549198448658,-0.0003207888512406498,-0.00494892755523324,0.4451187551021576,0.1332460641860962,-0.0391850471496582 +1769682193,214515200,0.0,0.0,0.0,1.0,-0.004900453146547079,0.0001366647338727489,-0.005290435627102852,0.8986203074455261,0.19244597852230072,-0.012083565816283226 +1769682193,247763968,0.0,0.0,0.0,1.0,-0.005053437780588865,0.0003565022780094296,-0.005533195566385984,0.7666597366333008,0.021920502185821533,-0.0037860143929719925 +1769682193,279480832,0.0,0.0,0.0,1.0,-0.005238384939730167,0.0002859826199710369,-0.005585601553320885,0.46386557817459106,-0.01698782481253147,0.00039209285750985146 +1769682193,312031488,0.0,0.0,0.0,1.0,-0.0038350564427673817,0.0009205691167153418,-0.005411629099398851,0.6062080264091492,0.07748691737651825,-0.0392928346991539 +1769682193,359963392,0.0,0.0,0.0,1.0,-0.0027601353358477354,0.0017325002700090408,-0.005152937024831772,0.6156542301177979,0.002345588058233261,-0.020708050578832626 +1769682193,380021760,0.0,0.0,0.0,1.0,-0.002428509294986725,0.002111028879880905,-0.005002666264772415,0.6253728270530701,-0.07309271395206451,-0.014051693491637707 +1769682193,412257536,0.0,0.0,0.0,1.0,-0.0021200012415647507,0.002301853848621249,-0.004891543183475733,0.6153087019920349,0.002895444631576538,-0.003947046585381031 +1769682193,446171136,0.0,0.0,0.0,1.0,-0.0017919255187734962,0.0022486650850623846,-0.004785648547112942,0.6151092052459717,0.003220846876502037,0.00564189488068223 +1769682193,478739200,0.0,0.0,0.0,1.0,-0.0016733617521822453,0.002245226176455617,-0.004738982301205397,0.9174609184265137,0.043061815202236176,0.020712388679385185 +1769682193,512081664,0.0,0.0,0.0,1.0,-0.0014957148814573884,0.0020111985504627228,-0.004700388293713331,0.7758428454399109,-0.05203055590391159,0.02938292920589447 +1769682193,546704896,0.0,0.0,0.0,1.0,-0.0013247266178950667,0.0015992692206054926,-0.004643590189516544,0.45360708236694336,0.059674423187971115,0.01784253865480423 +1769682193,579264256,0.0,0.0,0.0,1.0,-0.001170980278402567,0.0014791327994316816,-0.004564768634736538,0.46363717317581177,-0.016045495867729187,0.012547601014375687 +1769682193,612361984,0.0,0.0,0.0,1.0,-0.0009947496000677347,0.001468118280172348,-0.004448273219168186,0.6051565408706665,0.07935480773448944,0.0063733370043337345 +1769682193,646774272,0.0,0.0,0.0,1.0,-0.000882210792042315,0.0012932006502524018,-0.0042370096780359745,0.7661613821983337,0.023876721039414406,0.018180059269070625 +1769682193,679475200,0.0,0.0,0.0,1.0,-0.0008304798393510282,0.0012914917897433043,-0.004060184583067894,0.4537730813026428,0.05972661077976227,0.008400430902838707 +1769682193,713177088,0.0,0.0,0.0,1.0,-0.0009671509033069015,0.001427148119546473,-0.00390170281752944,0.7760831117630005,-0.051561929285526276,0.020065857097506523 +1769682193,747572224,0.0,0.0,0.0,1.0,-0.0014609933132305741,0.0010898271575570107,-0.0036029298789799213,0.7665579915046692,0.0237693153321743,-0.0007821805775165558 +1769682193,779918080,0.0,0.0,0.0,1.0,-0.002188263460993767,0.0008185450569726527,-0.0034783913288265467,0.4740036427974701,-0.0917007103562355,-0.00458503607660532 +1769682193,812407296,0.0,0.0,0.0,1.0,-0.00273119262419641,0.0005417198990471661,-0.003516973927617073,0.624954104423523,-0.07136812806129456,0.012540621683001518 +1769682193,850705408,0.0,0.0,0.0,1.0,-0.0032010998111218214,4.665483720600605e-05,-0.0036595643032342196,0.604928195476532,0.08005846291780472,0.013700703158974648 +1769682193,880772352,0.0,0.0,0.0,1.0,-0.0019042888889089227,-0.0011310745030641556,-0.0036764147225767374,0.6156110167503357,0.003808002918958664,-0.01787582039833069 +1769682193,913802752,0.0,0.0,0.0,1.0,-0.0015060659497976303,-0.0018881302094087005,-0.0038241303991526365,0.6251342296600342,-0.07129047065973282,0.005334330257028341 +1769682193,958906624,0.0,0.0,0.0,1.0,-0.001101608737371862,-0.002422854769974947,-0.004113208502531052,0.45401790738105774,0.05988067016005516,-0.005875533912330866 +1769682193,979348224,0.0,0.0,0.0,1.0,-0.0009093806147575378,-0.0025412137620151043,-0.004475744441151619,0.7760871052742004,-0.05073299631476402,0.022320661693811417 +1769682194,12319488,0.0,0.0,0.0,1.0,-0.0007828436209820211,-0.0023651535157114267,-0.004889796953648329,0.47378218173980713,-0.09097269177436829,0.009540685452520847 +1769682194,46405120,0.0,0.0,0.0,1.0,-0.00036617444129660726,-0.0022523950319737196,-0.005428626202046871,0.6049145460128784,0.08052897453308105,0.011090772226452827 +1769682194,79870976,0.0,0.0,0.0,1.0,-3.673670289572328e-05,-0.0021017577964812517,-0.005739865358918905,0.7661729454994202,0.02518046274781227,0.015593476593494415 +1769682194,112108288,0.0,0.0,0.0,1.0,0.000478890142403543,-0.0018821271369233727,-0.005922690499573946,0.7862380743026733,-0.12584899365901947,0.021490463986992836 +1769682194,148675328,0.0,0.0,0.0,1.0,0.0009085358469747007,-0.001621023751795292,-0.005987906828522682,0.6049193143844604,0.0808335691690445,0.008589173667132854 +1769682194,179611648,0.0,0.0,0.0,1.0,0.0010789309162646532,-0.001598493428900838,-0.005922418087720871,0.7760526537895203,-0.04976796358823776,0.026773760095238686 +1769682194,214513920,0.0,0.0,0.0,1.0,0.0012292107567191124,-0.001623080694116652,-0.005782304797321558,0.7762116193771362,-0.04978006333112717,0.019588850438594818 +1769682194,247994624,0.0,0.0,0.0,1.0,0.0012503574835136533,-0.0017145011806860566,-0.005537961609661579,0.6147478818893433,0.0058349501341581345,0.022185396403074265 +1769682194,279353600,0.0,0.0,0.0,1.0,0.0005774461897090077,-0.0017456876812502742,-0.005592092406004667,0.9377794861793518,-0.10493649542331696,0.01446589920669794 +1769682194,328481280,0.0,0.0,0.0,1.0,-8.523876022081822e-05,-0.0019596279598772526,-0.00607264693826437,0.7861445546150208,-0.12468364089727402,0.033163100481033325 +1769682194,359921920,0.0,0.0,0.0,1.0,-0.00015520481974817812,-0.002274886006489396,-0.006609942298382521,0.9170883893966675,0.04705200716853142,0.029820457100868225 +1769682194,370061824,0.0,0.0,0.0,1.0,-0.00026752465055324137,-0.002314010402187705,-0.006865863222628832,0.7560077905654907,0.10204924643039703,0.011012931354343891 +1769682194,412094976,0.0,0.0,0.0,1.0,-0.0003089458041358739,-0.0020439540967345238,-0.007353953551501036,0.4637089967727661,-0.014148924499750137,0.012168116867542267 +1769682194,448092672,0.0,0.0,0.0,1.0,-0.0002952846116386354,-0.0019408718217164278,-0.007807823363691568,0.7661716341972351,0.026912042871117592,0.012673066928982735 +1769682194,480203264,0.0,0.0,0.0,1.0,-0.000197811663383618,-0.0016851841937750578,-0.008090635761618614,0.6048950552940369,0.08198380470275879,0.00105367973446846 +1769682194,507279872,0.0,0.0,0.0,1.0,-0.00016242192941717803,-0.0018109917873516679,-0.008460000157356262,0.6249107718467712,-0.0685289278626442,0.028418902307748795 +1769682194,547609344,0.0,0.0,0.0,1.0,-0.0003932832623831928,-0.002503610448911786,-0.008860490284860134,0.453201025724411,0.06220564991235733,0.02217596396803856 +1769682194,579116288,0.0,0.0,0.0,1.0,-0.0004945747787132859,-0.00282893143594265,-0.00896815862506628,0.45309019088745117,0.06242595240473747,0.026906060054898262 +1769682194,613600000,0.0,0.0,0.0,1.0,-0.0005426936550065875,-0.0028810014482587576,-0.008974046446383,0.9481297135353088,-0.17788125574588776,0.027475537732243538 +1769682194,655762944,0.0,0.0,0.0,1.0,0.0003665901313070208,-0.0030850120820105076,-0.00799976009875536,0.6149844527244568,0.007453957572579384,0.00972154550254345 +1769682194,680238336,0.0,0.0,0.0,1.0,0.00011228961375309154,-0.002968311309814453,-0.0074449991807341576,0.9276842474937439,-0.026415430009365082,0.014194836840033531 +1769682194,713403136,0.0,0.0,0.0,1.0,-0.00020748673705384135,-0.0027274840977042913,-0.006980701815336943,0.7664030194282532,0.028262274339795113,-0.0021297717466950417 +1769682194,749243648,0.0,0.0,0.0,1.0,-0.00048054533544927835,-0.0026057653594762087,-0.006447644904255867,0.4533960819244385,0.06262414902448654,0.007619625888764858 +1769682194,780003584,0.0,0.0,0.0,1.0,-0.0006761168478988111,-0.002481664065271616,-0.006071728654205799,0.7556884288787842,0.10446438193321228,0.010260967537760735 +1769682194,813409280,0.0,0.0,0.0,1.0,-0.0008067494491115212,-0.0023177973926067352,-0.005702716764062643,0.9277225732803345,-0.025635316967964172,0.013879397884011269 +1769682194,849278208,0.0,0.0,0.0,1.0,-0.0008920035324990749,-0.002417226554825902,-0.005214049015194178,0.7661000490188599,0.029204580932855606,0.011905577033758163 +1769682194,879131648,0.0,0.0,0.0,1.0,-0.0009741489193402231,-0.0025073918513953686,-0.004855971317738295,0.46363040804862976,-0.012403910979628563,0.01877649873495102 +1769682194,912648448,0.0,0.0,0.0,1.0,-0.0010483519872650504,-0.0024112346582114697,-0.004534238018095493,0.4638635218143463,-0.01258525438606739,0.006825682241469622 +1769682194,945930496,0.0,0.0,0.0,1.0,-0.0012256231857463717,-0.00236212438903749,-0.004216649103909731,0.7869240641593933,-0.12139547616243362,0.022378478199243546 +1769682194,979429376,0.0,0.0,0.0,1.0,-0.0014065040741115808,-0.0023155149538069963,-0.004075978882610798,0.6254271864891052,-0.0668981671333313,0.013342590071260929 +1769682195,15953920,0.0,0.0,0.0,1.0,-0.0014686585636809468,-0.002423012861981988,-0.004025085363537073,0.7659473419189453,0.029889460653066635,0.018766993656754494 +1769682195,63363072,0.0,0.0,0.0,1.0,-0.0015517559368163347,-0.002372083254158497,-0.004030698910355568,0.7975859642028809,-0.19672255218029022,0.019147777929902077 +1769682195,68328704,0.0,0.0,0.0,1.0,-0.0016620918177068233,-0.0023850479628890753,-0.004073403310030699,0.6254543662071228,-0.0666729211807251,0.013199148699641228 +1769682195,112223744,0.0,0.0,0.0,1.0,-0.0015015910612419248,-0.0020763922948390245,-0.00418057618662715,0.7555382251739502,0.10559704899787903,0.009713389910757542 +1769682197,548854528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682197,579412224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682197,612676864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682197,651532800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682197,680969984,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682197,712420352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682197,752482560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682197,780813824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682197,813421312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682197,847537920,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682197,879491328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682197,916501760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682197,947309824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682197,980279808,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,13523968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,51688704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,80081920,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,113909760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,161047808,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,179833088,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,212895488,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,246274304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,279599360,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,313015296,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,348326400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,379715584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,412878848,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.116104875924066e-05,4.60894443676807e-05,0.002383194398134947 +1769682198,446332160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,479724032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,513217280,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,562071296,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,570911744,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,612452352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,647262208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,679890688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,712583168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,747471104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,785970944,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,813213952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,849940992,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,879300608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,914982656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,949789952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682198,979589888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,12694272,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,59095040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,80193024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,113126144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,146390784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,182530048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,213185280,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,249255936,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.116093598189764e-05,4.6089349780231714e-05,0.002383194398134947 +1769682199,279440896,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,314727424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,348283904,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,380083200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.1160812290618196e-05,4.608933159033768e-05,0.002383194398134947 +1769682199,413421056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,459637248,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.116068496135995e-05,4.60893425042741e-05,0.002383194398134947 +1769682199,479366144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,514479360,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,547274240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,580472576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,613793280,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,653031680,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,679529216,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,713768704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,749262848,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,779961344,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,812732416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,864351232,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.1159964641556144e-05,4.608938252204098e-05,0.002383194398134947 +1769682199,873803264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.115992826176807e-05,-4.608937888406217e-05,-0.002383194398134947 +1769682199,913622528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.115985550219193e-05,4.608938252204098e-05,0.002383194398134947 +1769682199,949498112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682199,980352768,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.115972817293368e-05,4.6089375246083364e-05,0.002383194398134947 +1769682200,12973824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.1159673603251576e-05,4.6089375246083364e-05,0.002383194398134947 +1769682200,50682880,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,79653376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,112893696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,155663616,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,179623168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,214170112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,260712704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,280346368,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.1159186114091426e-05,-4.6089360694168136e-05,-0.002383194398134947 +1769682200,315093504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,347288064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.115905514685437e-05,-4.608936433214694e-05,-0.002383194398134947 +1769682200,381636352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,413020160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,448744192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,479946752,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,514544384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,550950144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,579957504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,612649984,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,658644992,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,679801344,0.0,0.0,0.0,1.0,-3.4874034327003756e-07,-7.384572313640092e-07,2.976481027872069e-06,0.0,-0.0,0.0 +1769682200,714676480,0.0,0.0,0.0,1.0,-3.4874034327003756e-07,-7.384572313640092e-07,2.976481027872069e-06,0.0,-0.0,0.0 +1769682200,747594240,0.0,0.0,0.0,1.0,-3.4874034327003756e-07,-7.384572313640092e-07,2.976481027872069e-06,0.0,-0.0,0.0 +1769682200,780452608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,812896512,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,847276800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,880267520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682200,914920192,0.0,0.0,0.0,1.0,1.2957970341176406e-07,4.157252533332212e-07,2.9704558528464986e-06,0.0,-0.0,0.0 +1769682200,949722880,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.1158760470570996e-05,-4.60892406408675e-05,-0.002383194398134947 +1769682200,984146176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682201,14167552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682201,51516416,0.0,0.0,0.0,1.0,-5.61993260816962e-08,4.0255582689496805e-07,2.9685895697184606e-06,0.0,-0.0,0.0 +1769682201,80684544,0.0,0.0,0.0,1.0,-4.277573850686167e-07,3.762170024401712e-07,2.9648570034623845e-06,0.0,-0.0,0.0 +1769682201,112692480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-0.010744350962340832,0.0755147710442543,-0.001691044308245182 +1769682201,146200064,0.0,0.0,0.0,1.0,1.2957967499005463e-07,4.1572519648980233e-07,2.9704558528464986e-06,0.0,-0.0,0.0 +1769682201,180784896,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682201,214642944,0.0,0.0,0.0,1.0,-5.6199340292550914e-08,4.025558553166775e-07,2.968589797092136e-06,0.0,-0.0,0.0 +1769682201,247884800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682201,280931584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682201,312790528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682201,347690496,0.0,0.0,0.0,1.0,-5.619933318712356e-08,4.0255582689496805e-07,2.968589797092136e-06,0.0,-0.0,0.0 +1769682201,379849472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682201,413529856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682201,460046848,0.0,0.0,0.0,1.0,-1.1840225511150493e-07,1.768393786960587e-07,4.656126748159295e-06,0.0,-0.0,0.0 +1769682201,479690496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682201,513675008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.1159251597709954e-05,-4.6089160605333745e-05,-0.002383194398134947 +1769682201,561444352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682201,580511488,0.0,0.0,0.0,1.0,-4.277573566469073e-07,3.7621722981384664e-07,2.9648570034623845e-06,0.0,-0.0,0.0 +1769682201,612676608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682201,647673344,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682201,682579456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682201,713920000,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682201,747437056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682201,780154624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682201,815861760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682201,847981568,0.0,0.0,0.0,1.0,-2.9860956374250236e-08,3.0997711064628675e-08,2.9724642445216887e-06,0.0,-0.0,0.0 +1769682201,880405504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682201,912601856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682201,959414272,0.0,0.0,0.0,1.0,-9.164915582005051e-08,1.3727235170790664e-07,2.127771267623757e-06,0.0,-0.0,0.0 +1769682201,981423616,0.0,0.0,0.0,1.0,-2.156399858677105e-07,1.7828547527187766e-08,2.970598188767326e-06,0.0,-0.0,0.0 +1769682202,13104896,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682202,47662848,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682202,85422336,0.0,0.0,0.0,1.0,-2.4550095645281544e-07,4.882623727553437e-08,5.943062205915339e-06,0.0,-0.0,0.0 +1769682202,114481920,0.0,0.0,0.0,1.0,-2.9860959926963915e-08,3.09976897483466e-08,2.9724646992690396e-06,0.0,-0.0,0.0 +1769682202,148117760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682202,179475968,0.0,0.0,0.0,1.0,1.2605710253410507e-07,7.516445066357846e-08,5.946796136413468e-06,0.0,-0.0,0.0 +1769682202,218497792,0.0,0.0,0.0,1.0,-2.156400000785652e-07,1.782859904153611e-08,2.970598188767326e-06,0.0,-0.0,0.0 +1769682202,251586816,0.0,0.0,0.0,1.0,-4.479144877223007e-08,4.649650620081047e-08,4.458696821529884e-06,0.0,-0.0,0.0 +1769682202,280838656,0.0,0.0,0.0,1.0,-4.1634953618086e-07,2.0158417157745134e-08,4.454964255273808e-06,0.0,-0.0,0.0 +1769682202,312990976,0.0,0.0,0.0,1.0,-2.3057049247654504e-07,3.332746700834832e-08,4.456830538401846e-06,0.0,-0.0,0.0 +1769682202,357616128,0.0,0.0,0.0,1.0,-2.3057049247654504e-07,3.332747766648936e-08,4.456830993149197e-06,0.0,-0.0,0.0 +1769682202,379851008,0.0,0.0,0.0,1.0,1.409875949320849e-07,5.96654814444264e-08,4.460563104657922e-06,0.0,-0.0,0.0 +1769682202,412938752,0.0,0.0,0.0,1.0,-2.3057049247654504e-07,3.332747766648936e-08,4.456830993149197e-06,0.0,-0.0,0.0 +1769682202,464187904,0.0,0.0,0.0,1.0,-2.569084074366401e-07,4.0488552599526884e-07,4.452956090972293e-06,-5.1159498980268836e-05,4.608906965586357e-05,0.002383194398134947 +1769682202,482581504,0.0,0.0,0.0,1.0,-4.479145587765743e-08,4.649645646281897e-08,4.458696821529884e-06,0.0,-0.0,0.0 +1769682202,504058880,0.0,0.0,0.0,1.0,-2.3057049247654504e-07,3.3327520299053504e-08,4.456830993149197e-06,5.115949170431122e-05,-4.6089073293842375e-05,-0.002383194398134947 +1769682202,547624448,0.0,0.0,0.0,1.0,-2.3057049247654504e-07,3.332752740448086e-08,4.456830538401846e-06,-5.1159488066332415e-05,4.6089084207778797e-05,0.002383194398134947 +1769682202,580489472,0.0,0.0,0.0,1.0,1.409875949320849e-07,5.966536775758868e-08,4.460563559405273e-06,0.0,-0.0,0.0 +1769682202,613717248,0.0,0.0,0.0,1.0,-2.3057052089825447e-07,3.3327545168049255e-08,4.456830993149197e-06,0.0,-0.0,0.0 +1769682202,654583808,0.0,0.0,0.0,1.0,-4.4791462983084784e-08,4.649644580467793e-08,4.458697276277235e-06,0.0,-0.0,0.0 +1769682202,681798656,0.0,0.0,0.0,1.0,-2.3057052089825447e-07,3.332755937890397e-08,4.456830993149197e-06,5.115946987643838e-05,-4.608906965586357e-05,-0.002383194398134947 +1769682202,713890816,0.0,0.0,0.0,1.0,-2.3057052089825447e-07,3.332755582619029e-08,4.456830993149197e-06,0.0,-0.0,0.0 +1769682202,759813376,0.0,0.0,0.0,1.0,-2.3057052089825447e-07,3.332756648433133e-08,4.456830993149197e-06,0.0,-0.0,0.0 +1769682202,779984384,0.0,0.0,0.0,1.0,-2.3057052089825447e-07,3.332758069518604e-08,4.456830993149197e-06,0.0,-0.0,0.0 +1769682202,814251776,0.0,0.0,0.0,1.0,-2.3057052089825447e-07,3.332758424789972e-08,4.456830993149197e-06,0.0,-0.0,0.0 +1769682202,847671040,0.0,0.0,0.0,1.0,3.2676661021469044e-07,7.28340268096872e-08,4.462429842533311e-06,0.0,-0.0,0.0 +1769682202,887168768,0.0,0.0,0.0,1.0,-4.1634953618086e-07,2.0158807956249802e-08,4.454964255273808e-06,0.0,-0.0,0.0 +1769682202,912802816,0.0,0.0,0.0,1.0,-4.1634953618086e-07,2.015883993067291e-08,4.454964710021159e-06,0.0,-0.0,0.0 +1769682202,950350592,0.0,0.0,0.0,1.0,-6.021286367285938e-07,6.990104495230298e-09,4.453098426893121e-06,0.0,-0.0,0.0 +1769682202,980963072,0.0,0.0,0.0,1.0,-4.479147008851214e-08,4.649637475040436e-08,4.458697276277235e-06,0.0,-0.0,0.0 +1769682203,15610112,0.0,0.0,0.0,1.0,-2.3057052089825447e-07,3.332762688046387e-08,4.456830993149197e-06,0.0,-0.0,0.0 +1769682203,49167872,0.0,0.0,0.0,1.0,-4.163495930242789e-07,2.015890743223281e-08,4.454964710021159e-06,5.1159462600480765e-05,-4.608902600011788e-05,-0.002383194398134947 +1769682203,80348672,0.0,0.0,0.0,1.0,-4.479148429936686e-08,4.6496346328694926e-08,4.458697276277235e-06,0.0,-0.0,0.0 +1769682203,113116160,0.0,0.0,0.0,1.0,3.531040135840158e-07,-2.9872435902689176e-07,4.4663047447102144e-06,-5.115944804856554e-05,4.608904419001192e-05,0.002383194398134947 +1769682203,163691008,0.0,0.0,0.0,1.0,-1.8454080930041528e-08,-3.250617908179265e-07,4.462572633201489e-06,0.0,-0.0,0.0 +1769682203,169520896,0.0,0.0,0.0,1.0,-2.0423314595063857e-07,-3.3823047829173447e-07,4.460705440578749e-06,0.0,-0.0,0.0 +1769682203,212940288,0.0,0.0,0.0,1.0,-3.90012218076663e-07,-3.5139908050041413e-07,4.458839157450711e-06,-5.115934618515894e-05,4.608904419001192e-05,0.002383194398134947 +1769682203,246577152,0.0,0.0,0.0,1.0,-1.8454080930041528e-08,-3.250617908179265e-07,4.462572633201489e-06,0.0,-0.0,0.0 +1769682203,282164480,0.0,0.0,0.0,1.0,-2.0423314595063857e-07,-3.382304214483156e-07,4.460705440578749e-06,0.010743720456957817,-0.07551486045122147,0.0016910280101001263 +1769682203,314843136,0.0,0.0,0.0,1.0,-1.845409869360992e-08,-3.2506181923963595e-07,4.46257308794884e-06,0.0,-0.0,0.0 +1769682203,348214016,0.0,0.0,0.0,1.0,-3.900122464983724e-07,-3.513990520787047e-07,4.458839612198062e-06,0.0,-0.0,0.0 +1769682203,380381440,0.0,0.0,0.0,1.0,-1.845409869360992e-08,-3.250618476613454e-07,4.46257308794884e-06,0.0,-0.0,0.0 +1769682203,413886976,0.0,0.0,0.0,1.0,-1.8454091588182564e-08,-3.250618476613454e-07,4.462572633201489e-06,5.1159149734303355e-05,-4.6089036914054304e-05,-0.002383194398134947 +1769682203,451190784,0.0,0.0,0.0,1.0,-3.3384473852038354e-08,-3.095630347615952e-07,5.9488047554623336e-06,-5.115910971653648e-05,4.6089047827990726e-05,0.002383194398134947 +1769682203,479776000,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.115908061270602e-05,4.6089036914054304e-05,0.002383194398134947 +1769682203,512874496,0.0,0.0,0.0,1.0,-4.049426252095145e-07,-3.359001539138262e-07,5.945072643953608e-06,0.0,-0.0,0.0 +1769682203,560125952,0.0,0.0,0.0,1.0,-2.0599503613993875e-07,-5.085107659397181e-07,5.9488770602911245e-06,0.0,-0.0,0.0 +1769682203,581160448,0.0,0.0,0.0,1.0,-3.5237306406088464e-09,-3.405606037176767e-07,2.9763402835669694e-06,-5.115897874929942e-05,4.608902963809669e-05,0.002383194398134947 +1769682203,613738240,0.0,0.0,0.0,1.0,2.854997376289248e-07,4.59890145521058e-07,5.944788426859304e-06,0.0,-0.0,0.0 +1769682203,648172288,0.0,0.0,0.0,1.0,-3.338445608846996e-08,-3.095631484484329e-07,5.9488052102096844e-06,0.0,-0.0,0.0 +1769682203,684510976,0.0,0.0,0.0,1.0,-3.5237803786003496e-09,-3.4056063213938614e-07,2.9763402835669694e-06,0.0,-0.0,0.0 +1769682203,714240768,0.0,0.0,0.0,1.0,1.2605772781171254e-07,7.51634559037484e-08,5.94679704590817e-06,0.0,-0.0,0.0 +1769682203,751216384,0.0,0.0,0.0,1.0,-2.1916359571605426e-07,-3.2273152328343713e-07,5.946939381828997e-06,0.0,-0.0,0.0 +1769682203,779996160,0.0,0.0,0.0,1.0,-1.893029093480436e-07,-3.5372909223951865e-07,2.974473773065256e-06,0.0,-0.0,0.0 +1769682203,815042304,0.0,0.0,0.0,1.0,-3.338447740475203e-08,-3.0956317687014234e-07,5.9488052102096844e-06,0.0,-0.0,0.0 +1769682203,850882816,0.0,0.0,0.0,1.0,1.5239461959026812e-07,-2.9639480203513813e-07,5.950671038590372e-06,0.0,-0.0,0.0 +1769682203,880355840,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682203,913111808,0.0,0.0,0.0,1.0,-2.1916355308349011e-07,-3.22731580126856e-07,5.946939381828997e-06,0.0,-0.0,0.0 +1769682203,966001920,0.0,0.0,0.0,1.0,-4.049426820529334e-07,-3.3589992654015077e-07,5.945073098700959e-06,0.0,-0.0,0.0 +1769682203,971684352,0.0,0.0,0.0,1.0,-2.191635388726354e-07,-3.22731580126856e-07,5.946939836576348e-06,0.0,-0.0,0.0 +1769682204,12922880,0.0,0.0,0.0,1.0,-3.3384445430328924e-08,-3.095632337135612e-07,5.948806119704386e-06,0.0,-0.0,0.0 +1769682204,48120320,0.0,0.0,0.0,1.0,-1.8454144878887746e-08,-3.2506193292647367e-07,4.462572633201489e-06,0.0,-0.0,0.0 +1769682204,80590592,0.0,0.0,0.0,1.0,-1.7789662365430559e-07,-7.097884235918173e-07,4.464580797503004e-06,0.0,-0.0,0.0 +1769682204,112930048,0.0,0.0,0.0,1.0,-3.636757242020394e-07,-7.229566563182743e-07,4.462714514374966e-06,0.0,-0.0,0.0 +1769682204,147217664,0.0,0.0,0.0,1.0,-3.6367569578033e-07,-7.229567131616932e-07,4.462714969122317e-06,0.0,-0.0,0.0 +1769682204,179911680,0.0,0.0,0.0,1.0,-5.494547963280638e-07,-7.361249458881503e-07,4.460847776499577e-06,0.0,-0.0,0.0 +1769682204,213518080,0.0,0.0,0.0,1.0,-2.3056963982526213e-07,3.332786491228035e-08,4.4568319026438985e-06,0.0,-0.0,0.0 +1769682204,250569984,0.0,0.0,0.0,1.0,-2.3056963982526213e-07,3.3327872017707705e-08,4.4568319026438985e-06,0.0,-0.0,0.0 +1769682204,284277248,0.0,0.0,0.0,1.0,-3.3384292663640736e-08,-3.095634326655272e-07,5.948806119704386e-06,0.0,-0.0,0.0 +1769682204,312861184,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682204,347226368,0.0,0.0,0.0,1.0,-2.04233174372348e-07,-3.3823027933976846e-07,4.460706350073451e-06,-5.1158225687686354e-05,4.608896415447816e-05,0.002383194398134947 +1769682204,380374528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682204,414141952,0.0,0.0,0.0,1.0,-3.224094484721718e-07,-1.1100133860963979e-06,2.980356839543674e-06,0.15108337998390198,0.02150421217083931,0.00044212688226252794 +1769682204,449938176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682204,480552960,0.0,0.0,0.0,1.0,4.914873485972748e-08,-1.0836771480171592e-06,2.984089860547101e-06,0.0,-0.0,0.0 +1769682204,512913664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.1157825510017574e-05,4.608895324054174e-05,0.002383194398134947 +1769682204,549652480,0.0,0.0,0.0,1.0,-3.523773273172992e-09,-3.405608026696427e-07,2.9763402835669694e-06,0.0,-0.0,0.0 +1769682204,580603648,0.0,0.0,0.0,1.0,-1.8930286671547947e-07,-3.537289501309715e-07,2.9744740004389314e-06,0.0,-0.0,0.0 +1769682204,618385664,0.0,0.0,0.0,1.0,2.2812443489783618e-08,-7.121190606085293e-07,2.980215185743873e-06,0.0,-0.0,0.0 +1769682204,650309888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682204,681045760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682204,713627648,0.0,0.0,0.0,1.0,2.281243993706994e-08,-7.121190037651104e-07,2.9802154131175485e-06,0.0,-0.0,0.0 +1769682204,761677056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682204,780194560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682204,813369856,0.0,0.0,0.0,1.0,2.0859155824837217e-07,-6.989509984123288e-07,2.9820812414982356e-06,5.115731619298458e-05,-4.6089036914054304e-05,-0.002383194398134947 +1769682204,847959552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682204,881282304,0.0,0.0,0.0,1.0,2.2812461253352012e-08,-7.121191174519481e-07,2.9802154131175485e-06,0.0,-0.0,0.0 +1769682204,913455104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682204,948805120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682204,980887296,0.0,0.0,0.0,1.0,2.2812432831642582e-08,-7.121190606085293e-07,2.9802154131175485e-06,0.0,-0.0,0.0 +1769682205,13743104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682205,49545984,0.0,0.0,0.0,1.0,1.5591959368066455e-07,4.416537535689713e-08,2.974332119265455e-06,0.0,-0.0,0.0 +1769682205,81024768,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682205,115131136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682205,162513920,0.0,0.0,0.0,1.0,-2.9859510419782964e-08,3.099743040024805e-08,2.9724658361374168e-06,0.0,-0.0,0.0 +1769682205,182123264,0.0,0.0,0.0,1.0,9.236840270432367e-08,-1.984498254614664e-08,3.6178873870085226e-06,-5.115689054946415e-05,4.608917879522778e-05,0.002383194398134947 +1769682205,213227776,0.0,0.0,0.0,1.0,3.3691677003844234e-08,9.500776343429607e-08,2.328910113646998e-06,0.0,-0.0,0.0 +1769682205,266850816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682205,277556992,0.0,0.0,0.0,1.0,-2.9859570815915504e-08,3.099743750567541e-08,2.9724658361374168e-06,0.0,-0.0,0.0 +1769682205,331454720,0.0,0.0,0.0,1.0,-2.9859567263201825e-08,3.0997441058389086e-08,2.9724658361374168e-06,0.0,-0.0,0.0 +1769682205,348093184,0.0,0.0,0.0,1.0,-2.156386926799314e-07,1.7829531628876794e-08,2.9705995530093787e-06,0.0,-0.0,0.0 +1769682205,385018624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682205,413339648,0.0,0.0,0.0,1.0,-2.9859567263201825e-08,3.0997416189393334e-08,2.9724658361374168e-06,0.0,-0.0,0.0 +1769682205,496827392,0.0,0.0,0.0,1.0,-8.253111616340902e-08,7.741138574601791e-07,2.964716713904636e-06,-5.115709063829854e-05,4.608917151927017e-05,0.002383194398134947 +1769682205,516192000,0.0,0.0,0.0,1.0,-8.253111616340902e-08,7.741138574601791e-07,2.964716713904636e-06,0.0,-0.0,0.0 +1769682205,548017152,0.0,0.0,0.0,1.0,1.032480199114616e-07,7.87281749126123e-07,2.9665827696589986e-06,0.0,-0.0,0.0 +1769682205,579902976,0.0,0.0,0.0,1.0,-8.253111616340902e-08,7.741138574601791e-07,2.9647169412783114e-06,0.01074308343231678,-0.07551494985818863,0.0016910114791244268 +1769682205,614350848,0.0,0.0,0.0,1.0,1.0324804833317103e-07,7.87281749126123e-07,2.9665827696589986e-06,0.0,-0.0,0.0 +1769682205,660438528,0.0,0.0,0.0,1.0,-8.25310877416996e-08,7.74113914303598e-07,2.9647169412783114e-06,0.0,-0.0,0.0 +1769682205,668539648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682205,713044224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682205,747598080,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682205,782151936,0.0,0.0,0.0,1.0,-8.253111616340902e-08,7.741139711470169e-07,2.9647169412783114e-06,0.0,-0.0,0.0 +1769682205,814215936,0.0,0.0,0.0,1.0,-8.253110195255431e-08,7.741139711470169e-07,2.9647169412783114e-06,0.0,-0.0,0.0 +1769682205,848543232,0.0,0.0,0.0,1.0,-8.253110905798167e-08,7.741139711470169e-07,2.964717168651987e-06,0.0,-0.0,0.0 +1769682205,880548864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682205,914795264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682205,948289536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682205,980253952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682206,13656064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682206,58860544,0.0,0.0,0.0,1.0,1.0324804833317103e-07,7.87281749126123e-07,2.9665827696589986e-06,0.0,-0.0,0.0 +1769682206,414201856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682206,450503680,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682206,480825088,0.0,0.0,0.0,1.0,1.5591905366818537e-07,4.4165066270807074e-08,2.9743323466391303e-06,0.0,-0.0,0.0 +1769682206,514312448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682206,547335168,0.0,0.0,0.0,1.0,-2.986008240668525e-08,3.099749434909427e-08,2.9724662908847677e-06,0.0,-0.0,0.0 +1769682206,570462720,0.0,0.0,0.0,1.0,-2.986008240668525e-08,3.099749434909427e-08,2.9724662908847677e-06,0.0,-0.0,0.0 +1769682206,613355264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682206,650707712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682206,680594432,0.0,0.0,0.0,1.0,1.559190820898948e-07,4.416502719095661e-08,2.9743323466391303e-06,0.0,-0.0,0.0 +1769682206,714924800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682206,753233152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682206,780522240,0.0,0.0,0.0,1.0,-2.986007885397157e-08,3.0997497901807947e-08,2.972466518258443e-06,0.0,-0.0,0.0 +1769682206,813116416,0.0,0.0,0.0,1.0,-2.986008240668525e-08,3.099748724366691e-08,2.972466518258443e-06,0.0,-0.0,0.0 +1769682206,858145024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682206,881164544,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682206,913673216,0.0,0.0,0.0,1.0,1.5591906787904009e-07,4.4164973900251425e-08,2.9743325740128057e-06,0.0,-0.0,0.0 +1769682206,957926400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682206,979968768,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682207,447247872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682207,480645376,0.0,0.0,0.0,1.0,2.8902869075864146e-07,8.004488449842029e-07,2.9684499622817384e-06,0.0,-0.0,0.0 +1769682207,514481664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682207,548655872,0.0,0.0,0.0,1.0,1.0324950494577934e-07,7.872815217524476e-07,2.966583451780025e-06,0.0,-0.0,0.0 +1769682207,580645888,0.0,0.0,0.0,1.0,1.0324950494577934e-07,7.872814649090287e-07,2.966583451780025e-06,0.0,-0.0,0.0 +1769682207,615678208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682207,647806976,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.115847670822404e-05,-4.608945891959593e-05,-0.002383194398134947 +1769682207,680773632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.115852763992734e-05,4.608945164363831e-05,0.002383194398134947 +1769682207,713639168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.115858220960945e-05,-4.6089462557574734e-05,-0.002383194398134947 +1769682207,751612416,0.0,0.0,0.0,1.0,4.748078197280847e-07,8.136159408422827e-07,2.970316472783452e-06,0.0,-0.0,0.0 +1769682207,781714176,0.0,0.0,0.0,1.0,2.8902869075864146e-07,8.004487312973652e-07,2.968450189655414e-06,0.0,-0.0,0.0 +1769682207,814317312,0.0,0.0,0.0,1.0,1.0324951205120669e-07,7.872815785958664e-07,2.9665836791537004e-06,0.0,-0.0,0.0 +1769682207,848845568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682207,880267008,0.0,0.0,0.0,1.0,1.0324952626206141e-07,7.872814649090287e-07,2.9665836791537004e-06,0.0,-0.0,0.0 +1769682207,913544192,0.0,0.0,0.0,1.0,2.890287191803509e-07,8.004486744539463e-07,2.968449734908063e-06,0.0,-0.0,0.0 +1769682207,947030528,0.0,0.0,0.0,1.0,6.603198698940105e-08,3.517192226354382e-07,3.614062734413892e-06,0.0,-0.0,0.0 +1769682207,981445120,0.0,0.0,0.0,1.0,-2.986090663625873e-08,3.099762935221406e-08,2.972466518258443e-06,0.0,-0.0,0.0 +1769682208,14342400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682208,480090624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682208,514722816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682208,550673664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682208,581160448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682208,613378816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682208,647109888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682208,682750208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682208,714509056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682208,749421824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682208,781450496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682208,814075648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682208,848402432,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682208,881190656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682208,914659328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682208,949089024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682208,980747776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682209,14102528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682209,49723392,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682209,551373056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682209,582344448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682209,614155776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682209,648739328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682209,681752832,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682209,713648640,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682209,749011456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682209,784227840,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682209,815459328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682209,848587008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682209,880320256,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682209,914726656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682209,951537152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682209,983013376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682210,13873152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682210,63742720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682210,70483968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682210,614204928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682210,647528192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682210,681203968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682210,715659776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682210,752173312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682210,780635136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682210,814579968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682210,851224576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682210,881192960,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682210,913957888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682210,960615680,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682210,980291072,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682211,14420480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.115654130349867e-05,4.608980816556141e-05,0.002383194398134947 +1769682211,49052672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682211,82545920,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682211,113846272,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682211,147550208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682211,183842048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682211,214430208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682211,682818048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682211,715521024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.115591920912266e-05,-4.608984454534948e-05,-0.002383194398134947 +1769682211,765939968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682211,772672512,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682211,813689344,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682211,863396864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682211,870596352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682211,913689088,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682211,948365824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682211,981578752,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682212,15378688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682212,49292288,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682212,81242368,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682212,114604544,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682212,150271232,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682212,182477824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682212,214076160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682212,261332224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682212,281572352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682212,763267328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682212,769348352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682212,814838528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682212,848485632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682212,881574656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682212,914497024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682212,949743872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682212,980566784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682213,16034304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682213,60377856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682213,80902656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.115468957228586e-05,-4.6089648094493896e-05,-0.002383194398134947 +1769682213,114817792,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682213,160107008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682213,181013504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682213,214041856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682213,251510016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682213,284535296,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682213,852500480,0.0,0.0,0.0,1.0,-0.0013328943168744445,-0.03460562229156494,-0.0017352803843095899,-0.6239258646965027,0.06215896084904671,-0.14984378218650818 +1769682213,881910528,0.0,0.0,0.0,1.0,-0.00038092094473540783,-0.02360665611922741,-0.002037872327491641,-0.46200302243232727,0.007831873372197151,-0.1654626429080963 +1769682213,913990144,0.0,0.0,0.0,1.0,0.0006700223311781883,-0.013701433315873146,-0.0025026779621839523,-0.7641828656196594,-0.03537118434906006,-0.16789667308330536 +1769682213,960889344,0.0,0.0,0.0,1.0,0.0011709383688867092,-0.003744096029549837,-0.0030922547448426485,-0.6026344895362854,-0.08897766470909119,-0.1434098184108734 +1769682213,969658368,0.0,0.0,0.0,1.0,0.001268660882487893,-0.00022686264128424227,-0.003333750180900097,-0.7862903475761414,0.11630097776651382,-0.12780536711215973 +1769682214,15030016,0.0,0.0,0.0,1.0,0.0012166957603767514,0.003801289713010192,-0.0037533342838287354,-0.7650666236877441,-0.034216251224279404,-0.09146008640527725 +1769682214,50361088,0.0,0.0,0.0,1.0,0.0009687258861958981,0.004998783115297556,-0.00411904975771904,-0.30169159173965454,-0.04394002631306648,-0.036027319729328156 +1769682214,81829632,0.0,0.0,0.0,1.0,0.000651398382615298,0.004748926032334566,-0.004368472844362259,-0.6364968419075012,0.13963188230991364,-0.019552070647478104 +1769682214,114897408,0.0,0.0,0.0,1.0,0.00038407096872106194,0.003987985197454691,-0.004607532173395157,-0.604182243347168,-0.08670307695865631,-0.0007088687270879745 +1769682214,150551040,0.0,0.0,0.0,1.0,2.654320269357413e-06,0.0024731315206736326,-0.004910718649625778,-0.593542754650116,-0.16196458041667938,0.01982954889535904 +1769682214,181376000,0.0,0.0,0.0,1.0,-0.00026147550670430064,0.0013995853951200843,-0.0051290192641317844,-0.3132476210594177,0.03253732621669769,0.024268383160233498 +1769682214,215461376,0.0,0.0,0.0,1.0,-0.0004648249305319041,0.00021528889192268252,-0.005353997461497784,-0.31336721777915955,0.03266586735844612,0.03379771485924721 +1769682214,254120448,0.0,0.0,0.0,1.0,-0.00075545534491539,-0.0016319729620590806,-0.0056998697109520435,-0.46433159708976746,0.010699108242988586,0.027649782598018646 +1769682214,281085184,0.0,0.0,0.0,1.0,-0.0009165640221908689,-0.0026685423217713833,-0.005960182286798954,-0.6152864694595337,-0.011306742206215858,0.02153243124485016 +1769682214,314329600,0.0,0.0,0.0,1.0,-0.0010210908949375153,-0.00345710595138371,-0.006239684764295816,-0.6261431574821472,0.06398367881774902,0.015288772992789745 +1769682214,362276096,0.0,0.0,0.0,1.0,-0.0012059600558131933,-0.00289446790702641,-0.006675149314105511,-0.776603639125824,0.041032738983631134,-0.03364528715610504 +1769682214,370404864,0.0,0.0,0.0,1.0,-0.0012727233115583658,-0.0017477415967732668,-0.0068314457312226295,-0.4856410622596741,0.16039368510246277,-0.025300849229097366 +1769682214,414927616,0.0,0.0,0.0,1.0,-0.001072006649337709,0.001713159610517323,-0.006996124982833862,-0.625572681427002,0.06258946657180786,-0.03704738989472389 +1769682214,448020480,0.0,0.0,0.0,1.0,-0.00100320007186383,0.0050460402853786945,-0.007057578768581152,-0.496320515871048,0.2349914014339447,-0.06026621535420418 +1769682214,950551040,0.0,0.0,0.0,1.0,-0.000937566626816988,-0.004122212529182434,-0.010918901301920414,-0.7652089595794678,-0.038638390600681305,-0.062189631164073944 +1769682214,988251392,0.0,0.0,0.0,1.0,-0.0007886664243414998,-0.0020940275862812996,-0.01124725304543972,-0.7653501629829407,-0.03863862156867981,-0.04782569035887718 +1769682215,15065344,0.0,0.0,0.0,1.0,-0.0006882635061629117,-0.0004222061834298074,-0.011583682149648666,-0.7652885317802429,-0.03898600488901138,-0.05257229879498482 +1769682215,49886976,0.0,0.0,0.0,1.0,-0.000699173950124532,0.0005782590014860034,-0.012058292515575886,-0.3356984257698059,0.1803511083126068,-0.02575288526713848 +1769682215,81252608,0.0,0.0,0.0,1.0,-0.0006289560114964843,0.0012075448175892234,-0.012399613857269287,-0.7542141675949097,-0.11442111432552338,-0.015400144271552563 +1769682215,115252736,0.0,0.0,0.0,1.0,-0.000711113796569407,0.0016487326938658953,-0.012735605239868164,-0.6261482238769531,0.058952249586582184,-0.021917562931776047 +1769682215,151410944,0.0,0.0,0.0,1.0,-0.0006741333054378629,0.002315776189789176,-0.013152018189430237,-0.6147220730781555,-0.01674242690205574,-0.01813589408993721 +1769682215,181591040,0.0,0.0,0.0,1.0,-0.0007014073198661208,0.0032161944545805454,-0.013421320356428623,-0.6262238621711731,0.058418963104486465,-0.019635599106550217 +1769682215,214305280,0.0,0.0,0.0,1.0,-0.0007547374698333442,0.0035563718993216753,-0.01371673122048378,-0.7656822800636292,-0.04009627923369408,-0.005175989121198654 +1769682215,258866432,0.0,0.0,0.0,1.0,-0.000842719164211303,0.0022360943257808685,-0.014200789853930473,-0.9166772961616516,-0.06338436901569366,0.012561468407511711 +1769682215,281754368,0.0,0.0,0.0,1.0,-0.0009971554391086102,0.001121298992075026,-0.014606209471821785,-1.0674561262130737,-0.08704157173633575,0.011270174756646156 +1769682215,315438592,0.0,0.0,0.0,1.0,-0.0010847540106624365,0.0003555464791134,-0.015031247399747372,-0.6266660094261169,0.05780210345983505,0.011181369423866272 +1769682215,348140544,0.0,0.0,0.0,1.0,-0.0012196027673780918,-0.0005836899508722126,-0.0156474057585001,-0.9398686289787292,0.08583343029022217,0.00010127667337656021 +1769682215,383158528,0.0,0.0,0.0,1.0,-0.0012715780176222324,-0.000894172873813659,-0.01612766645848751,-0.4642590284347534,0.00527329184114933,0.016273807734251022 +1769682215,416108800,0.0,0.0,0.0,1.0,-0.0012687741545960307,-0.001035082619637251,-0.016619492322206497,-0.7538979053497314,-0.117618627846241,0.005692929960787296 +1769682215,449895936,0.0,0.0,0.0,1.0,-0.001342089264653623,-0.0008997860131785274,-0.017285894602537155,-0.7773223519325256,0.032381799072027206,-0.009053485468029976 +1769682215,481461504,0.0,0.0,0.0,1.0,-0.001341892872005701,-0.000688179163262248,-0.0177980437874794,-0.6383981108665466,0.13094854354858398,-0.01636977307498455 +1769682215,515430656,0.0,0.0,0.0,1.0,-0.001409523538313806,-0.00045572390081360936,-0.018319260329008102,-0.626594066619873,0.05529584735631943,-0.012551641091704369 +1769682216,15818240,0.0,0.0,0.0,1.0,-0.0018802249105647206,0.0013047632528468966,-0.02809607796370983,-0.7648913860321045,-0.05269535630941391,-0.007912594825029373 +1769682216,55197184,0.0,0.0,0.0,1.0,-0.0026237929705530405,0.0009315616334788501,-0.029013125225901604,-0.9279491901397705,-0.0043260566890239716,-0.022544994950294495 +1769682216,82661120,0.0,0.0,0.0,1.0,-0.0030260030180215836,0.0007844464271329343,-0.0296845193952322,-0.6530621647834778,0.19698262214660645,-0.022620031610131264 +1769682216,114466304,0.0,0.0,0.0,1.0,-0.0028545644599944353,0.0007468010298907757,-0.030225325375795364,-0.7517356276512146,-0.13010279834270477,-0.006651660427451134 +1769682216,150411776,0.0,0.0,0.0,1.0,-0.0017751384293660522,0.0002509830810595304,-0.030750857666134834,-0.5162244439125061,0.29691624641418457,-0.02499866671860218 +1769682216,173456896,0.0,0.0,0.0,1.0,-0.0013657251838594675,-0.00015436256944667548,-0.03103136643767357,-0.6273280382156372,0.04490896314382553,-0.019935784861445427 +1769682216,217024512,0.0,0.0,0.0,1.0,-0.0009735539788380265,-0.0005321307689882815,-0.03166875243186951,-0.64061439037323,0.11924763768911362,-0.02125534787774086 +1769682216,248967424,0.0,0.0,0.0,1.0,-0.0007254116935655475,-0.0007341448799706995,-0.03240233659744263,-0.7910830974578857,0.0918608009815216,-0.015414879657328129 +1769682216,282017792,0.0,0.0,0.0,1.0,-0.0005869264132343233,-0.0008364543318748474,-0.0330052375793457,-0.7912284731864929,0.0911540761590004,-0.010626459494233131 +1769682216,314620416,0.0,0.0,0.0,1.0,-0.000417733914218843,-0.0009365203441120684,-0.03364573046565056,-0.6412244439125061,0.117449551820755,-0.0021276716142892838 +1769682216,352665856,0.0,0.0,0.0,1.0,-0.00036987161729484797,-0.0010426228400319815,-0.03456488624215126,-0.49127086997032166,0.14379191398620605,0.00160287506878376 +1769682216,381427200,0.0,0.0,0.0,1.0,-0.0004675575182773173,-0.0012022292939946055,-0.03534264117479324,-0.6687396168708801,0.2658858001232147,-0.011874081566929817 +1769682216,414572032,0.0,0.0,0.0,1.0,-0.0004634243668988347,-0.0012337095104157925,-0.0361691415309906,-0.641631543636322,0.11520611494779587,-0.0020514209754765034 +1769682216,452051712,0.0,0.0,0.0,1.0,-0.0004921245854347944,-0.001145948306657374,-0.03731866180896759,-0.4777994751930237,0.06682392209768295,-0.008931100368499756 +1769682216,482475776,0.0,0.0,0.0,1.0,-0.0005956458626314998,-0.0010101532097905874,-0.03822978213429451,-0.7918316721916199,0.08548734337091446,-0.012829596176743507 +1769682216,514237952,0.0,0.0,0.0,1.0,-0.0006722211255691946,-0.000891759293153882,-0.03914133459329605,-0.7919036746025085,0.08452828228473663,-0.015189185738563538 +1769682216,561804800,0.0,0.0,0.0,1.0,-0.0006215281900949776,-0.0008773647132329643,-0.0403592474758625,-0.3705212473869324,0.3181114196777344,-0.013914653100073338 +1769682216,569531136,0.0,0.0,0.0,1.0,-0.0006382535211741924,-0.0008548222249373794,-0.04098747298121452,-0.6422231793403625,0.11108564585447311,-0.011472485959529877 +1769682217,115889664,0.0,0.0,0.0,1.0,-0.004193434026092291,-0.002274434780701995,-0.06281445175409317,-0.6776812672615051,0.24213889241218567,-0.013095621950924397 +1769682217,150471936,0.0,0.0,0.0,1.0,-0.004037827253341675,-0.002263525268062949,-0.06425255537033081,-0.6452746987342834,0.09138428419828415,-0.015399022027850151 +1769682217,181701632,0.0,0.0,0.0,1.0,-0.0039969985373318195,-0.0022350812796503305,-0.06531225144863129,-0.49656882882118225,0.1234419196844101,-0.01179087907075882 +1769682217,215188224,0.0,0.0,0.0,1.0,-0.004042886663228273,-0.0022258476819843054,-0.06635569781064987,-0.6792641878128052,0.23778076469898224,-0.010461707599461079 +1769682217,251087360,0.0,0.0,0.0,1.0,-0.004028938245028257,-0.002283945679664612,-0.06769368797540665,-0.62896728515625,0.01283989567309618,-0.006919211708009243 +1769682217,282400256,0.0,0.0,0.0,1.0,-0.004037609323859215,-0.0023274593986570835,-0.06870696693658829,-0.8462749123573303,0.27471041679382324,-0.00542342197149992 +1769682217,315241216,0.0,0.0,0.0,1.0,-0.004026728216558695,-0.002396490192040801,-0.069705531001091,-0.4976140260696411,0.1190432608127594,-0.013963745906949043 +1769682217,352760832,0.0,0.0,0.0,1.0,-0.00397402374073863,-0.0024254564195871353,-0.0709431990981102,-0.7165683507919312,0.3797928988933563,-0.0075671374797821045 +1769682217,383354624,0.0,0.0,0.0,1.0,-0.003987970296293497,-0.002442772965878248,-0.07183123379945755,-0.6644443273544312,0.1556394249200821,-0.0017744945362210274 +1769682217,416128768,0.0,0.0,0.0,1.0,-0.004015766084194183,-0.002471146173775196,-0.07266025245189667,-0.646940290927887,0.07999051362276077,-0.0029968200251460075 +1769682217,449959680,0.0,0.0,0.0,1.0,-0.004059385508298874,-0.0024976918939501047,-0.07376416772603989,-0.6831395626068115,0.2262263298034668,-0.014614498242735863 +1769682217,473621504,0.0,0.0,0.0,1.0,-0.004203638527542353,-0.0024494596291333437,-0.07436089217662811,-0.6654064059257507,0.15120120346546173,-0.006337602157145739 +1769682217,514808832,0.0,0.0,0.0,1.0,-0.005465354770421982,-0.0018074511317536235,-0.0755847692489624,-0.6661295890808105,0.14950931072235107,0.019972164183855057 +1769682217,548225024,0.0,0.0,0.0,1.0,-0.0068368748761713505,-0.0007824270869605243,-0.07696536183357239,-0.5370721220970154,0.2585192322731018,0.008187208324670792 +1769682217,582387712,0.0,0.0,0.0,1.0,-0.007633517496287823,-0.0002679878380149603,-0.07815227657556534,-0.5188347101211548,0.1832408756017685,0.0021201707422733307 +1769682217,615708160,0.0,0.0,0.0,1.0,-0.007805646397173405,0.0014978647232055664,-0.07943757623434067,-0.38938888907432556,0.2927378714084625,-0.09546949714422226 +1769682217,649132800,0.0,0.0,0.0,1.0,-0.007594882510602474,0.0038523171097040176,-0.08114250004291534,-0.5380733609199524,0.25321537256240845,-0.08942762762308121 +1769682217,683330048,0.0,0.0,0.0,1.0,-0.0076383985579013824,0.0050004408694803715,-0.08250948041677475,-0.5389125347137451,0.25213220715522766,-0.06799004971981049 +1769682217,715337216,0.0,0.0,0.0,1.0,-0.006749232765287161,0.005245557986199856,-0.08390974253416061,-0.5399210453033447,0.25115734338760376,-0.03226238489151001 +1769682218,214541312,0.0,0.0,0.0,1.0,-0.0037543936632573605,-0.0012912364909425378,-0.10781178623437881,-0.4290660619735718,0.34399697184562683,-0.019766632467508316 +1769682218,260973312,0.0,0.0,0.0,1.0,-0.0035920024383813143,-0.0015457968693226576,-0.10969684273004532,-0.2853858172893524,0.38891899585723877,-0.013381593860685825 +1769682218,281366784,0.0,0.0,0.0,1.0,-0.0035472542513161898,-0.0015231590950861573,-0.11108265072107315,-0.4082346260547638,0.26823127269744873,-0.006942370440810919 +1769682218,314480128,0.0,0.0,0.0,1.0,-0.003503852291032672,-0.00146023731213063,-0.11240790784358978,-0.5542381405830383,0.21922019124031067,0.005869513377547264 +1769682218,348481536,0.0,0.0,0.0,1.0,-0.0036799204535782337,-0.001113654812797904,-0.11417663842439651,-0.3141324520111084,0.4581611752510071,0.002732128370553255 +1769682218,382337280,0.0,0.0,0.0,1.0,-0.003897508606314659,-0.0010168526787310839,-0.11560539156198502,-0.411435604095459,0.26366785168647766,0.0075095598585903645 +1769682218,415413504,0.0,0.0,0.0,1.0,-0.004098161123692989,-0.00084016373148188,-0.11708853393793106,-0.4370137155056,0.334397554397583,0.00443456694483757 +1769682218,449421824,0.0,0.0,0.0,1.0,-0.004361055791378021,-0.000723989331163466,-0.11916910856962204,-0.29443246126174927,0.38238459825515747,0.0036666938103735447 +1769682218,482745344,0.0,0.0,0.0,1.0,-0.004661500919610262,-0.0007485841633751988,-0.12083248794078827,-0.6090564131736755,0.3521345555782318,0.0046843551099300385 +1769682218,515256064,0.0,0.0,0.0,1.0,-0.004980724770575762,-0.0007374347769655287,-0.12266411632299423,-0.32269760966300964,0.4520920515060425,-0.0016788714565336704 +1769682218,550416384,0.0,0.0,0.0,1.0,-0.0041365851648151875,-0.00029618979897350073,-0.12485301494598389,-0.12970077991485596,0.35884130001068115,0.008489996194839478 +1769682218,581934336,0.0,0.0,0.0,1.0,-0.004001809284090996,5.5411801440641284e-05,-0.12666717171669006,-0.30057746171951294,0.37764203548431396,0.008674678392708302 +1769682218,614966784,0.0,0.0,0.0,1.0,-0.003728407435119152,0.0002409525914117694,-0.12849223613739014,-0.21182866394519806,0.5725230574607849,0.008951033465564251 +1769682218,659201536,0.0,0.0,0.0,1.0,-0.005094244610518217,-0.0009343720157630742,-0.13152986764907837,-0.47424814105033875,0.39286166429519653,0.054234154522418976 +1769682218,681180928,0.0,0.0,0.0,1.0,-0.005955694243311882,-0.0017426209524273872,-0.13369423151016235,-0.3059042990207672,0.3738365173339844,0.0422423854470253 +1769682218,715095552,0.0,0.0,0.0,1.0,-0.00661001680418849,-0.002365994732826948,-0.135780468583107,-0.3071989119052887,0.3725086450576782,0.025646328926086426 +1769682218,761345536,0.0,0.0,0.0,1.0,-0.007188319228589535,-0.0028856301214545965,-0.13837821781635284,-0.22252629697322845,0.568442165851593,0.009471419267356396 +1769682218,768659968,0.0,0.0,0.0,1.0,-0.007438205182552338,-0.0030269359704107046,-0.13960710167884827,-0.1960875689983368,0.4968392550945282,0.007776565849781036 +1769682219,282203136,0.0,0.0,0.0,1.0,-0.00492990855127573,0.004080926068127155,-0.1634616106748581,-0.06323006749153137,0.4783520996570587,-0.01472544763237238 +1769682219,315528192,0.0,0.0,0.0,1.0,-0.0036542818415910006,0.0035969887394458055,-0.16476553678512573,-0.029999537393450737,0.7508179545402527,-0.018744299188256264 +1769682219,352013056,0.0,0.0,0.0,1.0,-0.003078474197536707,0.0026158096734434366,-0.16649849712848663,-0.000789949088357389,0.6824122071266174,-0.015919188037514687 +1769682219,381622016,0.0,0.0,0.0,1.0,-0.002886640839278698,0.002036471152678132,-0.16792403161525726,0.06469164788722992,0.546345055103302,0.0015196023741737008 +1769682219,417160192,0.0,0.0,0.0,1.0,-0.002899307757616043,0.0015842737630009651,-0.1694357693195343,-0.13973279297351837,0.2713509500026703,0.008169429376721382 +1769682219,452340736,0.0,0.0,0.0,1.0,-0.0027516193222254515,0.001177451340481639,-0.1714814305305481,0.057825807482004166,0.5470286011695862,0.030243294313549995 +1769682219,481389568,0.0,0.0,0.0,1.0,-0.0025433737318962812,0.0009053086396306753,-0.17301999032497406,-0.2501254975795746,0.4719046950340271,0.007214751094579697 +1769682219,514671104,0.0,0.0,0.0,1.0,-0.0019055467564612627,0.0005050553008913994,-0.17449070513248444,-0.2885916531085968,0.5378312468528748,0.0021435455419123173 +1769682219,559576832,0.0,0.0,0.0,1.0,-0.0015260281506925821,6.594390288228169e-05,-0.1763928085565567,-0.29227346181869507,0.5358046889305115,-0.004975600633770227 +1769682219,581442560,0.0,0.0,0.0,1.0,-0.0014489670284092426,-0.00012698842328973114,-0.17786958813667297,-0.2583172619342804,0.46744677424430847,0.0025215321220457554 +1769682219,615535104,0.0,0.0,0.0,1.0,-0.0013507541734725237,-0.0002585865731816739,-0.1793622076511383,-0.37260696291923523,0.6657904386520386,0.003973177168518305 +1769682219,649675776,0.0,0.0,0.0,1.0,-0.0009955493733286858,-0.00037371297366917133,-0.18137702345848083,0.0010028474498540163,0.6150816679000854,0.008663216605782509 +1769682219,686424064,0.0,0.0,0.0,1.0,-0.0007318719290196896,-0.0009215506142936647,-0.1829681545495987,-0.1729498952627182,0.6049301624298096,0.03035150095820427 +1769682219,714955008,0.0,0.0,0.0,1.0,-0.0011255333665758371,-0.0010650934418663383,-0.18442799150943756,0.2959713339805603,0.7029435634613037,0.03416554629802704 +1769682219,767133952,0.0,0.0,0.0,1.0,-0.001504996558651328,-0.0011243419721722603,-0.18631614744663239,-0.1416379064321518,0.5370742082595825,0.01641681231558323 +1769682219,773274624,0.0,0.0,0.0,1.0,-0.0017710537649691105,-0.001101433066651225,-0.18724794685840607,-0.14358612895011902,0.5365538001060486,0.011670514941215515 +1769682219,814768640,0.0,0.0,0.0,1.0,-0.0019866859074681997,-0.0010734725510701537,-0.18901437520980835,-0.0966239720582962,0.7451595067977905,0.008214278146624565 +1769682220,359399680,0.0,0.0,0.0,1.0,0.001207544468343258,0.0007535341428592801,-0.21601425111293793,-0.13074807822704315,0.6697492599487305,0.0016837208531796932 +1769682220,381934848,0.0,0.0,0.0,1.0,0.0017398531781509519,0.0009994424181059003,-0.21741034090518951,-0.1584376096725464,0.6990097761154175,-0.010406779125332832 +1769682220,415100160,0.0,0.0,0.0,1.0,0.0022214967757463455,0.0011831664014607668,-0.21875527501106262,-0.09083238989114761,0.8524243831634521,0.0007051471620798111 +1769682220,448713984,0.0,0.0,0.0,1.0,0.002594508696347475,0.0013904403895139694,-0.22046874463558197,-0.16920001804828644,0.6964715123176575,-0.005763388704508543 +1769682220,473122816,0.0,0.0,0.0,1.0,0.002728193998336792,0.0015171216800808907,-0.22134003043174744,0.0885029062628746,0.8586341738700867,0.0028940225020051003 +1769682220,515689984,0.0,0.0,0.0,1.0,0.0027923083398491144,0.0016883352072909474,-0.2230457067489624,0.05648541823029518,0.8887432217597961,0.005038843490183353 +1769682220,549412352,0.0,0.0,0.0,1.0,0.0028758763801306486,0.0017910171300172806,-0.2247486263513565,-0.13540855050086975,0.6342360377311707,-0.012833332642912865 +1769682220,581809664,0.0,0.0,0.0,1.0,0.002535229781642556,0.001567572122439742,-0.2260543704032898,-0.04854346439242363,0.7614367604255676,-0.008776959031820297 +1769682220,615325440,0.0,0.0,0.0,1.0,0.002193486550822854,0.0014029421145096421,-0.22734996676445007,-0.028798583894968033,0.7322382926940918,-0.0039032730273902416 +1769682220,648875776,0.0,0.0,0.0,1.0,0.0015439309645444155,0.001508162822574377,-0.22915217280387878,0.028635703027248383,0.8902475237846375,-0.023857703432440758 +1769682220,682469632,0.0,0.0,0.0,1.0,0.0011968391481786966,0.0016370391240343451,-0.23047420382499695,0.23781156539916992,0.8784307241439819,-0.00942173320800066 +1769682220,714934016,0.0,0.0,0.0,1.0,0.0009232340380549431,0.001723326276987791,-0.23186743259429932,0.06726117432117462,0.8339056968688965,0.0050268350169062614 +1769682220,750099712,0.0,0.0,0.0,1.0,0.0005513892974704504,0.0015904089668765664,-0.23412854969501495,-0.1646444946527481,0.6272306442260742,0.010758060030639172 +1769682220,782114304,0.0,0.0,0.0,1.0,0.0001043716911226511,0.0014301815535873175,-0.23585309088230133,-0.057972777634859085,0.7303752303123474,0.02694566175341606 +1769682220,816260608,0.0,0.0,0.0,1.0,-0.000160514609888196,0.0013891098788008094,-0.2374044805765152,-0.010512393899261951,0.6747010350227356,0.02252337709069252 +1769682220,861400832,0.0,0.0,0.0,1.0,-0.0001187552697956562,0.0013414632994681597,-0.23921586573123932,-0.20594079792499542,0.6505723595619202,0.0034085658844560385 +1769682220,870354688,0.0,0.0,0.0,1.0,-9.164726361632347e-05,0.0013686122838407755,-0.24000002443790436,-0.07330615073442459,0.7291074395179749,0.0007215052610263228 +1769682220,915350528,0.0,0.0,0.0,1.0,-0.00012346729636192322,0.0016285594319924712,-0.2413301169872284,0.18954631686210632,0.8899965286254883,0.0025248106103390455 +1769682220,948540672,0.0,0.0,0.0,1.0,8.44856258481741e-05,0.0017631049267947674,-0.24234643578529358,0.15350833535194397,0.9184280037879944,0.019046997651457787 +1769682221,384669952,0.0,0.0,0.0,1.0,0.0037271573673933744,-2.0273408154025674e-05,-0.2522755265235901,0.085309699177742,0.9059682488441467,-0.0003096577129326761 +1769682221,416197376,0.0,0.0,0.0,1.0,0.0033343613613396883,0.00034042162587866187,-0.25333118438720703,0.07843172550201416,0.9065896272659302,-0.00040085799992084503 +1769682221,453061632,0.0,0.0,0.0,1.0,0.0029943983536213636,0.0006978483870625496,-0.2547938823699951,0.12980009615421295,0.8610024452209473,0.002300076186656952 +1769682221,483143936,0.0,0.0,0.0,1.0,0.0029123856220394373,0.000953210168518126,-0.2559100091457367,0.12319593876600266,0.8619723916053772,0.0022264490835368633 +1769682221,515273984,0.0,0.0,0.0,1.0,0.0030759312212467194,0.0010785909835249186,-0.25701287388801575,0.08594977855682373,0.8856189250946045,-0.0028358169365674257 +1769682221,549494016,0.0,0.0,0.0,1.0,0.0032353177666664124,0.001077387947589159,-0.2583675682544708,0.018076414242386818,0.7404274940490723,0.007345087360590696 +1769682221,581816320,0.0,0.0,0.0,1.0,0.0034105731174349785,0.0009674580069258809,-0.2593044340610504,0.0697508454322815,0.8869362473487854,0.011273645795881748 +1769682221,615223552,0.0,0.0,0.0,1.0,0.003537947777658701,0.0008402090752497315,-0.26016002893447876,-0.02460598759353161,0.7625579237937927,-0.00018976221326738596 +1769682221,654693632,0.0,0.0,0.0,1.0,0.003782278159633279,0.000621446524746716,-0.261282354593277,0.08503583073616028,0.8664987683296204,0.011285399086773396 +1769682221,682871808,0.0,0.0,0.0,1.0,0.0037927995435893536,0.00039581910823471844,-0.2621382772922516,0.16353487968444824,0.9937095046043396,0.00822613574564457 +1769682221,715100416,0.0,0.0,0.0,1.0,0.003948963712900877,0.00022769550560042262,-0.26295971870422363,0.10321995615959167,0.8466807007789612,0.008942827582359314 +1769682221,750121984,0.0,0.0,0.0,1.0,0.0038997670635581017,-2.450568717904389e-05,-0.26405051350593567,0.17713715136051178,0.9757811427116394,0.015347806736826897 +1769682221,784613632,0.0,0.0,0.0,1.0,0.003762188134714961,-0.00011007314606104046,-0.2648775577545166,0.16935819387435913,0.977143406867981,0.017621133476495743 +1769682221,815586304,0.0,0.0,0.0,1.0,0.003736641025170684,-0.00017627984925638884,-0.2656446695327759,0.12936340272426605,0.9987552165985107,0.0053445142693817616 +1769682221,851360000,0.0,0.0,0.0,1.0,0.00393114797770977,-0.00032148571335710585,-0.26650914549827576,0.10436616837978363,0.8300878405570984,0.003968250006437302 +1769682221,881757440,0.0,0.0,0.0,1.0,0.004238085821270943,-0.00047515222104266286,-0.26702389121055603,0.17612247169017792,0.9617586731910706,0.007951756939291954 +1769682221,917550848,0.0,0.0,0.0,1.0,0.003932359162718058,-0.0006009858334437013,-0.2675897777080536,0.12387142330408096,0.8122772574424744,0.008781601674854755 +1769682221,958086400,0.0,0.0,0.0,1.0,0.003934066742658615,0.0007013106951490045,-0.26847708225250244,0.0589548759162426,1.0219495296478271,-0.005006843246519566 +1769682222,483210240,0.0,0.0,0.0,1.0,0.005244850181043148,0.0016772621311247349,-0.25767990946769714,0.07144726067781448,0.7933826446533203,-0.006774095818400383 +1769682222,515293184,0.0,0.0,0.0,1.0,0.0054374514147639275,0.0024257898330688477,-0.2558433711528778,0.00960115622729063,0.6518018841743469,-0.001135439146310091 +1769682222,549235200,0.0,0.0,0.0,1.0,0.0059965443797409534,0.002244662493467331,-0.2533997595310211,0.1638842225074768,0.7536975145339966,0.024900181218981743 +1769682222,582323200,0.0,0.0,0.0,1.0,0.0059999385848641396,0.0006411445210687816,-0.25186222791671753,0.30011239647865295,1.0276638269424438,0.03492971882224083 +1769682222,617937920,0.0,0.0,0.0,1.0,0.005956728011369705,-0.0014249514788389206,-0.2506382167339325,0.1685204952955246,0.9124672412872314,0.03991151601076126 +1769682222,653165056,0.0,0.0,0.0,1.0,0.005856436677277088,-0.0026864379178732634,-0.24885393679141998,0.05817004665732384,0.626230001449585,0.03713547810912132 +1769682222,681587712,0.0,0.0,0.0,1.0,0.006507144309580326,-0.0021012190263718367,-0.2474994957447052,0.15268361568450928,0.9153162837028503,0.032345645129680634 +1769682222,715181312,0.0,0.0,0.0,1.0,0.007339807227253914,-0.0012760157696902752,-0.24600975215435028,0.1336294561624527,0.7596451044082642,0.028881823644042015 +1769682222,758742272,0.0,0.0,0.0,1.0,0.008218815550208092,-0.0003974016581196338,-0.24377815425395966,0.12639304995536804,0.7610059976577759,0.009563707746565342 +1769682222,772212480,0.0,0.0,0.0,1.0,0.008645138703286648,0.0008359908824786544,-0.2423841953277588,0.08686540275812149,0.7734131217002869,-0.038584087044000626 +1769682222,814968064,0.0,0.0,0.0,1.0,0.009568747133016586,0.0036596297286450863,-0.239053413271904,0.143522247672081,0.5945456624031067,-0.010299966670572758 +1769682222,850885632,0.0,0.0,0.0,1.0,0.009919323958456516,0.004609914030879736,-0.2355833351612091,0.2178829461336136,0.7311651110649109,0.002809833502396941 +1769682222,883919872,0.0,0.0,0.0,1.0,0.009570986032485962,0.0033690063282847404,-0.23337596654891968,0.29175999760627747,0.8685219883918762,0.018292419612407684 +1769682222,916107776,0.0,0.0,0.0,1.0,0.008841801434755325,0.0005659924354404211,-0.23164352774620056,0.363901287317276,1.0069749355316162,0.021784203127026558 +1769682222,948922112,0.0,0.0,0.0,1.0,0.007768007926642895,-0.0023308221716433764,-0.22989146411418915,0.1606646478176117,0.5888212323188782,0.0036472678184509277 +1769682222,982191616,0.0,0.0,0.0,1.0,0.006649942137300968,-0.003290593856945634,-0.2287837713956833,0.15676704049110413,0.589950680732727,-0.010792715474963188 +1769682223,16723456,0.0,0.0,0.0,1.0,0.005888690240681171,-0.0037024717312306166,-0.22767587006092072,0.07762405276298523,0.4527965188026428,-0.009747487492859364 +1769682223,48747008,0.0,0.0,0.0,1.0,0.0055163465440273285,-0.0034948489628732204,-0.22608071565628052,0.03625384718179703,0.6199582815170288,-0.007395141292363405 +1769682223,83129856,0.0,0.0,0.0,1.0,0.005090647377073765,-0.0031441550236195326,-0.22486825287342072,0.06924223899841309,0.6112625002861023,-0.01667025312781334 +1769682223,114959360,0.0,0.0,0.0,1.0,0.005012644454836845,-0.002696637064218521,-0.2234555184841156,-0.04404781758785248,0.4805266857147217,-0.00871008075773716 +1769682223,149073408,0.0,0.0,0.0,1.0,0.005444953218102455,-0.0020791273564100266,-0.22131426632404327,0.05586306005716324,0.7694774866104126,-0.007009880617260933 +1769682223,181595392,0.0,0.0,0.0,1.0,0.005978054367005825,-0.0013334692921489477,-0.2195037305355072,0.0557207390666008,0.6126574873924255,-0.024166539311408997 +1769682223,215761152,0.0,0.0,0.0,1.0,0.007108238525688648,-0.0005216628778725863,-0.21762357652187347,-0.06598754972219467,0.7938427925109863,-0.0322159007191658 +1769682223,249556480,0.0,0.0,0.0,1.0,0.007228114642202854,0.0004292100202292204,-0.21515502035617828,-0.13359498977661133,0.4940487742424011,-0.005074919201433659 +1769682223,282949888,0.0,0.0,0.0,1.0,0.007459609303623438,0.0007033186266198754,-0.2134062945842743,-0.06177029386162758,0.4785661995410919,-0.01637957990169525 +1769682223,315197696,0.0,0.0,0.0,1.0,0.007508797571063042,0.0007885349914431572,-0.21157105267047882,-0.04583444818854332,0.7850832343101501,0.0009425666648894548 +1769682223,349733888,0.0,0.0,0.0,1.0,0.004693504422903061,-0.0006679070647805929,-0.20929454267024994,-0.020515412092208862,0.3139423429965973,-0.044994596391916275 +1769682235,251281408,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-3.469299554126337e-05,2.8886790460092016e-05,0.0023837615735828876 +1769682235,284360192,0.0,0.0,0.0,1.0,-2.5088178290388896e-07,-1.6368252886422852e-07,7.710929821769241e-06,0.0,-0.0,0.0 +1769682235,307036672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-3.4692940971581265e-05,2.8886775908176787e-05,0.0023837615735828876 +1769682235,350732032,0.0,0.0,0.0,1.0,-2.3778613922331715e-07,-1.3930574027654075e-07,9.090326784644276e-06,0.0,-0.0,0.0 +1769682235,383137024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682235,417087744,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682235,454083584,0.0,0.0,0.0,1.0,-4.4682477096102957e-07,-2.4171222889890487e-07,7.70998030930059e-06,0.0,-0.0,0.0 +1769682235,470484480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682235,516899584,0.0,0.0,0.0,1.0,4.62890312746822e-08,-3.8027681625862897e-07,9.093850167118944e-06,-3.4692751796683297e-05,2.8886723157484084e-05,0.0023837615735828876 +1769682235,550847488,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 +1769682235,570887680,0.0,0.0,0.0,1.0,1.7121331552516494e-07,-2.4200451775868714e-07,9.09392019821098e-06,3.469271177891642e-05,-2.8886719519505277e-05,-0.0023837615735828876 +1769682235,616463616,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 diff --git a/applications/tests/test_autoware/src/lib.rs b/applications/tests/test_autoware/src/lib.rs new file mode 100644 index 000000000..4ea886cb6 --- /dev/null +++ b/applications/tests/test_autoware/src/lib.rs @@ -0,0 +1,1121 @@ +#![no_std] +extern crate alloc; + +use alloc::{borrow::Cow, vec, vec::Vec, collections::VecDeque, string::String, format, sync::Arc}; +use awkernel_async_lib::dag::{create_dag, finish_create_dags}; +use awkernel_async_lib::scheduler::SchedulerType; +use awkernel_async_lib::task::perf::get_period_count; +use awkernel_lib::net::{add_ipv4_addr, poll_interface, get_all_interface}; +use awkernel_async_lib::net::{tcp::TcpStream, tcp::TcpConfig, udp::{UdpConfig, UdpSocketError},IpAddr}; +use awkernel_lib::delay::wait_microsec; +use awkernel_lib::sync::mutex::{MCSNode, Mutex}; +use core::time::Duration; +use core::net::Ipv4Addr; +use csv_core::{Reader, ReadRecordResult}; +// Thread-safe state management using atomic operations +use core::sync::atomic::{AtomicBool, AtomicU64, AtomicUsize,Ordering}; +// Global gyro odometer core instance with proper synchronization +use core::sync::atomic::{AtomicPtr, Ordering as AtomicOrdering}; +use core::ptr::null_mut; + + +// IMU ドライバーライブラリをインポート +use imu_driver::{ImuMsg,TamagawaImuParser, Header, Vector3}; +use imu_corrector::{ImuCorrector, ImuWithCovariance, Transform}; + +// Vehicle Velocity Converter ライブラリをインポート(C++のpubsub機能に対応) +use vehicle_velocity_converter::{ + VehicleVelocityConverter, VelocityReport, TwistWithCovarianceStamped, + TwistWithCovariance, Twist, reactor_helpers}; + +// Gyro Odometer ライブラリをインポート +use gyro_odometer::{ + GyroOdometerCore, GyroOdometerConfig}; + +// EKF Localizer ライブラリをインポート +use ekf_localizer::{EKFModule, EKFParameters, Pose, Point3D, Quaternion, PoseWithCovariance}; +// COMMENTED OUT: 手動積分用の関数をコメントアウトしたためlibmは不要 +// use libm::{atan2, cos, sin}; + +/// EKF Odometry structure for publishing (equivalent to C++ nav_msgs::msg::Odometry) +#[derive(Debug, Clone)] +pub struct EKFOdometry { + pub header: imu_driver::Header, + pub child_frame_id: &'static str, + pub pose: PoseWithCovariance, + pub twist: TwistWithCovariance, +} + +const LOG_ENABLE: bool = false; + + +// EKF pose covariance (6x6 matrix flattened to array) +// Layout: [x, xy, xz, xr, xp, xy_yaw, +// yx, y, yz, yr, yp, y_yaw, +// zx, zy, z, zr, zp, z_yaw, +// rx, ry, rz, r, rp, r_yaw, +// px, py, pz, pr, p, p_yaw, +// yaw_x, yaw_y, yaw_z, yaw_r, yaw_p, yaw] +const EKF_POSE_COVARIANCE: [f64; 36] = [ + 0.0225, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0225, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0225, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.000625, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.000625, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.000625, +]; + +// EKF twist covariance (6x6 matrix flattened to array) +// For twist, we mainly care about linear.x (vx) and angular.z (wz) +// Layout: [vx_x, vx_y, vx_z, vx_rx, vx_ry, vx_wz, +// vy_x, vy_y, vy_z, vy_rx, vy_ry, vy_wz, +// vz_x, vz_y, vz_z, vz_rx, vz_ry, vz_wz, +// wx_x, wx_y, wx_z, wx_rx, wx_ry, wx_wz, +// wy_x, wy_y, wy_z, wy_rx, wy_ry, wy_wz, +// wz_x, wz_y, wz_z, wz_rx, wz_ry, wz] +// Based on Autoware's typical twist uncertainty (0.01 m/s for linear, 0.01 rad/s for angular) +const EKF_TWIST_COVARIANCE: [f64; 36] = [ + 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0001, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0001, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001, +]; + +static LAST_DR_TIMESTAMP: AtomicU64 = AtomicU64::new(0); + +// ネットワーク状態管理 +const INTERFACE_ID: u64 = 0; + +// 10.0.2.0/24 is the IP address range of the Qemu's network. +const INTERFACE_ADDR: Ipv4Addr = Ipv4Addr::new(10, 0, 2, 64); + +// const INTERFACE_ADDR: Ipv4Addr = Ipv4Addr::new(192, 168, 100, 52); // For experiment. + +// 10.0.2.2 is the IP address of the Qemu's host. +const UDP_TCP_DST_ADDR: Ipv4Addr = Ipv4Addr::new(10, 0, 2, 2); + +// const UDP_TCP_DST_ADDR: Ipv4Addr = Ipv4Addr::new(192, 168, 100, 1); // For experiment. + +const UDP_DST_PORT: u16 = 26099; +const TCP_DST_PORT: u16 = 26099; +const TCP_LISTEN_PORT: u16 = 26100; + +// JSONデータ保存用のグローバル変数 +static mut LATEST_JSON_DATA: Option = None; +static JSON_DATA_READY: AtomicBool = AtomicBool::new(false); +static JSON_DATA_LENGTH: AtomicUsize = AtomicUsize::new(0); + +// CSVデータ埋め込み +const IMU_CSV_DATA_STR: &str = include_str!("../imu_raw.csv"); +const VELOCITY_CSV_DATA_STR: &str = include_str!("../velocity_status.csv"); + +// CSVパース結果の保存 +#[derive(Clone, Debug)] +struct ImuCsvRow { + timestamp: u64, + orientation: imu_driver::Quaternion, + angular_velocity: imu_driver::Vector3, + linear_acceleration: imu_driver::Vector3, +} + +#[derive(Clone, Debug)] +struct VelocityCsvRow { + timestamp: u64, + longitudinal_velocity: f64, + lateral_velocity: f64, + heading_rate: f64, +} + +static mut IMU_CSV_DATA: Option> = None; +static mut VELOCITY_CSV_DATA: Option> = None; +static IMU_CSV_COUNT: Mutex = Mutex::new(0); +static VELOCITY_CSV_COUNT: Mutex = Mutex::new(0); + + +// Global EKF Localizer instance with proper synchronization +static EKF_LOCALIZER: AtomicPtr = AtomicPtr::new(null_mut()); + +// COMMENTED OUT: 手動積分用のDR_POSEはEKF内部状態からポーズを取得するようになったため不要 +// static mut DR_POSE: Option = None; + + +pub async fn run() { + wait_microsec(1000000); + + if let Err(e) = initialize_csv_data() { + log::warn!("CSVデータの初期化に失敗しました: {}", e); + } + + log::info!("Starting Autoware test application with simplified TCP networking"); + + // 初期ネットワークインターフェース情報を表示 + //print_network_interfaces(); + + let dag = create_dag(); + let dag_id = dag.get_id(); + + // ダミーデータ送信用リアクター + // MODIFIED: 周期を10msから50msに変更(Autowareのekf_data_publisher.pyと同じ周期) + // これにより、CSVデータの消費速度が両システムで一致する + dag.register_periodic_reactor::<_, ((i32, u32), (i32, u32), (i32, u32))>( + "start_dummy_data".into(), + move || -> ((i32, u32), (i32, u32), (i32, u32)) { + let period_id = get_period_count(dag_id as usize) as u32; + return ((1, period_id), (2, period_id), (3, period_id)); // 通常のデータ処理用の値 + }, + vec![Cow::from("start_imu"),Cow::from("start_vel"),Cow::from("start_pose")], + SchedulerType::GEDF(5), + Duration::from_millis(50) // CHANGED: 10ms -> 50ms (Autowareと同じ) + ) + .await; + + // IMU driver node (periodic_reactor) - Dummy data generator + dag.register_reactor::<_, ((i32, u32),), ((ImuMsg, u32),)>( + "imu_driver".into(), + move |((_a, period_id),): ((i32, u32),)| -> ((ImuMsg, u32),) { + let mut node = MCSNode::new(); + let mut count_guard = IMU_CSV_COUNT.lock(&mut node); + let count = *count_guard; + let data = unsafe { IMU_CSV_DATA.as_ref() }; + + let imu_msg = if let Some(csv_data) = data { + if csv_data.is_empty() { + let mut parser = TamagawaImuParser::new("imu_link"); + let awkernel_timestamp = get_awkernel_uptime_timestamp(); + let static_dummy_data = parser.generate_static_dummy_data(awkernel_timestamp); + parser + .parse_binary_data(&static_dummy_data, awkernel_timestamp) + .unwrap_or_default() + } else { + let idx = count % csv_data.len(); + let row = &csv_data[idx]; + let awkernel_timestamp = get_awkernel_uptime_timestamp(); + ImuMsg { + header: Header { + frame_id: "imu_link", + timestamp: awkernel_timestamp, + }, + orientation: row.orientation.clone(), + angular_velocity: row.angular_velocity.clone(), + linear_acceleration: row.linear_acceleration.clone(), + } + } + } else { + let mut parser = TamagawaImuParser::new("imu_link"); + let awkernel_timestamp = get_awkernel_uptime_timestamp(); + let static_dummy_data = parser.generate_static_dummy_data(awkernel_timestamp); + parser + .parse_binary_data(&static_dummy_data, awkernel_timestamp) + .unwrap_or_default() + }; + + *count_guard += 1; + if *count_guard >= 5700 { + *count_guard = 0; + log::info!("rust_e2e_app: finish csv for IMU"); + loop {} + } + + if LOG_ENABLE { + log::debug!( + "IMU data in imu_driver_node,num={}, timestamp={}", + count, imu_msg.header.timestamp + ); + } + + ((imu_msg, period_id),) + }, + vec![Cow::from("start_imu")], + vec![Cow::from("imu_data")], + SchedulerType::GEDF(5), + ) + .await; + + // Vehicle Velocity Converter node - VelocityReport to TwistWithCovarianceStamped converter + dag.register_reactor::<_, ((i32, u32),), ((TwistWithCovarianceStamped, u32),)>( + "vehicle_velocity_converter".into(), + move |((_b, period_id),): ((i32, u32),)| -> ((TwistWithCovarianceStamped, u32),) { + let converter = VehicleVelocityConverter::default(); + + let mut node = MCSNode::new(); + let mut count_guard = VELOCITY_CSV_COUNT.lock(&mut node); + let count = *count_guard; + let data = unsafe { VELOCITY_CSV_DATA.as_ref() }; + + let csv_data = data.expect("VELOCITY_CSV_DATA must be initialized"); + let idx = count % csv_data.len(); + let row = &csv_data[idx]; + let awkernel_timestamp = get_awkernel_uptime_timestamp(); + let velocity_report = VelocityReport { + header: Header { + frame_id: "base_link", + timestamp: awkernel_timestamp, + }, + longitudinal_velocity: row.longitudinal_velocity, + lateral_velocity: row.lateral_velocity, + heading_rate: row.heading_rate, + }; + + *count_guard += 1; + if *count_guard >= 5700 { + *count_guard = 0; + log::info!("rust_e2e_app: finish csv for Velocity"); + loop {} + } + + let twist_msg = converter.convert_velocity_report(&velocity_report); + + if LOG_ENABLE { + log::debug!("Vehicle velocity converter: Converted velocity report to twist - linear.x={:.3}, angular.z={:.3}, awkernel_timestamp={}", + twist_msg.twist.twist.linear.x, + twist_msg.twist.twist.angular.z, + twist_msg.header.timestamp + ); + } + + ((twist_msg, period_id),) + }, + vec![Cow::from("start_vel")], // Subscribe to start_vel topic + vec![Cow::from("velocity_twist")], // Publish to twist_with_covariance topic + SchedulerType::GEDF(5), + ) + .await; + + //Imu Corrector + dag.register_reactor::<_, ((ImuMsg, u32),), ((ImuWithCovariance, u32),)>( + "imu_corrector".into(), + |((imu_msg, period_id),): ((ImuMsg, u32),)| -> ((ImuWithCovariance, u32),) { + + let corrector = ImuCorrector::new(); + // Use the enhanced corrector that outputs ImuWithCovariance + let corrected = corrector.correct_imu_with_covariance(&imu_msg, None); + // if LOG_ENABLE { + // log::debug!("IMU corrected in imu_corrector node with covariance"); + // } + ((corrected, period_id),) + }, + vec![Cow::from("imu_data")], + vec![Cow::from("corrected_imu_data")], + SchedulerType::GEDF(5), + ) + .await; + + // Gyro Odometer node - Simplified single processing step + dag.register_reactor::<_, ((ImuWithCovariance, u32), (TwistWithCovarianceStamped, u32)), ((TwistWithCovarianceStamped, u32),)>( + "gyro_odometer".into(), + |((imu_with_cov, period_imu), (vehicle_twist, _period_twist)): ((ImuWithCovariance, u32), (TwistWithCovarianceStamped, u32))| -> ((TwistWithCovarianceStamped, u32),) { + let current_timestamp = imu_with_cov.header.timestamp; + let current_time = get_awkernel_uptime_timestamp(); + + // Get or initialize gyro odometer core + let gyro_odometer = match gyro_odometer::get_or_initialize() { + Ok(core) => core, + Err(_) => { + return ((reactor_helpers::create_empty_twist(current_timestamp), period_imu),); + } + }; + + // Add both messages to queues (both arrive together in test_autoware) + gyro_odometer.add_vehicle_twist(vehicle_twist); + gyro_odometer.add_imu(imu_with_cov); + + // Process once with current time and return result + match gyro_odometer.process_and_get_result(current_time) { + Some(result) => ((gyro_odometer.process_result(result), period_imu),), + None => ((reactor_helpers::create_empty_twist(current_timestamp), period_imu),) + } + }, + vec![Cow::from("corrected_imu_data"),Cow::from("velocity_twist")], + vec![Cow::from("twist_with_covariance")], + SchedulerType::GEDF(5), + ) + .await; + + // Pose dummy data generator reactor + dag.register_reactor::<_, ((i32, u32),), ((Pose, u32),)>( + "pose_dummy_generator".into(), + move |((_counter, period_id),): ((i32, u32),)| -> ((Pose, u32),) { + // Generate dummy pose data that moves in a circle + // let time = counter as f64 * 0.1; // Time progression + // let radius = 10.0; // Circle radius + // let angular_velocity = 0.5; // rad/s + + // aip_x1_description/config/sensors_calibration.yaml + // if needed, comment out and use fixed values below + // let x = 0.86419; + // let y = 0.0; + // let z = 2.18096; + // let yaw = angular_velocity * time; + // for initial pose + let x = 0.0; + let y = 0.0; + let z = 0.0; + + let pose = Pose { + position: Point3D { x,y,z}, + orientation: Quaternion { + x: 0.0, + y: 0.0, + z: 0.0, + w: 1.0, + }, + }; + + // if LOG_ENABLE { + // log::debug!("Generated dummy pose: x={:.3}, y={:.3}, yaw={:.3}, counter={}", + // pose.position.x, pose.position.y, yaw, counter); + // } + + ((pose, period_id),) + }, + vec![Cow::from("start_pose")], + vec![Cow::from("dummy_pose")], + SchedulerType::GEDF(5), + ) + .await; + + // EKF Localizer reactor - combines pose and twist data + // MODIFIED: 手動積分(integrated_pose)を廃止し、EKFの内部状態から直接ポーズを取得するように変更 + dag.register_reactor::<_, ((Pose, u32), (TwistWithCovarianceStamped, u32)), ((Pose, u32), (EKFOdometry, u32))>( + "ekf_localizer".into(), + |((pose, period_pose), (twist, _period_twist)): ((Pose, u32), (TwistWithCovarianceStamped, u32))| -> ((Pose, u32), (EKFOdometry, u32)) { + // Initialize EKF Localizer if not already done + if get_ekf_localizer().is_none() { + if let Err(e) = initialize_ekf_localizer() { + // if LOG_ENABLE { + // log::error!("Failed to initialize EKF Localizer: {}", e); + // } + return ((pose, period_pose), (EKFOdometry { + header: imu_driver::Header { + frame_id: "map", + timestamp: twist.header.timestamp, + }, + child_frame_id: "base_link", + pose: PoseWithCovariance { + pose: pose, + covariance: EKF_POSE_COVARIANCE, + }, + twist: TwistWithCovariance { + twist: Twist { + linear: imu_driver::Vector3::new(0.0, 0.0, 0.0), + angular: imu_driver::Vector3::new(0.0, 0.0, 0.0), + }, + covariance: EKF_TWIST_COVARIANCE, + }, + }, period_pose)); + } + } + + let ekf = get_ekf_localizer().unwrap(); + + // Initialize EKF with first pose if not already initialized + static mut INITIALIZED: bool = false; + unsafe { + if !INITIALIZED { + ekf.initialize(pose.clone()); + // COMMENTED OUT: 手動積分用の変数は使用しない + // DR_POSE = Some(pose.clone()); + LAST_DR_TIMESTAMP.store(twist.header.timestamp, Ordering::Relaxed); + INITIALIZED = true; + // if LOG_ENABLE { + // log::info!("EKF Localizer initialized with initial pose"); + // } + } + } + + // Predict step using measured time gap + // MODIFIED: CSVタイムスタンプ差ではなく、固定dtを使用 + // Autowareのekf_data_publisher.pyは50ms固定周期でデータをpublishする + // EKFは実際の経過時間(システムクロック)を使用するため、 + // Awkernelも同様に固定dtを使用することで挙動を一致させる + // + // OLD CODE (CSVタイムスタンプ差を使用): + // let current_ts = twist.header.timestamp; + // let last_ts = LAST_DR_TIMESTAMP.swap(current_ts, Ordering::Relaxed); + // let dt = if last_ts == 0 { + // 0.0 + // } else { + // (current_ts.saturating_sub(last_ts)) as f64 / 1_000_000_000.0 + // }; + // + // NEW CODE: 固定dt = 50ms (0.05秒) - Autowareと同じ周期 + const FIXED_DT: f64 = 0.05; // 50ms in seconds + let dt = FIXED_DT; + + if dt > 0.0 { + ekf.predict(dt); + } + + // ADDED: EKFに速度観測値を更新(カルマンフィルタの観測更新ステップ) + let vx = twist.twist.twist.linear.x; + let wz = twist.twist.twist.angular.z; + ekf.update_velocity(vx, wz); + + // COMMENTED OUT: 手動積分(Dead Reckoning)処理 + // Autowareとの精度向上のため、EKF内部状態から直接ポーズを取得するように変更 + // let mut integrated_pose = unsafe { DR_POSE.clone().unwrap_or_else(|| pose.clone()) }; + // let yaw = quaternion_to_yaw(&integrated_pose.orientation); + // let vx = twist.twist.twist.linear.x; + // let vy = twist.twist.twist.linear.y; + // let vz = twist.twist.twist.linear.z; + // let wz = twist.twist.twist.angular.z; + // + // if dt > 0.0 { + // let cos_yaw = cos(yaw); + // let sin_yaw = sin(yaw); + // let new_yaw = yaw + wz * dt; + // + // integrated_pose.position.x += (vx * cos_yaw - vy * sin_yaw) * dt; + // integrated_pose.position.y += (vx * sin_yaw + vy * cos_yaw) * dt; + // integrated_pose.position.z += vz * dt; + // integrated_pose.orientation = yaw_to_quaternion(new_yaw); + // } + // + // unsafe { + // DR_POSE = Some(integrated_pose.clone()); + // } + + // MODIFIED: EKFの内部状態から直接ポーズを取得 + // get_biased_yaw=false でyaw_biasを考慮したポーズを取得 + let ekf_pose = ekf.get_current_pose(false); + + // MODIFIED: EKFから動的な共分散を取得(固定値ではなく) + // これにより、走行距離や時間の経過に伴う不確かさの変化を反映 + let pose_covariance = ekf.get_current_pose_covariance(); + let twist_covariance = ekf.get_current_twist_covariance(); + + // COMMENTED OUT: 固定共分散の使用 + // let pose_covariance = EKF_POSE_COVARIANCE; + // let twist_covariance = EKF_TWIST_COVARIANCE; + + // Get EKF's estimated twist + let ekf_twist = ekf.get_current_twist(); + + // Create odometry message using EKF's estimated pose and twist + let odometry = EKFOdometry { + header: imu_driver::Header { + frame_id: "map", + timestamp: twist.header.timestamp, + }, + child_frame_id: "base_link", + pose: PoseWithCovariance { + pose: ekf_pose.clone(), + covariance: pose_covariance, + }, + twist: TwistWithCovariance { + // Use EKF's estimated twist instead of input twist + twist: Twist { + linear: imu_driver::Vector3::new(ekf_twist.linear.x, ekf_twist.linear.y, ekf_twist.linear.z), + angular: imu_driver::Vector3::new(ekf_twist.angular.x, ekf_twist.angular.y, ekf_twist.angular.z), + }, + covariance: twist_covariance, + }, + }; + + // if LOG_ENABLE { + // log::debug!("EKF Localizer: ekf_pose=({:.3}, {:.3}, {:.3}), dt={:.3}, awkernel_timestamp={}", + // ekf_pose.position.x, ekf_pose.position.y, ekf_pose.position.z, dt, odometry.header.timestamp); + // log::debug!("EKF Localizer: ekf_twist=({:.3}, {:.3}, {:.3}), angular=({:.3}, {:.3}, {:.3})", + // ekf_twist.linear.x, ekf_twist.linear.y, ekf_twist.linear.z, + // ekf_twist.angular.x, ekf_twist.angular.y, ekf_twist.angular.z); + // } + + // COMMENTED OUT: 手動積分のポーズを返していた + // (integrated_pose, odometry) + // MODIFIED: EKFの推定ポーズを返す + ((ekf_pose, period_pose), (odometry, period_pose)) + }, + vec![Cow::from("dummy_pose"), Cow::from("twist_with_covariance")], + vec![Cow::from("estimated_pose"), Cow::from("ekf_odometry")], + SchedulerType::GEDF(5), + ) + .await; + + // Sink reactor for EKF Localizer output with TCP sending + dag.register_sink_reactor::<_, ((Pose, u32), (EKFOdometry, u32))>( + "ekf_sink".into(), + move|((_pose, _period_pose), (ekf_odom, _period_odom)): ((Pose, u32), (EKFOdometry, u32))| { + // log::info!("=== EKF Sink Reactor 実行 ==="); + + // if LOG_ENABLE { + // log::info!("Estimated Pose:"); + // log::info!(" Position: x={:.3}, y={:.3}, z={:.3}", + // pose.position.x, pose.position.y, pose.position.z); + // log::info!(" Orientation: x={:.3}, y={:.3}, z={:.3}, w={:.3}", + // pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w); + + // log::info!("EKF Odometry (ekf_odom):"); + // log::info!(" Frame: {} -> {}", ekf_odom.header.frame_id, ekf_odom.child_frame_id); + // log::info!(" Timestamp: {}", ekf_odom.header.timestamp); + // log::info!(" Position: x={:.3}, y={:.3}, z={:.3}", + // ekf_odom.pose.pose.position.x, ekf_odom.pose.pose.position.y, ekf_odom.pose.pose.position.z); + // log::info!(" Orientation: x={:.3}, y={:.3}, z={:.3}, w={:.3}", + // ekf_odom.pose.pose.orientation.x, ekf_odom.pose.pose.orientation.y, + // ekf_odom.pose.pose.orientation.z, ekf_odom.pose.pose.orientation.w); + // log::info!(" Linear Velocity: x={:.3}, y={:.3}, z={:.3}", + // ekf_odom.twist.twist.linear.x, ekf_odom.twist.twist.linear.y, ekf_odom.twist.twist.linear.z); + // log::info!(" Angular Velocity: x={:.3}, y={:.3}, z={:.3}", + // ekf_odom.twist.twist.angular.x, ekf_odom.twist.twist.angular.y, ekf_odom.twist.twist.angular.z); + // log::info!("============================="); + // } + + // JSONデータを作成してグローバル変数に保存 + let json_data = format!( + r#"{{"header":{{"frame_id":"{}","timestamp":{}}},"child_frame_id":"{}","pose":{{"pose":{{"position":{{"x":{:.6},"y":{:.6},"z":{:.6}}},"orientation":{{"x":{:.6},"y":{:.6},"z":{:.6},"w":{:.6}}}}},"covariance":[{}]}},"twist":{{"twist":{{"linear":{{"x":{:.6},"y":{:.6},"z":{:.6}}},"angular":{{"x":{:.6},"y":{:.6},"z":{:.6}}}}},"covariance":[{}]}}}}"#, + ekf_odom.header.frame_id, + ekf_odom.header.timestamp, + ekf_odom.child_frame_id, + ekf_odom.pose.pose.position.x, + ekf_odom.pose.pose.position.y, + ekf_odom.pose.pose.position.z, + ekf_odom.pose.pose.orientation.x, + ekf_odom.pose.pose.orientation.y, + ekf_odom.pose.pose.orientation.z, + ekf_odom.pose.pose.orientation.w, + ekf_odom.pose.covariance.iter().map(|&x| format!("{:.6}", x)).collect::>().join(","), + ekf_odom.twist.twist.linear.x, + ekf_odom.twist.twist.linear.y, + ekf_odom.twist.twist.linear.z, + ekf_odom.twist.twist.angular.x, + ekf_odom.twist.twist.angular.y, + ekf_odom.twist.twist.angular.z, + ekf_odom.twist.covariance.iter().map(|&x| format!("{:.6}", x)).collect::>().join(",") + ); + + let awkernel_timestamp = get_awkernel_uptime_timestamp(); + // log::info!("JSONデータ作成完了: {} bytes, awkernel_timestamp={}", json_data.len(), awkernel_timestamp); + + // グローバル変数にJSONデータを保存 + save_json_data_to_global(json_data); + }, + vec![Cow::from("estimated_pose"), Cow::from("ekf_odometry")], + SchedulerType::GEDF(5), + Duration::from_millis(50), // CHANGED: 10ms -> 50ms (Autowareと同じ) + ) + .await; + + // DAG の作成を完了 + let result = finish_create_dags(&[dag.clone()]).await; + + match result { + Ok(_) => { + log::info!("Autoware test application DAGs created successfully"); + } + Err(errors) => { + log::error!("Failed to create Autoware test application DAGs"); + for error in errors { + log::error!("- {error}"); + } + } + } + + // ノード数の確認 + // assert_eq!(dag.node_count(), 9); // 1つの periodic reactor + 8つの reactor(network_info_display追加) + // assert_eq!(dag.edge_count(), 10); // トピックエッジの数 + + log::info!("Autoware test application DAG completed"); + + log::info!("=== ネットワークテスト開始 ==="); + log::info!("インターフェースID: {}", INTERFACE_ID); + log::info!("インターフェースIP: {}", INTERFACE_ADDR); + log::info!("宛先IP: {}", UDP_TCP_DST_ADDR); + // + awkernel_lib::net::add_ipv4_addr(INTERFACE_ID, INTERFACE_ADDR, 24); + log::info!("IPv4アドレス設定完了: {} をインターフェース {} に追加", INTERFACE_ADDR, INTERFACE_ID); + + // ネットワークスタックの初期化を待つ + log::info!("ネットワークスタック初期化のため待機中..."); + awkernel_async_lib::sleep(Duration::from_secs(2)).await; + + // リアクターAPIに干渉しない周期UDP送信タスクを開始 + log::info!("周期UDP送信タスクを開始します"); + start_periodic_udp_sender().await; + + // または、設定可能な周期で開始する場合 + // start_configurable_udp_sender(2).await; // 2秒間隔 + + // JSONデータが準備されるまで待機(最大3秒) + log::info!("JSONデータの準備を待機中..."); + let mut wait_count = 0; + const MAX_WAIT_COUNT: u32 = 3; + + while !JSON_DATA_READY.load(Ordering::Relaxed) && wait_count < MAX_WAIT_COUNT { + // log::info!("JSONデータ待機中... ({}/{})", wait_count + 1, MAX_WAIT_COUNT); + awkernel_async_lib::sleep(Duration::from_secs(1)).await; + wait_count += 1; + } + + if JSON_DATA_READY.load(Ordering::Relaxed) { + // log::info!("JSONデータが準備されました。周期UDP送信タスクが動作中です"); + // 周期UDP送信タスクは既に動作中なので、ここでは何もしない + } else { + log::warn!("JSONデータが準備されませんでした。周期UDP送信タスクは待機中です"); + } + + log::info!("Autoware test application completed"); +} + +fn initialize_csv_data() -> Result<(), &'static str> { + unsafe { + if IMU_CSV_DATA.is_none() { + let imu_data = parse_imu_csv(IMU_CSV_DATA_STR)?; + if imu_data.is_empty() { + return Err("IMU CSVが空です"); + } + log::info!("IMU CSVデータをロード: {} rows", imu_data.len()); + IMU_CSV_DATA = Some(imu_data); + } + + if VELOCITY_CSV_DATA.is_none() { + let velocity_data = parse_velocity_csv(VELOCITY_CSV_DATA_STR)?; + if velocity_data.is_empty() { + return Err("Velocity CSVが空です"); + } + log::info!("Velocity CSVデータをロード: {} rows", velocity_data.len()); + VELOCITY_CSV_DATA = Some(velocity_data); + } + } + + // let imu_start = find_first_active_imu_index(); + // IMU_CSV_INDEX.store(imu_start, Ordering::Relaxed); + // let velocity_start = find_first_moving_velocity_index(); + // VELOCITY_CSV_INDEX.store(velocity_start, Ordering::Relaxed); + // log::info!( + // "CSV開始インデックス: IMU={}, Velocity={}", + // imu_start, + // velocity_start + // ); + + Ok(()) +} + +fn parse_imu_csv(csv: &str) -> Result, &'static str> { + let mut rows = Vec::new(); + + parse_csv_records(csv, |fields| { + if fields.len() < 12 { + return Err("IMU CSVの列数が不足しています"); + } + + let timestamp = parse_timestamp(fields[0], fields[1])?; + let orientation = imu_driver::Quaternion { + x: parse_f64(fields[2])?, + y: parse_f64(fields[3])?, + z: parse_f64(fields[4])?, + w: parse_f64(fields[5])?, + }; + let angular_velocity = imu_driver::Vector3::new( + parse_f64(fields[6])?, + parse_f64(fields[7])?, + parse_f64(fields[8])?, + ); + let linear_acceleration = imu_driver::Vector3::new( + parse_f64(fields[9])?, + parse_f64(fields[10])?, + parse_f64(fields[11])?, + ); + + rows.push(ImuCsvRow { + timestamp, + orientation, + angular_velocity, + linear_acceleration, + }); + Ok(()) + })?; + + Ok(rows) +} + +fn parse_velocity_csv(csv: &str) -> Result, &'static str> { + let mut rows = Vec::new(); + + parse_csv_records(csv, |fields| { + if fields.len() < 5 { + return Err("Velocity CSVの列数が不足しています"); + } + + let timestamp = parse_timestamp(fields[0], fields[1])?; + let longitudinal_velocity = parse_f64(fields[2])?; + let lateral_velocity = parse_f64(fields[3])?; + let heading_rate = parse_f64(fields[4])?; + + rows.push(VelocityCsvRow { + timestamp, + longitudinal_velocity, + lateral_velocity, + heading_rate, + }); + Ok(()) + })?; + + Ok(rows) +} + +fn parse_csv_records(csv: &str, mut on_record: F) -> Result<(), &'static str> +where + F: FnMut(&[&str]) -> Result<(), &'static str>, +{ + let mut reader = Reader::new(); + let mut input = csv.as_bytes(); + let mut output = vec![0u8; 4096]; + let mut ends = vec![0usize; 32]; + let mut header_skipped = false; + + loop { + let (result, in_read, _out_written, num_fields) = reader.read_record(input, &mut output, &mut ends); + input = &input[in_read..]; + + if matches!(result, ReadRecordResult::OutputFull) { + return Err("CSV出力バッファが不足しています"); + } + + if num_fields == 0 { + if matches!(result, ReadRecordResult::InputEmpty | ReadRecordResult::End) { + break; + } + continue; + } + + let mut fields: Vec<&str> = Vec::with_capacity(num_fields); + let mut start = 0usize; + for i in 0..num_fields { + let end = ends[i]; + let slice = &output[start..end]; + let field = core::str::from_utf8(slice).map_err(|_| "CSV UTF-8変換に失敗しました")?; + fields.push(field); + start = end; + } + + if !header_skipped { + header_skipped = true; + } else { + on_record(&fields)?; + } + + if matches!(result, ReadRecordResult::End) { + break; + } + } + + Ok(()) +} + +fn parse_timestamp(sec: &str, nsec: &str) -> Result { + let sec_val = parse_u64(sec)?; + let nsec_val = parse_u64(nsec)?; + let ts = sec_val + .checked_mul(1_000_000_000) + .and_then(|v| v.checked_add(nsec_val)) + .ok_or("timestamp計算でオーバーフローしました")?; + Ok(ts) +} + +fn parse_u64(field: &str) -> Result { + let trimmed = field.trim(); + if trimmed.is_empty() { + return Ok(0); + } + trimmed.parse::().map_err(|_| "u64パースに失敗しました") +} + +fn parse_f64(field: &str) -> Result { + let trimmed = field.trim(); + if trimmed.is_empty() { + return Ok(0.0); + } + trimmed.parse::().map_err(|_| "f64パースに失敗しました") +} + +// fn find_first_moving_velocity_index() -> usize { + // const EPS: f64 = 1.0e-6; + // let data = unsafe { VELOCITY_CSV_DATA.as_ref() }; + // if let Some(rows) = data { + // for (idx, row) in rows.iter().enumerate() { + // if row.longitudinal_velocity.abs() > EPS || row.lateral_velocity.abs() > EPS { + // return idx; + // } + // } + // } + // 0 +// } +// +// fn find_first_active_imu_index() -> usize { + // const EPS: f64 = 1.0e-6; + // let data = unsafe { IMU_CSV_DATA.as_ref() }; + // if let Some(rows) = data { + // for (idx, row) in rows.iter().enumerate() { + // if row.angular_velocity.x.abs() > EPS + // || row.angular_velocity.y.abs() > EPS + // || row.angular_velocity.z.abs() > EPS + // || row.linear_acceleration.x.abs() > EPS + // || row.linear_acceleration.y.abs() > EPS + // || row.linear_acceleration.z.abs() > EPS + // { + // return idx; + // } + // } + // } + // 0 +// } + +// Awkernel起動時間からのタイムスタンプを取得する関数 +fn get_awkernel_uptime_timestamp() -> u64 { + // awkernel_lib::delay::uptime_nano()はu128を返すが、JSONではu64を使用 + // ナノ秒単位のタイムスタンプを取得 + let uptime_nanos = awkernel_lib::delay::uptime_nano(); + // u128からu64に変換(オーバーフローを防ぐため、適切な範囲に制限) + if uptime_nanos > u64::MAX as u128 { + u64::MAX + } else { + uptime_nanos as u64 + } +} + +// リアクターAPIに干渉しないUDP送信タスク(一定周期実行) +pub async fn start_periodic_udp_sender() { + // log::info!("=== 周期UDP送信タスク開始 ==="); + + // 独立したタスクとして実行 + awkernel_async_lib::spawn( + "periodic_udp_sender".into(), + periodic_udp_sender_task(), + awkernel_async_lib::scheduler::SchedulerType::PrioritizedFIFO(0), + ) + .await; + + // log::info!("周期UDP送信タスクを開始しました"); +} + +// 周期UDP送信タスクの実装 +async fn periodic_udp_sender_task() { + // log::info!("周期UDP送信タスク: 開始"); + + // UDPソケットを作成(一度だけ) + let socket_result = awkernel_async_lib::net::udp::UdpSocket::bind_on_interface( + INTERFACE_ID, + &Default::default(), + ); + + let mut socket = match socket_result { + Ok(socket) => { + // log::info!("周期UDP送信タスク: UDPソケット作成成功"); + socket + } + Err(e) => { + log::error!("周期UDP送信タスク: UDPソケット作成失敗: {:?}", e); + return; + } + }; + + let dst_addr = IpAddr::new_v4(UDP_TCP_DST_ADDR); + let mut counter = 0; + + // 無限ループで一定周期実行 + loop { + // JSONデータの準備チェック + if !JSON_DATA_READY.load(Ordering::Relaxed) { + // log::debug!("周期UDP送信タスク: JSONデータ未準備、待機中..."); + awkernel_async_lib::sleep(Duration::from_secs(1)).await; + continue; + } + + // 安全にJSONデータを取得 + let json_data = unsafe { + LATEST_JSON_DATA.as_ref().map(|s| s.clone()) + }; + + if let Some(data) = json_data { + // UDP送信を実行 + match socket.send(data.as_bytes(), &dst_addr, UDP_DST_PORT).await { + Ok(_) => { + counter += 1; + log::info!("周期UDP送信タスク: 送信成功 #{} ({} bytes)", counter, data.len()); + + // レスポンス受信(オプション、タイムアウト付き) + let mut buf = [0u8; 1024]; + if let Some(Ok((n, src_addr, src_port))) = + awkernel_async_lib::timeout( + Duration::from_millis(100), // 短いタイムアウト + socket.recv(&mut buf) + ).await { + if let Ok(response) = core::str::from_utf8(&buf[..n]) { + log::debug!("周期UDP送信タスク: レスポンス受信: {}:{} - {}", + src_addr.get_addr(), src_port, response); + } + } + } + Err(e) => { + log::warn!("周期UDP送信タスク: 送信失敗: {:?}", e); + } + } + } else { + log::warn!("周期UDP送信タスク: JSONデータが取得できませんでした"); + } + + // 一定周期で待機(例: 2秒間隔 - DAGの実行周期と衝突を避けるため) + awkernel_async_lib::sleep(Duration::from_millis(5)).await; + } +} + +// リアクターAPIに干渉しないUDP送信タスク(設定可能な周期) +// pub async fn start_configurable_udp_sender(interval_sec: u64) { +// log::info!("=== 設定可能周期UDP送信タスク開始 (間隔: {}秒) ===", interval_sec); + +// // 独立したタスクとして実行 +// awkernel_async_lib::spawn( +// "configurable_udp_sender".into(), +// configurable_udp_sender_task(interval_sec), +// awkernel_async_lib::scheduler::SchedulerType::GEDF(5), +// ) +// .await; + +// log::info!("設定可能周期UDP送信タスクを開始しました"); +// } + +// 設定可能な周期UDP送信タスクの実装 +// async fn configurable_udp_sender_task(interval_sec: u64) { +// log::info!("設定可能周期UDP送信タスク: 開始 (間隔: {}秒)", interval_sec); + +// // UDPソケットを作成 +// let socket_result = awkernel_async_lib::net::udp::UdpSocket::bind_on_interface( +// INTERFACE_ID, +// &Default::default(), +// ); + +// let mut socket = match socket_result { +// Ok(socket) => { +// log::info!("設定可能周期UDP送信タスク: UDPソケット作成成功"); +// socket +// } +// Err(e) => { +// log::error!("設定可能周期UDP送信タスク: UDPソケット作成失敗: {:?}", e); +// return; +// } +// }; + +// let dst_addr = IpAddr::new_v4(UDP_TCP_DST_ADDR); +// let mut counter = 0; + +// loop { +// // ネットワーク初期化チェック +// if !NETWORK_INITIALIZED.load(Ordering::Relaxed) { +// log::debug!("設定可能周期UDP送信タスク: ネットワーク未初期化、待機中..."); +// awkernel_async_lib::sleep(Duration::from_secs(1)).await; +// continue; +// } + +// // JSONデータの準備チェック +// if !JSON_DATA_READY.load(Ordering::Relaxed) { +// log::debug!("設定可能周期UDP送信タスク: JSONデータ未準備、待機中..."); +// awkernel_async_lib::sleep(Duration::from_secs(1)).await; +// continue; +// } + +// // 安全にJSONデータを取得 +// let json_data = unsafe { +// LATEST_JSON_DATA.as_ref().map(|s| s.clone()) +// }; + +// if let Some(data) = json_data { +// // UDP送信を実行 +// match socket.send(data.as_bytes(), &dst_addr, UDP_DST_PORT).await { +// Ok(_) => { +// counter += 1; +// log::info!("設定可能周期UDP送信タスク: 送信成功 #{} ({} bytes, 間隔: {}秒)", +// counter, data.len(), interval_sec); +// } +// Err(e) => { +// log::warn!("設定可能周期UDP送信タスク: 送信失敗: {:?}", e); +// } +// } +// } else { +// log::warn!("設定可能周期UDP送信タスク: JSONデータが取得できませんでした"); +// } + +// // 設定された周期で待機 +// awkernel_async_lib::sleep(Duration::from_secs(interval_sec)).await; +// } +// } + +// JSONデータをグローバル変数に保存する関数 +fn save_json_data_to_global(json_data: String) { + unsafe { + LATEST_JSON_DATA = Some(json_data.clone()); + } + JSON_DATA_READY.store(true, Ordering::Relaxed); + JSON_DATA_LENGTH.store(json_data.len(), Ordering::Relaxed); + // log::info!("JSONデータをグローバル変数に保存: {} bytes", json_data.len()); +} + +// Transform error handling function +fn get_transform_safely(from_frame: &str, to_frame: &str) -> Result { + // For now, return identity transform + // In a real implementation, this would query the transform tree + if from_frame == to_frame { + Ok(Transform::identity()) + } else { + // Simulate transform lookup + Ok(Transform::identity()) + } +} + +// Initialize EKF Localizer safely +fn initialize_ekf_localizer() -> Result<(), &'static str> { + let params = EKFParameters::default(); + let ekf = EKFModule::new(params); + + // Allocate on heap and store pointer + let boxed_ekf = alloc::boxed::Box::new(ekf); + let ptr = alloc::boxed::Box::into_raw(boxed_ekf); + + // Try to store the pointer atomically + let old_ptr = EKF_LOCALIZER.compare_exchange( + null_mut(), + ptr, + AtomicOrdering::Acquire, + AtomicOrdering::Relaxed, + ); + + match old_ptr { + Ok(_) => Ok(()), + Err(_) => { + // Another thread already initialized it, clean up our allocation + unsafe { + let _ = alloc::boxed::Box::from_raw(ptr); + } + Ok(()) + } + } +} + +// COMMENTED OUT: 手動積分用の関数はEKF内部状態からポーズを取得するようになったため不要 +// EKFModule内にquaternion_to_yawとrpy_to_quaternionがあるため、そちらを使用 +// fn quaternion_to_yaw(q: &Quaternion) -> f64 { +// // Yaw extraction for dead reckoning heading propagation +// let siny_cosp = 2.0 * (q.w * q.z + q.x * q.y); +// let cosy_cosp = 1.0 - 2.0 * (q.y * q.y + q.z * q.z); +// atan2(siny_cosp, cosy_cosp) +// } +// +// fn yaw_to_quaternion(yaw: f64) -> Quaternion { +// let half = yaw * 0.5; +// Quaternion { +// x: 0.0, +// y: 0.0, +// z: sin(half), +// w: cos(half), +// } +// } + +// Get EKF Localizer safely +fn get_ekf_localizer() -> Option<&'static mut EKFModule> { + let ptr = EKF_LOCALIZER.load(AtomicOrdering::Acquire); + if ptr.is_null() { + None + } else { + unsafe { Some(&mut *ptr) } + } +} \ No newline at end of file diff --git a/applications/tests/test_autoware/vehicle_velocity_converter/Cargo.toml b/applications/tests/test_autoware/vehicle_velocity_converter/Cargo.toml new file mode 100644 index 000000000..093a4714e --- /dev/null +++ b/applications/tests/test_autoware/vehicle_velocity_converter/Cargo.toml @@ -0,0 +1,11 @@ +[package] +name = "vehicle_velocity_converter" +version = "0.1.0" +edition = "2021" + +[dependencies] +log = "0.4" +heapless = "0.7" +awkernel_lib = { path = "../../../../awkernel_lib", default-features = false } +awkernel_async_lib = { path = "../../../../awkernel_async_lib", default-features = false } +imu_driver = { path = "../imu_driver", default-features = false } diff --git a/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs b/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs new file mode 100644 index 000000000..b529630b8 --- /dev/null +++ b/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs @@ -0,0 +1,300 @@ +// Copyright 2021 TierIV +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#![no_std] + +use imu_driver::{Vector3, Header}; + +/// 速度レポートメッセージの構造体 +#[derive(Debug, Clone)] +pub struct VelocityReport { + pub header: Header, + pub longitudinal_velocity: f64, + pub lateral_velocity: f64, + pub heading_rate: f64, +} + +/// TwistWithCovarianceStampedメッセージの構造体 +#[derive(Debug, Clone)] +pub struct TwistWithCovarianceStamped { + pub header: Header, + pub twist: TwistWithCovariance, +} + +/// TwistWithCovariance構造体 +#[derive(Debug, Clone)] +pub struct TwistWithCovariance { + pub twist: Twist, + pub covariance: [f64; 36], +} + +/// Twist構造体 +#[derive(Debug, Clone)] +pub struct Twist { + pub linear: Vector3, + pub angular: Vector3, +} + +#[repr(C)] +pub struct Odometry { + pub velocity: f64, +} + +/// 車両速度変換器の構造体 +pub struct VehicleVelocityConverter { + frame_id: &'static str, // → frame_id: base_link + stddev_vx: f64, // → velocity_stddev_xx: 0.2 + stddev_wz: f64, // → angular_velocity_stddev_zz: 0.1 + speed_scale_factor: f64, // → speed_scale_factor: 1.0 +} + +impl VehicleVelocityConverter { + /// 新しいVehicleVelocityConverterインスタンスを作成 + pub fn new( + frame_id: &'static str, + stddev_vx: f64, + stddev_wz: f64, + speed_scale_factor: f64, + ) -> Self { + Self { + frame_id, + stddev_vx, + stddev_wz, + speed_scale_factor, + } + } + + /// パラメータからVehicleVelocityConverterを作成(配列ベース版) + pub fn from_params_array( + velocity_stddev_xx: Option, + angular_velocity_stddev_zz: Option, + speed_scale_factor: Option, + frame_id: &'static str, + ) -> Self { + let stddev_vx = velocity_stddev_xx.unwrap_or(0.2); + let stddev_wz = angular_velocity_stddev_zz.unwrap_or(0.1); + let speed_scale_factor = speed_scale_factor.unwrap_or(1.0); + + Self::new(frame_id, stddev_vx, stddev_wz, speed_scale_factor) + } + + /// デフォルト設定でVehicleVelocityConverterを作成 + pub fn default() -> Self { + Self::new("base_link", 0.2, 0.1, 1.0) + } + + /// 速度レポートをTwistWithCovarianceStampedに変換 + pub fn convert_velocity_report(&self, msg: &VelocityReport) -> TwistWithCovarianceStamped { + // WARN Only + let _frame_id_mismatch = msg.header.frame_id != self.frame_id; + + // TwistWithCovarianceStampedメッセージを生成 + TwistWithCovarianceStamped { + header: msg.header.clone(), + twist: TwistWithCovariance { + twist: Twist { + linear: Vector3 { + x: msg.longitudinal_velocity * self.speed_scale_factor, + y: msg.lateral_velocity, + z: 0.0, + }, + angular: Vector3 { + x: 0.0, + y: 0.0, + z: msg.heading_rate, + }, + }, + covariance: self.create_covariance_matrix(), + }, + } + } + + /// 共分散行列を作成 + fn create_covariance_matrix(&self) -> [f64; 36] { + let mut covariance = [0.0; 36]; + + // 線形速度の分散 (x方向) + covariance[0 + 0 * 6] = self.stddev_vx * self.stddev_vx; + + // その他の線形速度成分は大きな値(低い信頼度)を設定 + covariance[1 + 1 * 6] = 10000.0; // y方向 + covariance[2 + 2 * 6] = 10000.0; // z方向 + + // 角速度成分は大きな値(低い信頼度)を設定 + covariance[3 + 3 * 6] = 10000.0; // x方向 + covariance[4 + 4 * 6] = 10000.0; // y方向 + + // 角速度の分散 (z方向) + covariance[5 + 5 * 6] = self.stddev_wz * self.stddev_wz; + + covariance + } + + /// パラメータを取得 + pub fn get_frame_id(&self) -> &'static str { + self.frame_id + } + + pub fn get_stddev_vx(&self) -> f64 { + self.stddev_vx + } + + pub fn get_stddev_wz(&self) -> f64 { + self.stddev_wz + } + + pub fn get_speed_scale_factor(&self) -> f64 { + self.speed_scale_factor + } +} + +/// リアクターAPI用のヘルパー関数 +pub mod reactor_helpers { + use super::*; + + /// 空のTwistWithCovarianceStampedを生成 + pub fn create_empty_twist(timestamp: u64) -> TwistWithCovarianceStamped { + TwistWithCovarianceStamped { + header: Header { + frame_id: "base_link", + timestamp, + }, + twist: TwistWithCovariance { + twist: Twist { + linear: Vector3 { x: 0.0, y: 0.0, z: 0.0 }, + angular: Vector3 { x: 0.0, y: 0.0, z: 0.0 }, + }, + covariance: [0.0; 36], + }, + } + } +} + +#[cfg(test)] +mod tests { + use super::*; + + #[test] + fn test_vehicle_velocity_converter_creation() { + let converter = VehicleVelocityConverter::new( + "base_link", + 0.1, + 0.1, + 1.0, + ); + + assert_eq!(converter.get_frame_id(), "base_link"); + assert_eq!(converter.get_stddev_vx(), 0.1); + assert_eq!(converter.get_stddev_wz(), 0.1); + assert_eq!(converter.get_speed_scale_factor(), 1.0); + } + + #[test] + fn test_vehicle_velocity_converter_default() { + let converter = VehicleVelocityConverter::default(); + assert_eq!(converter.get_frame_id(), "base_link"); + assert_eq!(converter.get_stddev_vx(), 0.1); + assert_eq!(converter.get_stddev_wz(), 0.1); + assert_eq!(converter.get_speed_scale_factor(), 1.0); + } + + #[test] + fn test_convert_velocity_report_success() { + let converter = VehicleVelocityConverter::new( + "base_link", + 0.1, + 0.1, + 1.0, + ); + + let velocity_report = VelocityReport { + header: Header { + frame_id: "base_link", + timestamp: 1234567890, + }, + longitudinal_velocity: 10.0, + lateral_velocity: 2.0, + heading_rate: 0.5, + }; + + let result = converter.convert_velocity_report(&velocity_report); + assert!(result.is_ok()); + + let twist_msg = result.unwrap(); + assert_eq!(twist_msg.twist.twist.linear.x, 10.0); + assert_eq!(twist_msg.twist.twist.linear.y, 2.0); + assert_eq!(twist_msg.twist.twist.angular.z, 0.5); + assert_eq!(twist_msg.twist.covariance[0], 0.01); // 0.1^2 + assert_eq!(twist_msg.twist.covariance[35], 0.01); // 0.1^2 + } + + #[test] + fn test_convert_velocity_report_wrong_frame_id() { + let converter = VehicleVelocityConverter::new( + "base_link", + 0.1, + 0.1, + 1.0, + ); + + let velocity_report = VelocityReport { + header: Header { + frame_id: "wrong_frame", + timestamp: 1234567890, + }, + longitudinal_velocity: 10.0, + lateral_velocity: 2.0, + heading_rate: 0.5, + }; + + let result = converter.convert_velocity_report(&velocity_report); + assert!(result.is_err()); + assert_eq!(result.unwrap_err(), "frame_id mismatch"); + } + + #[test] + fn test_from_params_array() { + let converter = VehicleVelocityConverter::from_params_array( + Some(0.2), + Some(0.3), + Some(1.5), + "base_link", + ); + + assert_eq!(converter.get_stddev_vx(), 0.2); + assert_eq!(converter.get_stddev_wz(), 0.3); + assert_eq!(converter.get_speed_scale_factor(), 1.5); + } + + #[test] + fn test_from_params_array_with_defaults() { + let converter = VehicleVelocityConverter::from_params_array( + None, + None, + None, + "base_link", + ); + + assert_eq!(converter.get_stddev_vx(), 0.1); + assert_eq!(converter.get_stddev_wz(), 0.1); + assert_eq!(converter.get_speed_scale_factor(), 1.0); + } + + #[test] + fn test_reactor_helpers() { + let empty_twist = reactor_helpers::create_empty_twist(1234567890); + assert_eq!(empty_twist.header.frame_id, "base_link"); + assert_eq!(empty_twist.twist.twist.linear.x, 0.0); + } +} diff --git a/applications/tests/test_autoware/velocity_status.csv b/applications/tests/test_autoware/velocity_status.csv new file mode 100644 index 000000000..395e34668 --- /dev/null +++ b/applications/tests/test_autoware/velocity_status.csv @@ -0,0 +1,5700 @@ +timestamp_sec,timestamp_nanosec,longitudinal_velocity,lateral_velocity,heading_rate +1769682011,700255232,0.0,-0.0,569.3849487304688 +1769682011,758522112,0.0,-0.0,569.3849487304688 +1769682011,769631744,0.0,-0.0,569.3849487304688 +1769682011,808847872,0.0,-0.0,569.3849487304688 +1769682011,864361984,0.0,-0.0,569.3849487304688 +1769682011,880172544,0.0,-0.0,569.3849487304688 +1769682011,910094592,0.0,-0.0,569.3849487304688 +1769682011,950354688,0.0,-0.0,569.3849487304688 +1769682011,978123520,0.0,-0.0,569.3849487304688 +1769682012,10280960,0.0,-0.0,569.3849487304688 +1769682012,51739648,0.0,-0.0,569.3849487304688 +1769682012,75805440,0.0,-0.0,569.3849487304688 +1769682012,113769472,0.0,-0.0,569.3849487304688 +1769682012,158029824,0.0,-0.0,569.3849487304688 +1769682012,169788672,0.0,-0.0,569.3849487304688 +1769682012,209098496,0.0,-0.0,569.3849487304688 +1769682012,263562240,0.0,-0.0,569.3849487304688 +1769682012,273020416,0.0,-0.0,569.3849487304688 +1769682012,308360704,0.0,-0.0,569.3849487304688 +1769682012,355533824,0.0,-0.0,569.3849487304688 +1769682012,375906560,0.0,-0.0,569.3849487304688 +1769682012,399995904,0.0,-0.0,569.3849487304688 +1769682012,451935232,0.0,-0.0,569.3849487304688 +1769682012,475962624,0.0,-0.0,569.3849487304688 +1769682012,511308544,0.0,-0.0,569.3849487304688 +1769682012,554384128,0.0,-0.0,569.3849487304688 +1769682012,572859904,0.0,-0.0,569.3849487304688 +1769682012,608497408,0.0,-0.0,569.3849487304688 +1769682012,646467584,0.0,-0.0,569.3849487304688 +1769682012,669081344,0.0,-0.0,569.3849487304688 +1769682012,709002496,0.0,-0.0,569.3849487304688 +1769682012,746405120,0.0,-0.0,569.3849487304688 +1769682012,775781120,0.0,-0.0,569.3849487304688 +1769682012,808895232,0.0,-0.0,569.3849487304688 +1769682012,852572928,0.0,-0.0,569.3849487304688 +1769682012,876762624,0.0,-0.0,569.3849487304688 +1769682012,908988928,0.0,-0.0,569.3849487304688 +1769682012,947235328,0.0,-0.0,569.3849487304688 +1769682012,979264256,0.0,-0.0,569.3849487304688 +1769682013,8980992,0.0,-0.0,569.3849487304688 +1769682013,42661376,0.0,-0.0,569.3849487304688 +1769682013,66936576,0.0,-0.0,569.3849487304688 +1769682013,109064192,0.0,-0.0,569.3849487304688 +1769682013,143434752,0.0,-0.0,569.3849487304688 +1769682013,175307776,0.0,-0.0,569.3849487304688 +1769682013,212890112,0.0,-0.0,569.3849487304688 +1769682013,257614592,0.0,-0.0,569.3849487304688 +1769682013,267284992,0.0,-0.0,569.3849487304688 +1769682013,308487424,0.0,-0.0,569.3849487304688 +1769682013,362421248,0.0,-0.0,569.3849487304688 +1769682013,379762176,0.0,-0.0,569.3849487304688 +1769682013,408749568,0.0,-0.0,569.3849487304688 +1769682013,445525760,0.0,-0.0,569.3849487304688 +1769682013,476374272,0.0,-0.0,569.3849487304688 +1769682013,510556928,0.0,-0.0,569.3849487304688 +1769682013,548176128,0.0,-0.0,569.3849487304688 +1769682013,576049920,0.0,-0.0,569.3849487304688 +1769682013,613592064,0.0,-0.0,569.3849487304688 +1769682013,658866432,0.0,-0.0,569.3849487304688 +1769682013,668812032,0.0,-0.0,569.3849487304688 +1769682013,708560896,0.0,-0.0,569.3849487304688 +1769682013,753995776,0.0,-0.0,569.3849487304688 +1769682013,776591872,0.0,-0.0,569.3849487304688 +1769682013,809442816,0.0,-0.0,569.3849487304688 +1769682013,842308864,0.0,-0.0,569.3849487304688 +1769682013,877677056,0.0,-0.0,569.3849487304688 +1769682013,909456640,0.0,-0.0,569.3849487304688 +1769682013,961141760,0.0,-0.0,569.3849487304688 +1769682013,967884544,0.0,-0.0,569.3849487304688 +1769682014,13824,0.0,-0.0,569.3849487304688 +1769682014,60951552,0.0,-0.0,569.3849487304688 +1769682014,72105984,0.0,-0.0,569.3849487304688 +1769682014,109562368,0.0,-0.0,569.3849487304688 +1769682014,162879488,0.0,-0.0,569.3849487304688 +1769682014,174462208,0.0,-0.0,569.3849487304688 +1769682014,209085184,0.0,-0.0,569.3849487304688 +1769682014,243574784,0.0,-0.0,569.3849487304688 +1769682014,275991552,0.0,-0.0,569.3849487304688 +1769682014,309744128,0.0,-0.0,569.3849487304688 +1769682014,353015296,0.0,-0.0,569.3849487304688 +1769682014,375981056,0.0,-0.0,569.3849487304688 +1769682014,408406784,0.0,-0.0,569.3849487304688 +1769682014,459114752,0.0,-0.0,569.3849487304688 +1769682014,468640512,0.0,-0.0,569.3849487304688 +1769682014,508637440,0.0,-0.0,569.3849487304688 +1769682014,543428352,0.0,-0.0,569.3849487304688 +1769682014,577775360,0.0,-0.0,569.3849487304688 +1769682014,609924608,0.0,-0.0,569.3849487304688 +1769682014,644710656,0.0,-0.0,569.3849487304688 +1769682014,675723520,0.0,-0.0,569.3849487304688 +1769682014,708867840,0.0,-0.0,569.3849487304688 +1769682014,742886400,0.0,-0.0,569.3849487304688 +1769682014,776319232,0.0,-0.0,569.3849487304688 +1769682014,812282368,0.0,-0.0,569.3849487304688 +1769682014,845304576,0.0,-0.0,569.3849487304688 +1769682014,877685504,0.0,-0.0,569.3849487304688 +1769682014,910222848,0.0,-0.0,569.3849487304688 +1769682014,957992960,0.0,-0.0,569.3849487304688 +1769682014,969115392,0.0,-0.0,569.3849487304688 +1769682015,10092032,0.0,-0.0,569.3849487304688 +1769682015,43204608,0.0,-0.0,569.3849487304688 +1769682015,77753344,0.0,-0.0,569.3849487304688 +1769682015,109543680,0.0,-0.0,569.3849487304688 +1769682015,144401664,0.0,-0.0,569.3849487304688 +1769682015,178896384,0.0,-0.0,569.3849487304688 +1769682015,209269504,0.0,-0.0,569.3849487304688 +1769682015,245459712,0.0,-0.0,569.3849487304688 +1769682015,278455808,0.0,-0.0,569.3849487304688 +1769682015,313575424,0.0,-0.0,569.3849487304688 +1769682015,348885760,0.0,-0.0,569.3849487304688 +1769682015,375457792,0.0,-0.0,569.3849487304688 +1769682015,409125632,0.0,-0.0,569.3849487304688 +1769682015,453744128,0.0,-0.0,569.3849487304688 +1769682015,475828992,0.0,-0.0,569.3849487304688 +1769682015,509189120,0.0,-0.0,569.3849487304688 +1769682015,543340288,0.0,-0.0,569.3849487304688 +1769682015,579919616,0.0,-0.0,569.3849487304688 +1769682015,611710464,0.0,-0.0,569.3849487304688 +1769682015,645071360,0.0,-0.0,569.3849487304688 +1769682015,675676416,0.0,-0.0,569.3849487304688 +1769682015,708974848,0.0,-0.0,569.3849487304688 +1769682015,754650624,0.0,-0.0,569.3849487304688 +1769682015,775636736,0.0,-0.0,569.3849487304688 +1769682015,808608000,0.0,-0.0,569.3849487304688 +1769682015,861485056,0.0,-0.0,569.3849487304688 +1769682015,868991744,0.0,-0.0,569.3849487304688 +1769682015,910497792,0.0,-0.0,569.3849487304688 +1769682015,944608768,0.0,-0.0,569.3849487304688 +1769682015,979958016,0.0,-0.0,569.3849487304688 +1769682016,8975104,0.0,-0.0,569.3849487304688 +1769682016,44931584,0.0,-0.0,569.3849487304688 +1769682016,75618048,0.0,-0.0,569.3849487304688 +1769682016,109694976,0.0,-0.0,569.3849487304688 +1769682016,144407808,0.0,-0.0,569.3849487304688 +1769682016,176874496,0.0,-0.0,569.3849487304688 +1769682016,209109248,0.0,-0.0,569.3849487304688 +1769682016,265109760,0.0,-0.0,569.3849487304688 +1769682016,274155264,0.0,-0.0,569.3849487304688 +1769682016,309134848,0.0,-0.0,569.3849487304688 +1769682016,342443008,0.0,-0.0,569.3849487304688 +1769682016,376755712,0.0,-0.0,569.3849487304688 +1769682016,410583552,0.0,-0.0,569.3849487304688 +1769682016,456397312,0.0,-0.0,569.3849487304688 +1769682016,475862016,0.0,-0.0,569.3849487304688 +1769682016,509884672,0.0,-0.0,569.3849487304688 +1769682016,551685376,0.0,-0.0,569.3849487304688 +1769682016,576078592,0.0,-0.0,569.3849487304688 +1769682016,608886784,0.0,-0.0,569.3849487304688 +1769682016,643988992,0.0,-0.0,569.3849487304688 +1769682016,665050112,0.0,-0.0,569.3849487304688 +1769682016,713223168,0.0,-0.0,569.3849487304688 +1769682016,746755840,0.0,-0.0,569.3849487304688 +1769682016,828164608,0.0,-0.0,569.3849487304688 +1769682016,830391808,0.0,-0.0,569.3849487304688 +1769682016,863160576,0.0,-0.0,569.3849487304688 +1769682016,870770944,0.0,-0.0,569.3849487304688 +1769682016,910422528,0.0,-0.0,569.3849487304688 +1769682016,943827968,0.0,-0.0,569.3849487304688 +1769682016,975929856,0.0,-0.0,569.3849487304688 +1769682017,9383936,0.0,-0.0,569.3849487304688 +1769682017,48541952,0.0,-0.0,569.3849487304688 +1769682017,76783616,0.0,-0.0,569.3849487304688 +1769682017,109331968,0.0,-0.0,569.3849487304688 +1769682017,158212608,0.0,-0.0,569.3849487304688 +1769682017,169605120,0.0,-0.0,569.3849487304688 +1769682017,208920064,0.0,-0.0,569.3849487304688 +1769682017,243268864,0.0,-0.0,569.3849487304688 +1769682017,275956992,0.0,-0.0,569.3849487304688 +1769682017,309727488,0.0,-0.0,569.3849487304688 +1769682017,357306112,0.0,-0.0,569.3849487304688 +1769682017,383682304,0.0,-0.0,569.3849487304688 +1769682017,409618432,0.0,-0.0,569.3849487304688 +1769682017,445664768,0.0,-0.0,569.3849487304688 +1769682017,476822528,0.0,-0.0,569.3849487304688 +1769682017,510077440,0.0,-0.0,569.3849487304688 +1769682017,549352960,0.0,-0.0,569.3849487304688 +1769682017,576484096,0.0,-0.0,569.3849487304688 +1769682017,609178368,0.0,-0.0,569.3849487304688 +1769682017,662101248,0.0,-0.0,569.3849487304688 +1769682017,668743936,0.0,-0.0,569.3849487304688 +1769682017,708879616,0.0,-0.0,569.3849487304688 +1769682017,743879424,0.0,-0.0,569.3849487304688 +1769682017,776214784,0.0,-0.0,569.3849487304688 +1769682017,809252864,0.0,-0.0,569.3849487304688 +1769682017,845326592,0.0,-0.0,569.3849487304688 +1769682017,876781312,0.0,-0.0,569.3849487304688 +1769682017,914567168,0.0,-0.0,569.3849487304688 +1769682017,946809600,0.0,-0.0,569.3849487304688 +1769682017,976403712,0.0,-0.0,569.3849487304688 +1769682018,8882688,0.0,-0.0,569.3849487304688 +1769682018,57296896,0.0,-0.0,569.3849487304688 +1769682018,66685952,0.0,-0.0,569.3849487304688 +1769682018,110140928,0.0,-0.0,569.3849487304688 +1769682018,142674688,0.0,-0.0,569.3849487304688 +1769682018,180656896,0.0,-0.0,569.3849487304688 +1769682018,209013248,0.0,-0.0,569.3849487304688 +1769682018,244921088,0.0,-0.0,569.3849487304688 +1769682018,277340928,0.0,-0.0,569.3849487304688 +1769682018,312886784,0.0,-0.0,569.3849487304688 +1769682018,353472000,0.00963905081152916,0.0038882032968103886,569.3850708007812 +1769682018,377942016,0.020210010930895805,0.00901066418737173,569.3860473632812 +1769682018,409864448,0.03129139170050621,0.012583667412400246,569.3878784179688 +1769682018,463794176,0.046559493988752365,0.014734799042344093,569.3907470703125 +1769682018,473165312,0.05780423432588577,0.015113649889826775,569.392822265625 +1769682018,509708288,0.06921159476041794,0.014711441472172737,569.3945922851562 +1769682018,548221952,0.08465200662612915,0.01368725299835205,569.396240234375 +1769682018,576468992,0.09643234312534332,0.012721788138151169,569.3968505859375 +1769682018,609244416,0.10836578905582428,0.01174214482307434,569.39697265625 +1769682018,646269696,0.12459100037813187,0.010521039366722107,569.3964233398438 +1769682018,675729408,0.13693653047084808,0.00967089831829071,569.3956909179688 +1769682018,715028480,0.1493261158466339,0.008894070982933044,569.3946533203125 +1769682018,750859520,0.16531477868556976,0.008028239011764526,569.3931274414062 +1769682018,775893760,0.1771790087223053,0.007413260638713837,569.3919677734375 +1769682018,808829184,0.18889310956001282,0.0068847015500068665,569.3908081054688 +1769682018,858827264,0.20497219264507294,0.006218567490577698,569.3895874023438 +1769682018,865270016,0.21297457814216614,0.005882948637008667,569.3890380859375 +1769682018,912216576,0.22905504703521729,0.005356132984161377,569.3881225585938 +1769682018,954541312,0.2443806231021881,0.004935204982757568,569.3875732421875 +1769682018,982667264,0.2542468011379242,0.004653647541999817,569.3875122070312 +1769682019,9133056,0.26301226019859314,0.004430167376995087,569.3876342773438 +1769682019,62677504,0.27643805742263794,0.004156246781349182,569.3883666992188 +1769682019,72739840,0.28907084465026855,0.004025071859359741,569.388916015625 +1769682019,100164608,0.2973051965236664,0.003893539309501648,569.3893432617188 +1769682019,148498688,0.31804442405700684,0.0037523210048675537,569.390625 +1769682019,178371328,0.33059680461883545,0.0036843419075012207,569.3916015625 +1769682019,209343488,0.3429432511329651,0.0036125928163528442,569.3927612304688 +1769682019,248334336,0.35973021388053894,0.003522023558616638,569.3945922851562 +1769682019,278630144,0.3724035322666168,0.003471165895462036,569.396240234375 +1769682019,309206016,0.3850468397140503,0.0034292638301849365,569.3980102539062 +1769682019,342484992,0.4019630253314972,0.0033818185329437256,569.4006958007812 +1769682019,376893952,0.41457265615463257,0.003342658281326294,569.4029541015625 +1769682019,410846720,0.4273275136947632,0.003273293375968933,569.4053955078125 +1769682019,446523392,0.44413766264915466,0.003113269805908203,569.4088745117188 +1769682019,480477952,0.45669275522232056,0.00306093692779541,569.4117431640625 +1769682019,509204992,0.46934008598327637,0.0029453039169311523,569.414794921875 +1769682019,554383104,0.4861355423927307,0.0027658194303512573,569.4191284179688 +1769682019,576036864,0.49872374534606934,0.0026638060808181763,569.422607421875 +1769682019,612462592,0.5112838745117188,0.0025794953107833862,569.42626953125 +1769682019,649218560,0.5279158353805542,0.002412661910057068,569.431396484375 +1769682019,676426240,0.5403468012809753,0.00232754647731781,569.4354858398438 +1769682019,709230848,0.552673876285553,0.0021771490573883057,569.439697265625 +1769682019,760854784,0.5692882537841797,0.002044767141342163,569.4456176757812 +1769682019,770100480,0.5775577425956726,0.002010822296142578,569.44873046875 +1769682019,809977600,0.594025731086731,0.001890331506729126,569.4550170898438 +1769682019,844037376,0.6103975772857666,0.0017547607421875,569.4617309570312 +1769682019,879037440,0.6225874423980713,0.001660376787185669,569.4668579101562 +1769682019,911650048,0.6347853541374207,0.0015984773635864258,569.47216796875 +1769682019,949195264,0.6510071158409119,0.0014482736587524414,569.4795532226562 +1769682019,976909568,0.6629921793937683,0.0013468265533447266,569.4851684570312 +1769682020,11323136,0.6750698089599609,0.0012751221656799316,569.4909057617188 +1769682020,58280448,0.690972626209259,0.0011684298515319824,569.4988403320312 +1769682020,71481088,0.6988595724105835,0.0011286437511444092,569.5029296875 +1769682020,111899648,0.7142924070358276,0.000997692346572876,569.5111694335938 +1769682020,160490752,0.7296130657196045,0.0009110569953918457,569.5196533203125 +1769682020,176830208,0.7410564422607422,0.0008169412612915039,569.5261840820312 +1769682020,200724224,0.7485756278038025,0.0007818043231964111,569.530517578125 +1769682020,267350784,0.7674989104270935,0.0006407201290130615,569.5416870117188 +1769682020,274970624,0.7786628007888794,0.000598520040512085,569.5484619140625 +1769682020,299857920,0.786003589630127,0.0005528032779693604,569.5530395507812 +1769682020,363693824,0.8042759299278259,0.000466763973236084,569.564697265625 +1769682020,373732096,0.8151874542236328,0.000398486852645874,569.57177734375 +1769682020,409488640,0.8259691596031189,0.00037151575088500977,569.5789184570312 +1769682020,459198976,0.8401409387588501,0.00034877657890319824,569.5885620117188 +1769682020,467980544,0.8471816778182983,0.0003236234188079834,569.5933837890625 +1769682020,509995008,0.8612171411514282,0.00024640560150146484,569.6031494140625 +1769682020,545180928,0.8750429153442383,0.0001806020736694336,569.6129150390625 +1769682020,573110016,0.8818517923355103,0.00014221668243408203,569.6178588867188 +1769682020,609743104,0.8954381942749023,7.647275924682617e-05,569.6278686523438 +1769682020,644400384,0.9087090492248535,2.8401613235473633e-05,569.6378784179688 +1769682020,678212864,0.9185709953308105,-5.27501106262207e-06,569.6454467773438 +1769682020,710027264,0.9283717274665833,-4.437565803527832e-05,569.653076171875 +1769682020,756964096,0.9420464038848877,-0.000674813985824585,569.6644897460938 +1769682020,778515200,0.9523967504501343,-0.0006685256958007812,569.67626953125 +1769682020,810356224,0.9627034664154053,-0.0005375146865844727,569.6902465820312 +1769682020,859299328,0.976203203201294,-0.00035879015922546387,569.71142578125 +1769682020,873161472,0.9828912019729614,-0.00020202994346618652,569.7227172851562 +1769682020,911720704,0.9961962699890137,-5.46574592590332e-05,569.746337890625 +1769682020,943036672,1.0093625783920288,4.583597183227539e-05,569.77099609375 +1769682020,976241664,1.019111156463623,0.00015661120414733887,569.7897338867188 +1769682021,11999232,1.0287154912948608,0.00024899840354919434,569.8087158203125 +1769682021,46505984,1.0410023927688599,0.00029599666595458984,569.8341674804688 +1769682021,76540416,1.050072193145752,0.0003516674041748047,569.8531494140625 +1769682021,109599232,1.0590667724609375,0.00041943788528442383,569.8720703125 +1769682021,161479168,1.0709161758422852,0.0005351603031158447,569.8970947265625 +1769682021,172013568,1.0767099857330322,0.0006052255630493164,569.9094848632812 +1769682021,210874112,1.088144063949585,0.0006151199340820312,569.9341430664062 +1769682021,247316480,1.0993202924728394,0.0006768703460693359,569.9583129882812 +1769682021,277769216,1.107635259628296,0.0007089376449584961,569.9763793945312 +1769682021,309600000,1.1159093379974365,0.0008350610733032227,569.9940795898438 +1769682021,343551232,1.1267750263214111,0.0009257197380065918,570.0174560546875 +1769682021,376654848,1.1348093748092651,0.0009786486625671387,570.0347900390625 +1769682021,410927360,1.142700433731079,0.0010250210762023926,570.0519409179688 +1769682021,445985536,1.1536376476287842,0.00039833784103393555,570.0741577148438 +1769682021,476542976,1.162210464477539,-0.000638127326965332,570.0875244140625 +1769682021,512369664,1.1706992387771606,-0.0016736388206481934,570.0982666015625 +1769682021,558393856,1.181755542755127,-0.002892613410949707,570.1096801757812 +1769682021,568260608,1.1872248649597168,-0.003498256206512451,570.1144409179688 +1769682021,609369600,1.1980537176132202,-0.004607975482940674,570.12255859375 +1769682021,647580416,1.2086665630340576,-0.005419671535491943,570.12939453125 +1769682021,678950656,1.2164682149887085,-0.005872368812561035,570.1339721679688 +1769682021,710074880,1.224184513092041,-0.006252467632293701,570.1381225585938 +1769682021,761200640,1.2342007160186768,-0.006584107875823975,570.143310546875 +1769682021,776425472,1.24160635471344,-0.006773233413696289,570.1470336914062 +1769682021,809286400,1.2488266229629517,-0.00686955451965332,570.1506958007812 +1769682021,851734528,1.258319616317749,-0.006914675235748291,570.1554565429688 +1769682021,881456384,1.2653332948684692,-0.006907284259796143,570.1590576171875 +1769682021,909940480,1.272186040878296,-0.006901741027832031,570.16259765625 +1769682021,944397056,1.2810794115066528,-0.006790101528167725,570.1672973632812 +1769682021,976044032,1.287627935409546,-0.00670778751373291,570.1707763671875 +1769682022,9891584,1.2940423488616943,-0.006606757640838623,570.17431640625 +1769682022,58281728,1.3023005723953247,-0.006484031677246094,570.1788330078125 +1769682022,70839808,1.3063623905181885,-0.006422996520996094,570.1810302734375 +1769682022,109234688,1.3142986297607422,-0.006267666816711426,570.185302734375 +1769682022,165016064,1.3219280242919922,-0.006155133247375488,570.1893310546875 +1769682022,173906688,1.327533483505249,-0.006082713603973389,570.1922607421875 +1769682022,210400256,1.3329973220825195,-0.00602489709854126,570.1951293945312 +1769682022,252211968,1.3400907516479492,-0.005932509899139404,570.19873046875 +1769682022,278469120,1.3452608585357666,-0.005863487720489502,570.2013549804688 +1769682022,309937152,1.3503382205963135,-0.005833804607391357,570.2039184570312 +1769682022,349891072,1.356782078742981,-0.0058089494705200195,570.2073364257812 +1769682022,378356736,1.361559510231018,-0.005807816982269287,570.2098388671875 +1769682022,410752000,1.3661987781524658,-0.005770325660705566,570.2122802734375 +1769682022,463164416,1.372117042541504,-0.00576549768447876,570.215576171875 +1769682022,475961088,1.3763995170593262,-0.005698859691619873,570.2178955078125 +1769682022,510950912,1.3805235624313354,-0.005669713020324707,570.22021484375 +1769682022,546003968,1.3857985734939575,-0.005613863468170166,570.2229614257812 +1769682022,567844352,1.38837730884552,-0.005531370639801025,570.2242431640625 +1769682022,609457664,1.3933947086334229,-0.00550311803817749,570.2265625 +1769682022,647819264,1.3981637954711914,-0.005510389804840088,570.2286376953125 +1769682022,676432640,1.4018484354019165,-0.005817294120788574,570.230224609375 +1769682022,710038784,1.4053689241409302,-0.00605463981628418,570.23193359375 +1769682022,753816832,1.4098438024520874,-0.006459414958953857,570.2342529296875 +1769682022,776315136,1.4131042957305908,-0.006767928600311279,570.2360229492188 +1769682022,810235648,1.4162051677703857,-0.006992697715759277,570.2378540039062 +1769682022,847983104,1.4201807975769043,-0.007283568382263184,570.2403564453125 +1769682022,877674496,1.423040747642517,-0.007479190826416016,570.2423706054688 +1769682022,909826048,1.4258060455322266,-0.007583260536193848,570.244384765625 +1769682022,944297216,1.4291646480560303,-0.007718145847320557,570.2471923828125 +1769682022,967449856,1.4308050870895386,-0.0077522993087768555,570.2486572265625 +1769682023,11631616,1.4349595308303833,-0.008425712585449219,570.2513427734375 +1769682023,51687936,1.43901526927948,-0.008259296417236328,570.25341796875 +1769682023,78000384,1.4420115947723389,-0.008024275302886963,570.2548217773438 +1769682023,110402048,1.4448353052139282,-0.0077492594718933105,570.2560424804688 +1769682023,149427456,1.4484431743621826,-0.007448375225067139,570.2575073242188 +1769682023,176985088,1.450972080230713,-0.007249176502227783,570.258544921875 +1769682023,209675264,1.4530045986175537,-0.00708085298538208,570.2594604492188 +1769682023,259544064,1.4553520679473877,-0.0069068074226379395,570.260498046875 +1769682023,266912000,1.4564688205718994,-0.006808817386627197,570.260986328125 +1769682023,311222016,1.4586056470870972,-0.006687819957733154,570.261962890625 +1769682023,348101120,1.46038818359375,-0.0066176652908325195,570.2627563476562 +1769682023,371555072,1.461255431175232,-0.006569087505340576,570.26318359375 +1769682023,410250240,1.4628708362579346,-0.00655055046081543,570.2637939453125 +1769682023,448106752,1.4642748832702637,-0.0065007805824279785,570.2643432617188 +1769682023,476479744,1.465095043182373,-0.006479918956756592,570.2647094726562 +1769682023,500643584,1.4656414985656738,-0.006459712982177734,570.264892578125 +1769682023,547759616,1.4665926694869995,-0.006450831890106201,570.2652587890625 +1769682023,576055296,1.4670159816741943,-0.006396353244781494,570.265380859375 +1769682023,609672192,1.4673590660095215,-0.006432831287384033,570.2654418945312 +1769682023,650035200,1.4675931930541992,-0.006460309028625488,570.2655029296875 +1769682023,677083136,1.46766197681427,-0.006436705589294434,570.2655029296875 +1769682023,709906944,1.4676696062088013,-0.0064713358879089355,570.2654418945312 +1769682023,766795520,1.4674938917160034,-0.006406247615814209,570.2654418945312 +1769682023,774999552,1.4672491550445557,-0.00642627477645874,570.2654418945312 +1769682023,810286080,1.4668655395507812,-0.006418883800506592,570.2655029296875 +1769682023,845579776,1.4661850929260254,-0.006449103355407715,570.265625 +1769682023,876539904,1.4655284881591797,-0.0064386725425720215,570.2657470703125 +1769682023,910625536,1.464797019958496,-0.006431698799133301,570.2659912109375 +1769682023,949912320,1.4639121294021606,-0.006606400012969971,570.2666015625 +1769682023,979220992,1.463228702545166,-0.006471157073974609,570.2681274414062 +1769682024,9494784,1.4624919891357422,-0.006299257278442383,570.270263671875 +1769682024,48824320,1.461342215538025,-0.005999863147735596,570.2738037109375 +1769682024,78976768,1.4603530168533325,-0.00581049919128418,570.2767333984375 +1769682024,111081216,1.459296703338623,-0.005657374858856201,570.27978515625 +1769682024,143403008,1.4575475454330444,-0.005473434925079346,570.283935546875 +1769682024,176911360,1.4559658765792847,-0.0053931474685668945,570.2870483398438 +1769682024,210180352,1.4542919397354126,-0.005321085453033447,570.2901611328125 +1769682024,247812864,1.4518803358078003,-0.005165219306945801,570.2942504882812 +1769682024,276721152,1.4499311447143555,-0.005102753639221191,570.2972412109375 +1769682024,310908160,1.4479113817214966,-0.005037426948547363,570.300048828125 +1769682024,346422528,1.4450902938842773,-0.0049359798431396484,570.3037109375 +1769682024,376124160,1.4428856372833252,-0.004870891571044922,570.3062744140625 +1769682024,409735680,1.4405992031097412,-0.004857778549194336,570.308837890625 +1769682024,446251264,1.4373998641967773,-0.004820466041564941,570.3119506835938 +1769682024,477371136,1.4349311590194702,-0.004778146743774414,570.314208984375 +1769682024,509789184,1.4324043989181519,-0.004737377166748047,570.31640625 +1769682024,561978112,1.4288465976715088,-0.0046776533126831055,570.3190307617188 +1769682024,568792064,1.427140235900879,-0.00473630428314209,570.3203125 +1769682024,611080448,1.4238603115081787,-0.005158901214599609,570.3214111328125 +1769682024,645825024,1.4204686880111694,-0.005579590797424316,570.3208618164062 +1769682024,676946944,1.4178593158721924,-0.0058307647705078125,570.3195190429688 +1769682024,709777920,1.4151439666748047,-0.006087601184844971,570.3175659179688 +1769682024,757107456,1.4114354848861694,-0.006300687789916992,570.3140869140625 +1769682024,766074624,1.4095600843429565,-0.006425082683563232,570.3121337890625 +1769682024,810304512,1.4057164192199707,-0.006579220294952393,570.3076171875 +1769682024,860168704,1.4017140865325928,-0.006653845310211182,570.3026123046875 +1769682024,875788032,1.398675799369812,-0.006672859191894531,570.298583984375 +1769682024,910029056,1.3955953121185303,-0.006637096405029297,570.2943725585938 +1769682024,945895680,1.3914016485214233,-0.006598412990570068,570.2886352539062 +1769682024,967036672,1.3892947435379028,-0.0065847039222717285,570.28564453125 +1769682025,14262016,1.3849163055419922,-0.006494402885437012,570.2796020507812 +1769682025,46508288,1.3803998231887817,-0.006346166133880615,570.2733154296875 +1769682025,76677888,1.3770029544830322,-0.006285488605499268,570.2684326171875 +1769682025,110007552,1.373533844947815,-0.006217062473297119,570.263427734375 +1769682025,152466688,1.36881422996521,-0.006015360355377197,570.2564086914062 +1769682025,178351616,1.3652430772781372,-0.00590139627456665,570.2508544921875 +1769682025,209779456,1.361573576927185,-0.005802810192108154,570.2451171875 +1769682025,249698048,1.356640338897705,-0.0056459903717041016,570.2371215820312 +1769682025,278513920,1.3528919219970703,-0.005554318428039551,570.2308349609375 +1769682025,310361344,1.3490948677062988,-0.005461752414703369,570.2243041992188 +1769682025,344456192,1.3438917398452759,-0.005258440971374512,570.2152709960938 +1769682025,366577408,1.3412437438964844,-0.00521010160446167,570.2106323242188 +1769682025,410379776,1.3359510898590088,-0.0050969719886779785,570.2010498046875 +1769682025,458596096,1.3299224376678467,-0.004411220550537109,570.1909790039062 +1769682025,468074240,1.3265104293823242,-0.003742516040802002,570.1853637695312 +1769682025,501568256,1.3196752071380615,-0.0022454261779785156,570.173583984375 +1769682025,548381696,1.3127775192260742,-0.0008481144905090332,570.160888671875 +1769682025,579007744,1.3075554370880127,0.00010949373245239258,570.1509399414062 +1769682025,613205248,1.3023066520690918,0.000948786735534668,570.1407470703125 +1769682025,650180096,1.2952643632888794,0.0018725991249084473,570.1267700195312 +1769682025,677007872,1.2899545431137085,0.0024089813232421875,570.1160278320312 +1769682025,709657088,1.2845860719680786,0.00283128023147583,570.1051635742188 +1769682025,762062848,1.277322769165039,0.0032035112380981445,570.09033203125 +1769682025,769367808,1.2736775875091553,0.0033341050148010254,570.082763671875 +1769682025,811301120,1.2663185596466064,0.0035970211029052734,570.0675048828125 +1769682025,845297664,1.2588778734207153,0.003710627555847168,570.0520629882812 +1769682025,896216320,1.2532851696014404,0.0036906003952026367,570.040283203125 +1769682025,915953920,1.247652530670166,0.0036672353744506836,570.0285034179688 +1769682025,949428224,1.2401466369628906,0.003451824188232422,570.0127563476562 +1769682025,965853952,1.2365556955337524,0.0033254027366638184,570.0048828125 +1769682026,9931264,1.22934889793396,0.003306448459625244,569.9888916015625 +1769682026,59662080,1.2220090627670288,0.003249943256378174,569.9729614257812 +1769682026,67353600,1.218313455581665,0.0032047033309936523,569.9650268554688 +1769682026,112329472,1.2108241319656372,0.0031914710998535156,569.94921875 +1769682026,152102144,1.2032591104507446,0.0031793713569641113,569.933349609375 +1769682026,178870016,1.197577953338623,0.0031754374504089355,569.92138671875 +1769682026,210887424,1.191680669784546,0.003114759922027588,569.9093017578125 +1769682026,247811072,1.1835047006607056,0.0030919313430786133,569.8930053710938 +1769682026,277165824,1.1772501468658447,0.003103971481323242,569.880615234375 +1769682026,312314880,1.1709585189819336,0.0031049251556396484,569.8682250976562 +1769682026,360579584,1.1625046730041504,0.003117680549621582,569.8516845703125 +1769682026,371497472,1.1582728624343872,0.0030648112297058105,569.8433227539062 +1769682026,410829312,1.1497864723205566,0.003114044666290283,569.8267211914062 +1769682026,456234240,1.1433812379837036,0.0031099319458007812,569.8142700195312 +1769682026,473700096,1.1346864700317383,0.003108382225036621,569.797607421875 +1769682026,510818048,1.1281338930130005,0.00312119722366333,569.7850952148438 +1769682026,546595072,1.1193509101867676,0.0031461715698242188,569.768310546875 +1769682026,568272384,1.114918828010559,0.0030820369720458984,569.7598876953125 +1769682026,610980608,1.1060948371887207,0.00315701961517334,569.7429809570312 +1769682026,661186816,1.0972572565078735,0.00310593843460083,569.7258911132812 +1769682026,667794944,1.0928001403808594,0.003069758415222168,569.7173461914062 +1769682026,709958912,1.083855152130127,0.003171265125274658,569.7001342773438 +1769682026,752225280,1.0748409032821655,0.003210723400115967,569.6827392578125 +1769682026,777706496,1.0680482387542725,0.003205239772796631,569.669677734375 +1769682026,811253760,1.0612399578094482,0.003212064504623413,569.6564331054688 +1769682026,855318528,1.0521458387374878,0.003198176622390747,569.6387329101562 +1769682026,877013760,1.0453118085861206,0.003284662961959839,569.6253662109375 +1769682026,910053376,1.0379053354263306,0.0037120580673217773,569.6116333007812 +1769682026,960334336,1.0276094675064087,0.003562629222869873,569.5892944335938 +1769682026,967832064,1.0224577188491821,0.0033068954944610596,569.5767211914062 +1769682027,11836928,1.0120668411254883,0.002973586320877075,569.5494384765625 +1769682027,44439808,1.0016783475875854,0.002626180648803711,569.520263671875 +1769682027,79593216,0.9938756823539734,0.0023915469646453857,569.4974365234375 +1769682027,110434304,0.9861663579940796,0.002217620611190796,569.4740600585938 +1769682027,151532800,0.9759067296981812,0.0020374655723571777,569.4424438476562 +1769682027,177962752,0.9681947827339172,0.0018832981586456299,569.4183959960938 +1769682027,213708288,0.9608729481697083,0.0018936693668365479,569.3942260742188 +1769682027,261926912,0.9543876647949219,0.001827925443649292,569.362548828125 +1769682027,275143168,0.9495632648468018,0.001761108636856079,569.3382568359375 +1769682027,310466816,0.9447576403617859,0.0016674399375915527,569.313720703125 +1769682027,364397824,0.9383409023284912,0.0016127228736877441,569.28076171875 +1769682027,373976832,0.9335269927978516,0.0015704333782196045,569.256103515625 +1769682027,411624704,0.9286788702011108,0.0015349090099334717,569.2313842773438 +1769682027,445452032,0.9221639633178711,0.0014999806880950928,569.1985473632812 +1769682027,476713728,0.9171479940414429,0.0014852583408355713,569.174072265625 +1769682027,510582528,0.9121495485305786,0.0014577209949493408,569.1495971679688 +1769682027,548461312,0.905417799949646,0.0014188289642333984,569.1170654296875 +1769682027,567404288,0.9020519256591797,0.001373887062072754,569.1008911132812 +1769682027,644111360,0.895104169845581,0.0013123154640197754,569.0687866210938 +1769682027,656914432,0.8881554007530212,0.0012467801570892334,569.0368041992188 +1769682027,684760064,0.8827405571937561,0.0012216567993164062,569.0130004882812 +1769682027,698005248,0.8791128396987915,0.001092463731765747,568.9971923828125 +1769682027,751879168,0.8699343800544739,0.001028597354888916,568.958251953125 +1769682027,767991552,0.8662237524986267,0.0009391605854034424,568.9428100585938 +1769682027,813732096,0.8586432933807373,0.000856935977935791,568.9124145507812 +1769682027,866561024,0.8510111570358276,0.0007573366165161133,568.8824462890625 +1769682027,875343616,0.8450344800949097,0.0006998777389526367,568.8602294921875 +1769682027,910790144,0.8390195369720459,0.0006293356418609619,568.8381958007812 +1769682027,963478784,0.8308883309364319,0.0004868805408477783,568.809326171875 +1769682027,969682176,0.8268053531646729,0.00042572617530822754,568.794921875 +1769682028,10211584,0.8182531595230103,0.0006546676158905029,568.7664794921875 +1769682028,49096448,0.8086415529251099,0.0016969144344329834,568.7416381835938 +1769682028,80280832,0.8013898134231567,0.002469360828399658,568.7257080078125 +1769682028,110780160,0.7939980030059814,0.00321120023727417,568.7115478515625 +1769682028,146125056,0.7840884923934937,0.004038304090499878,568.6947631835938 +1769682028,177079040,0.7766256332397461,0.0045822858810424805,568.6831665039062 +1769682028,211643392,0.7691256403923035,0.005023211240768433,568.67236328125 +1769682028,254212352,0.759049117565155,0.005441337823867798,568.6587524414062 +1769682028,277073920,0.7514827251434326,0.005681425333023071,568.6491088867188 +1769682028,310291456,0.7438399195671082,0.005835920572280884,568.6397705078125 +1769682028,360554240,0.7335982322692871,0.005937367677688599,568.6276245117188 +1769682028,368471040,0.7284496426582336,0.005967527627944946,568.6217651367188 +1769682028,412475136,0.7180731296539307,0.00596049427986145,568.610107421875 +1769682028,445781760,0.7076643109321594,0.005873769521713257,568.5985107421875 +1769682028,481013504,0.6998646855354309,0.005782127380371094,568.5899658203125 +1769682028,510216192,0.6920592188835144,0.0056719183921813965,568.5814819335938 +1769682028,560651776,0.6816635727882385,0.005577415227890015,568.5701904296875 +1769682028,566945792,0.6764436960220337,0.0054922401905059814,568.5646362304688 +1769682028,614487296,0.6659978628158569,0.005387485027313232,568.5535888671875 +1769682028,660991744,0.6554663777351379,0.00529053807258606,568.5426635742188 +1769682028,674107648,0.6475256681442261,0.005171984434127808,568.5345458984375 +1769682028,710073344,0.6395736932754517,0.005112737417221069,568.5264892578125 +1769682028,760282368,0.6291705369949341,0.004980891942977905,568.5158081054688 +1769682028,768824320,0.6239858865737915,0.004955947399139404,568.5105590820312 +1769682028,811567360,0.6135975122451782,0.004886448383331299,568.5000610351562 +1769682028,845769728,0.603320837020874,0.004808485507965088,568.4896850585938 +1769682028,882558464,0.595665454864502,0.00478518009185791,568.48193359375 +1769682028,911276544,0.5881590247154236,0.004753082990646362,568.4742431640625 +1769682028,945028096,0.5780695080757141,0.004675716161727905,568.4640502929688 +1769682028,978710272,0.5705798864364624,0.004644900560379028,568.4564819335938 +1769682029,12293632,0.5630281567573547,0.004650980234146118,568.4489135742188 +1769682029,56102400,0.5529813170433044,0.004574805498123169,568.43896484375 +1769682029,76901376,0.5453642010688782,0.004523545503616333,568.4315185546875 +1769682029,110517504,0.5377165079116821,0.0044913142919540405,568.4241943359375 +1769682029,157400064,0.5275828838348389,0.004421904683113098,568.4146118164062 +1769682029,167223808,0.5225407481193542,0.0044068992137908936,568.4098510742188 +1769682029,210168320,0.5124862790107727,0.004338309168815613,568.4005737304688 +1769682029,247192320,0.5023321509361267,0.0042601078748703,568.391357421875 +1769682029,282624000,0.4946204721927643,0.004167869687080383,568.384765625 +1769682029,310194944,0.4869912266731262,0.004110455513000488,568.378173828125 +1769682029,347652608,0.47687584161758423,0.003982469439506531,568.3696899414062 +1769682029,377350912,0.4692350924015045,0.003923505544662476,568.363525390625 +1769682029,411024384,0.4615742862224579,0.0038654357194900513,568.3574829101562 +1769682029,448530176,0.4513756334781647,0.0037002116441726685,568.3497924804688 +1769682029,477465600,0.4437216818332672,0.0036225616931915283,568.3441162109375 +1769682029,511297536,0.4345254898071289,0.0035324394702911377,568.338623046875 +1769682029,560945152,0.4181818664073944,0.0033995360136032104,568.33203125 +1769682029,588105216,0.40223538875579834,0.0032590925693511963,568.3275756835938 +1769682029,599667712,0.39161762595176697,0.0032034069299697876,568.324951171875 +1769682029,650412032,0.3650931417942047,0.003013819456100464,568.3193969726562 +1769682029,677948160,0.3504143953323364,0.002849876880645752,568.3164672851562 +1769682029,712882176,0.33759579062461853,0.0022565722465515137,568.3139038085938 +1769682029,749582592,0.319652259349823,0.0016498416662216187,568.3112182617188 +1769682029,779251968,0.30560117959976196,0.0012362897396087646,568.3099365234375 +1769682029,810401792,0.29346051812171936,0.0009064674377441406,568.3088989257812 +1769682029,860771072,0.27422070503234863,0.00036190450191497803,568.3080444335938 +1769682029,870544384,0.26522013545036316,0.00012759119272232056,568.307861328125 +1769682029,911330048,0.2497471570968628,-0.0002217516303062439,568.3076171875 +1769682029,954052864,0.2318413108587265,-0.0004913285374641418,568.3076782226562 +1769682029,978973184,0.2193201184272766,-0.0006867200136184692,568.3079223632812 +1769682030,10588928,0.20785000920295715,-0.0008244365453720093,568.308349609375 +1769682030,50333696,0.1947534829378128,-0.000963069498538971,568.3088989257812 +1769682030,76921344,0.18529489636421204,-0.0010307952761650085,568.309326171875 +1769682030,112819200,0.17582686245441437,-0.0010975450277328491,568.3097534179688 +1769682030,155048192,0.16318705677986145,-0.0011465847492218018,568.310302734375 +1769682030,177158400,0.15369611978530884,-0.001230582594871521,568.3108520507812 +1769682030,210197760,0.14420393109321594,-0.001211009919643402,568.3114013671875 +1769682030,255967744,0.126634418964386,-0.0012980923056602478,568.3125 +1769682030,265013760,0.1184837818145752,-0.0012944899499416351,568.3131713867188 +1769682030,312213760,0.10499685257673264,-0.0012997016310691833,568.3146362304688 +1769682030,346783232,0.0923539251089096,-0.001350313425064087,568.3161010742188 +1769682030,379937536,0.08287496119737625,-0.0013518482446670532,568.317138671875 +1769682030,410745344,0.07339383661746979,-0.001361347734928131,568.3181762695312 +1769682030,450412544,0.06074490398168564,-0.0014066118746995926,568.3196411132812 +1769682030,477702400,0.051249679177999496,-0.0013838186860084534,568.3207397460938 +1769682030,514553088,0.04175219684839249,-0.001406269147992134,568.3219604492188 +1769682030,557469952,0.0,-0.0,568.323486328125 +1769682030,570848000,0.0,-0.0,568.323486328125 +1769682030,610797312,0.0,-0.0,568.323486328125 +1769682030,663069184,0.0,-0.0,568.323486328125 +1769682030,669417984,0.0,-0.0,568.323486328125 +1769682030,711440384,0.0,-0.0,568.323486328125 +1769682030,748741888,0.0,-0.0,568.323486328125 +1769682030,778473472,0.0,-0.0,568.323486328125 +1769682030,810345472,0.0,-0.0,568.323486328125 +1769682030,849885440,0.0,-0.0,568.323486328125 +1769682030,877724160,0.0,-0.0,568.323486328125 +1769682030,916821504,0.0,-0.0,568.323486328125 +1769682030,949130240,0.0,-0.0,568.323486328125 +1769682030,977305088,0.0,-0.0,568.323486328125 +1769682031,10384896,0.0,-0.0,568.323486328125 +1769682031,57372928,0.0,-0.0,568.323486328125 +1769682031,77635584,0.0,-0.0,568.323486328125 +1769682031,111345408,0.0,-0.0,568.323486328125 +1769682031,143959040,0.0,-0.0,568.323486328125 +1769682031,184395008,0.0,-0.0,568.323486328125 +1769682031,210745856,0.0,-0.0,568.323486328125 +1769682031,250777600,0.0,-0.0,568.323486328125 +1769682031,277001728,0.0,-0.0,568.323486328125 +1769682031,310998272,0.0,-0.0,568.323486328125 +1769682031,349408000,0.0,-0.0,568.323486328125 +1769682031,378355712,0.0,-0.0,568.323486328125 +1769682031,410254336,0.0,-0.0,568.323486328125 +1769682031,461301248,0.0,-0.0,568.323486328125 +1769682031,471190528,0.0,-0.0,568.323486328125 +1769682031,500407552,0.0,-0.0,568.323486328125 +1769682031,546347520,0.0,-0.0,568.323486328125 +1769682031,580910080,0.0,-0.0,568.323486328125 +1769682031,610586624,0.0,-0.0,568.323486328125 +1769682031,648016128,0.0,-0.0,568.323486328125 +1769682031,677543424,0.0,-0.0,568.323486328125 +1769682031,714375680,0.0,-0.0,568.323486328125 +1769682031,750040832,0.0,-0.0,568.323486328125 +1769682031,776999168,0.0,-0.0,568.323486328125 +1769682031,810507008,0.0,-0.0,568.323486328125 +1769682031,853347328,0.0,-0.0,568.323486328125 +1769682031,878041088,0.0,-0.0,568.323486328125 +1769682031,913138432,0.0,-0.0,568.323486328125 +1769682031,946487040,0.0,-0.0,568.323486328125 +1769682031,978632192,0.0,-0.0,568.323486328125 +1769682032,10790912,0.0,-0.0,568.323486328125 +1769682032,48818176,0.0,-0.0,568.323486328125 +1769682032,82276096,0.0,-0.0,568.323486328125 +1769682032,107709440,0.0,-0.0,568.323486328125 +1769682032,154711040,0.0,-0.0,568.323486328125 +1769682032,179374336,0.0,-0.0,568.323486328125 +1769682032,212811776,0.0,-0.0,568.323486328125 +1769682032,262229760,0.0,-0.0,568.323486328125 +1769682032,275307776,0.0,-0.0,568.323486328125 +1769682032,310843904,0.0,-0.0,568.323486328125 +1769682032,346019328,0.0,-0.0,568.323486328125 +1769682032,377274112,0.0,-0.0,568.323486328125 +1769682032,410601728,0.0,-0.0,568.323486328125 +1769682032,444560128,0.0,-0.0,568.323486328125 +1769682032,477168384,0.0,-0.0,568.323486328125 +1769682032,502210816,0.0,-0.0,568.323486328125 +1769682032,545907968,0.0,-0.0,568.323486328125 +1769682032,577404928,0.0,-0.0,568.323486328125 +1769682032,610657280,0.0,-0.0,568.323486328125 +1769682032,647803904,0.0,-0.0,568.323486328125 +1769682032,680634112,0.0,-0.0,568.323486328125 +1769682032,710440448,0.0,-0.0,568.323486328125 +1769682032,745906176,0.0,-0.0,568.323486328125 +1769682032,777254912,0.0,-0.0,568.323486328125 +1769682032,811275264,0.0,-0.0,568.323486328125 +1769682032,844671744,0.0,-0.0,568.323486328125 +1769682032,877242624,0.0,-0.0,568.323486328125 +1769682032,911954944,0.0,-0.0,568.323486328125 +1769682032,945617408,0.0,-0.0,568.323486328125 +1769682032,977945600,0.0,-0.0,568.323486328125 +1769682033,11794432,0.0,-0.0,568.323486328125 +1769682033,60879104,0.0,-0.0,568.323486328125 +1769682033,69714432,0.0,-0.0,568.323486328125 +1769682033,111066880,0.0,-0.0,568.323486328125 +1769682033,158437632,0.0,-0.0,568.323486328125 +1769682033,166098688,0.0,-0.0,568.323486328125 +1769682033,210859520,0.0,-0.0,568.323486328125 +1769682033,244612608,0.0,-0.0,568.323486328125 +1769682033,281619968,0.0,-0.0,568.323486328125 +1769682033,311275008,0.0,-0.0,568.323486328125 +1769682033,347122176,0.0,-0.0,568.323486328125 +1769682033,377266944,0.0,-0.0,568.323486328125 +1769682033,413937920,0.0,-0.0,568.323486328125 +1769682033,450033408,0.0,-0.0,568.323486328125 +1769682033,478630400,0.0,-0.0,568.323486328125 +1769682033,511009024,0.0,-0.0,568.323486328125 +1769682033,556636416,0.0,-0.0,568.323486328125 +1769682033,577266944,0.0,-0.0,568.323486328125 +1769682033,611532288,0.0,-0.0,568.323486328125 +1769682033,644963584,0.0,-0.0,568.323486328125 +1769682033,680730624,0.0,-0.0,568.323486328125 +1769682033,710942208,0.0,-0.0,568.323486328125 +1769682033,747179520,0.0,-0.0,568.323486328125 +1769682033,777428992,0.0,-0.0,568.323486328125 +1769682033,811333632,0.0,-0.0,568.323486328125 +1769682033,848051968,0.0,-0.0,568.323486328125 +1769682033,877368832,0.0,-0.0,568.323486328125 +1769682033,911312384,0.0,-0.0,568.323486328125 +1769682033,964037120,0.0,-0.0,568.323486328125 +1769682033,972689664,0.0,-0.0,568.323486328125 +1769682034,12852480,0.0,-0.0,568.323486328125 +1769682034,51555584,0.0,-0.0,568.323486328125 +1769682034,77428224,0.0,-0.0,568.323486328125 +1769682034,111391744,0.0,-0.0,568.323486328125 +1769682034,146973440,0.0,-0.0,568.323486328125 +1769682034,179236096,0.0,-0.0,568.323486328125 +1769682034,211236352,0.0,-0.0,568.323486328125 +1769682034,250308864,0.0,-0.0,568.323486328125 +1769682034,279852032,0.0,-0.0,568.323486328125 +1769682034,311110144,0.0,-0.0,568.323486328125 +1769682034,346388992,0.0,-0.0,568.323486328125 +1769682034,377884928,0.0,-0.0,568.323486328125 +1769682034,410956032,0.0,-0.0,568.323486328125 +1769682034,445188864,0.0,-0.0,568.323486328125 +1769682034,478537472,0.0,-0.0,568.323486328125 +1769682034,499556864,0.0,-0.0,568.323486328125 +1769682034,558608896,0.0,-0.0,568.323486328125 +1769682034,566222336,0.0,-0.0,568.323486328125 +1769682034,610942720,0.0,-0.0,568.323486328125 +1769682034,649748992,0.0,-0.0,568.323486328125 +1769682034,678623744,0.0,-0.0,568.323486328125 +1769682034,711161856,0.0,-0.0,568.323486328125 +1769682034,744919040,0.0,-0.0,568.323486328125 +1769682034,770488576,0.0,-0.0,568.323486328125 +1769682034,810967552,0.0,-0.0,568.323486328125 +1769682034,844198656,0.0,-0.0,568.323486328125 +1769682034,877826816,0.0,-0.0,568.323486328125 +1769682034,911442944,0.0,-0.0,568.323486328125 +1769682034,947166464,0.0,-0.0,568.323486328125 +1769682034,977293568,0.0,-0.0,568.323486328125 +1769682035,10707712,0.0,-0.0,568.323486328125 +1769682035,48817664,0.0,-0.0,568.323486328125 +1769682035,78212608,0.0,-0.0,568.323486328125 +1769682035,110927616,0.0,-0.0,568.323486328125 +1769682035,144241664,0.0,-0.0,568.323486328125 +1769682035,180390144,0.0,-0.0,568.323486328125 +1769682035,211495680,0.0,-0.0,568.323486328125 +1769682035,245824768,0.0,-0.0,568.323486328125 +1769682035,278438912,0.0,-0.0,568.323486328125 +1769682035,312543744,0.0,-0.0,568.323486328125 +1769682035,350884352,0.0,-0.0,568.323486328125 +1769682035,378329600,0.0,-0.0,568.323486328125 +1769682035,410887680,0.0,-0.0,568.323486328125 +1769682035,449850880,0.0,-0.0,568.323486328125 +1769682035,478678272,0.0,-0.0,568.323486328125 +1769682035,510786304,0.0,-0.0,568.323486328125 +1769682035,560483328,0.0,-0.0,568.323486328125 +1769682035,568632576,0.0,-0.0,568.323486328125 +1769682035,613108992,0.0,-0.0,568.323486328125 +1769682035,646489088,0.0,-0.0,568.323486328125 +1769682035,678986240,0.0,-0.0,568.323486328125 +1769682035,711233280,0.0,-0.0,568.323486328125 +1769682035,745938176,0.0,-0.0,568.323486328125 +1769682035,778034688,0.0,-0.0,568.323486328125 +1769682035,813909504,0.0,-0.0,568.323486328125 +1769682035,861506560,0.0,-0.0,568.323486328125 +1769682035,869815040,0.0,-0.0,568.323486328125 +1769682035,910958592,0.0,-0.0,568.323486328125 +1769682035,957783296,0.0,-0.0,568.323486328125 +1769682035,964920832,0.0,-0.0,568.323486328125 +1769682036,11871488,0.0,-0.0,568.323486328125 +1769682036,46388992,0.0,-0.0,568.323486328125 +1769682036,79678720,0.0,-0.0,568.323486328125 +1769682036,112663808,0.0,-0.0,568.323486328125 +1769682036,147660288,0.0,-0.0,568.323486328125 +1769682036,178141440,0.0,-0.0,568.323486328125 +1769682036,213507328,0.0,-0.0,568.323486328125 +1769682036,260341760,0.0,-0.0,568.323486328125 +1769682036,267788544,0.0,-0.0,568.323486328125 +1769682036,311344640,0.0,-0.0,568.323486328125 +1769682036,357347840,0.0,-0.0,568.323486328125 +1769682036,367428608,0.0,-0.0,568.323486328125 +1769682036,411094784,0.0,-0.0,568.323486328125 +1769682036,447497472,0.0,-0.0,568.323486328125 +1769682036,479294208,0.0,-0.0,568.323486328125 +1769682036,511515392,0.0,-0.0,568.323486328125 +1769682036,545165824,0.0,-0.0,568.323486328125 +1769682036,564911360,0.0,-0.0,568.323486328125 +1769682036,611600640,0.0,-0.0,568.323486328125 +1769682036,665410816,0.0,-0.0,568.323486328125 +1769682036,667355392,0.0,-0.0,568.323486328125 +1769682036,710890752,0.0,-0.0,568.323486328125 +1769682036,753034752,0.0,-0.0,568.323486328125 +1769682036,777930240,0.0,-0.0,568.323486328125 +1769682036,810848512,0.0,-0.0,568.323486328125 +1769682036,846670336,0.0,-0.0,568.323486328125 +1769682036,878987008,0.0,-0.0,568.323486328125 +1769682036,913356032,0.0,-0.0,568.323486328125 +1769682036,948589824,0.0,-0.0,568.323486328125 +1769682036,977628672,0.0,-0.0,568.323486328125 +1769682037,13882880,0.0,-0.0,568.323486328125 +1769682037,57195008,0.0,-0.0,568.323486328125 +1769682037,79206400,0.0,-0.0,568.323486328125 +1769682037,111496192,0.0,-0.0,568.323486328125 +1769682037,162307840,0.0,-0.0,568.323486328125 +1769682037,170710016,0.0,-0.0,568.323486328125 +1769682037,211749376,0.0,-0.0,568.323486328125 +1769682037,244899840,0.0,-0.0,568.323486328125 +1769682037,278977024,0.0,-0.0,568.323486328125 +1769682037,311112192,0.0,-0.0,568.323486328125 +1769682037,345214208,0.0,-0.0,568.323486328125 +1769682037,377905664,0.0,-0.0,568.323486328125 +1769682037,415186688,0.0,-0.0,568.323486328125 +1769682037,449613312,0.0,-0.0,568.323486328125 +1769682037,478336256,0.0,-0.0,568.323486328125 +1769682037,510944768,0.0,-0.0,568.323486328125 +1769682037,558311680,0.0,-0.0,568.323486328125 +1769682037,569397504,0.0,-0.0,568.323486328125 +1769682037,613230080,0.0,-0.0,568.323486328125 +1769682037,645111552,0.0,-0.0,568.323486328125 +1769682037,681391104,0.0,-0.0,568.323486328125 +1769682037,713490176,0.0,-0.0,568.323486328125 +1769682037,755211776,0.0,-0.0,568.323486328125 +1769682037,778462720,0.0,-0.0,568.323486328125 +1769682037,798923008,0.0,-0.0,568.323486328125 +1769682037,849284864,0.0,-0.0,568.323486328125 +1769682037,877931264,0.0,-0.0,568.323486328125 +1769682037,911852288,0.0,-0.0,568.323486328125 +1769682037,964865280,0.0,-0.0,568.323486328125 +1769682037,975822080,0.0,-0.0,568.323486328125 +1769682038,13005056,0.0,-0.0,568.323486328125 +1769682038,46932736,0.0,-0.0,568.323486328125 +1769682038,66534656,0.0,-0.0,568.323486328125 +1769682038,111244032,0.0,-0.0,568.323486328125 +1769682038,146597120,0.0,-0.0,568.323486328125 +1769682038,177817088,0.0,-0.0,568.323486328125 +1769682038,211213824,0.0,-0.0,568.323486328125 +1769682038,246549248,0.0,-0.0,568.323486328125 +1769682038,278257920,0.0,-0.0,568.323486328125 +1769682038,311378944,0.0,-0.0,568.323486328125 +1769682038,351210752,0.0,-0.0,568.323486328125 +1769682038,379072256,0.0,-0.0,568.323486328125 +1769682038,411606016,0.0,-0.0,568.323486328125 +1769682038,463187200,0.0,-0.0,568.323486328125 +1769682038,470382336,0.0,-0.0,568.323486328125 +1769682038,511718656,0.0,-0.0,568.323486328125 +1769682038,545495296,0.0,-0.0,568.323486328125 +1769682038,581912832,0.0,-0.0,568.323486328125 +1769682038,611838720,0.0,-0.0,568.323486328125 +1769682038,652561408,0.0,-0.0,568.323486328125 +1769682038,677951744,0.0,-0.0,568.323486328125 +1769682038,713323264,0.0,-0.0,568.323486328125 +1769682038,760099072,0.0,-0.0,568.323486328125 +1769682038,770226944,0.0,-0.0,568.323486328125 +1769682038,812808192,0.0,-0.0,568.323486328125 +1769682038,861056512,0.0,-0.0,568.323486328125 +1769682038,869102592,0.0,-0.0,568.323486328125 +1769682038,913009152,0.0,-0.0,568.323486328125 +1769682038,945923328,0.0,-0.0,568.323486328125 +1769682038,980034560,0.0,-0.0,568.323486328125 +1769682039,11477760,0.0,-0.0,568.323486328125 +1769682039,46122240,0.0,-0.0,568.323486328125 +1769682039,78223104,0.0,-0.0,568.323486328125 +1769682039,114045184,0.0,-0.0,568.323486328125 +1769682039,149462528,0.0,-0.0,568.323486328125 +1769682039,179556608,0.0,-0.0,568.323486328125 +1769682039,211515136,0.0,-0.0,568.323486328125 +1769682039,258198272,0.0,-0.0,568.323486328125 +1769682039,267484416,0.0,-0.0,568.323486328125 +1769682039,314381824,0.0,-0.0,568.323486328125 +1769682039,345506304,0.0,-0.0,568.323486328125 +1769682039,380849408,0.004304932430386543,-0.0003387089818716049,568.3233032226562 +1769682039,411998720,0.010385260917246342,-0.0005474374629557133,568.3225708007812 +1769682039,447040768,0.021574074402451515,-0.0008427798748016357,568.3211059570312 +1769682039,478358784,0.03132953867316246,-0.0009535057470202446,568.3195190429688 +1769682039,515328768,0.041746724396944046,-0.0011375341564416885,568.317626953125 +1769682039,555527936,0.05619187653064728,-0.0012403745204210281,568.3148803710938 +1769682039,577938432,0.06737158447504044,-0.0013482943177223206,568.3126831054688 +1769682039,611113216,0.07889772206544876,-0.0014522597193717957,568.310302734375 +1769682039,658479616,0.09468492865562439,-0.0015175938606262207,568.306884765625 +1769682039,667680256,0.10273553431034088,-0.0015335269272327423,568.3052368164062 +1769682039,711694848,0.1193932443857193,-0.0015384145081043243,568.3016357421875 +1769682039,746969344,0.1364668756723404,-0.001567050814628601,568.2979125976562 +1769682039,783238400,0.1494489163160324,-0.0015780627727508545,568.2950439453125 +1769682039,811693312,0.16244125366210938,-0.001562073826789856,568.2921142578125 +1769682039,849479680,0.17987367510795593,-0.001544564962387085,568.2881469726562 +1769682039,878272256,0.19306673109531403,-0.0015404969453811646,568.2850341796875 +1769682039,913654016,0.20670358836650848,-0.0015006139874458313,568.281982421875 +1769682039,962109184,0.22613760828971863,-0.0014638155698776245,568.2777709960938 +1769682039,969804032,0.23627284169197083,-0.001462496817111969,568.275634765625 +1769682040,11296512,0.2567726969718933,-0.0013962611556053162,568.271240234375 +1769682040,68576256,0.27826350927352905,-0.0013244599103927612,568.2666625976562 +1769682040,70912256,0.28904828429222107,-0.0013183653354644775,568.264404296875 +1769682040,111466752,0.31204864382743835,-0.00134354829788208,568.259765625 +1769682040,145849344,0.33623233437538147,-0.0012784600257873535,568.2548217773438 +1769682040,178264064,0.35447147488594055,-0.0012617707252502441,568.2510986328125 +1769682040,212143872,0.3733103275299072,-0.001230284571647644,568.247314453125 +1769682040,253830656,0.3995092809200287,-0.001223236322402954,568.2421875 +1769682040,280110080,0.4196745753288269,-0.0011937618255615234,568.23828125 +1769682040,311152896,0.4408283233642578,-0.00122736394405365,568.2342529296875 +1769682040,365725696,0.4695686101913452,-0.0011677742004394531,568.2288818359375 +1769682040,374702592,0.4915226101875305,-0.0011626780033111572,568.2247924804688 +1769682040,411502336,0.5131500959396362,-0.0011919587850570679,568.2206420898438 +1769682040,462358272,0.5433793663978577,-0.0011799931526184082,568.21533203125 +1769682040,473967872,0.5664262771606445,-0.00118979811668396,568.211181640625 +1769682040,513156864,0.5899602770805359,-0.001141667366027832,568.2072143554688 +1769682040,546928384,0.6222689151763916,-0.0012237131595611572,568.2017822265625 +1769682040,578087424,0.6460424661636353,-0.0012307465076446533,568.19775390625 +1769682040,600729088,0.6616698503494263,-0.0012030601501464844,568.1951293945312 +1769682040,663548928,0.6994315385818481,-0.001234978437423706,568.1887817382812 +1769682040,671150848,0.720598578453064,-0.0012783408164978027,568.185302734375 +1769682040,700176128,0.7347152829170227,-0.0012572705745697021,568.1831665039062 +1769682040,757230848,0.7706850171089172,-0.0012704133987426758,568.1780395507812 +1769682040,768660224,0.7859275341033936,-0.0012997090816497803,568.176025390625 +1769682040,814699776,0.8171172142028809,-0.001349031925201416,568.1723022460938 +1769682040,869078272,0.8491211533546448,-0.0014038681983947754,568.1687622070312 +1769682040,873262336,0.8650867938995361,-0.001435995101928711,568.1671142578125 +1769682040,911824384,0.8971108794212341,-0.0014728903770446777,568.1640014648438 +1769682040,949116928,0.9291914701461792,-0.0015884637832641602,568.161376953125 +1769682040,978084608,0.9522980451583862,-0.0010297000408172607,568.1597290039062 +1769682041,13385216,0.9748398661613464,-0.000980287790298462,568.1588134765625 +1769682041,52774144,1.0042719841003418,-0.0011716187000274658,568.1583862304688 +1769682041,78231296,1.0255126953125,-0.0013151764869689941,568.1585693359375 +1769682041,112159232,1.0463204383850098,-0.0015009641647338867,568.1591796875 +1769682041,150008320,1.0749872922897339,-0.001716911792755127,568.1605834960938 +1769682041,170556672,1.0898969173431396,-0.0018076896667480469,568.1614990234375 +1769682041,199648000,1.1122981309890747,-0.0019145607948303223,568.1630859375 +1769682041,265998848,1.1515237092971802,-0.002238929271697998,568.1658935546875 +1769682041,278992896,1.1782214641571045,-0.002914130687713623,568.1661987304688 +1769682041,311483136,1.2046902179718018,-0.003213047981262207,568.1669921875 +1769682041,353374720,1.240330457687378,-0.003376483917236328,568.1686401367188 +1769682041,378348288,1.2670241594314575,-0.0034794211387634277,568.1702880859375 +1769682041,413697792,1.2936267852783203,-0.0035396814346313477,568.1722412109375 +1769682041,450527232,1.3296847343444824,-0.003555774688720703,568.1753540039062 +1769682041,478223616,1.3571369647979736,-0.0035824179649353027,568.1778564453125 +1769682041,511684352,1.3845794200897217,-0.0035862326622009277,568.1806030273438 +1769682041,551581696,1.4212216138839722,-0.003688216209411621,568.1846313476562 +1769682041,579405824,1.4487062692642212,-0.0037074685096740723,568.1878051757812 +1769682041,611560448,1.4764418601989746,-0.0038043856620788574,568.191162109375 +1769682041,657152768,1.5135058164596558,-0.0038946866989135742,568.19580078125 +1769682041,682241024,1.5409843921661377,-0.00392526388168335,568.1995239257812 +1769682041,697703424,1.5593030452728271,-0.003939986228942871,568.2019653320312 +1769682041,748988160,1.6062021255493164,-0.0041877031326293945,568.2103881835938 +1769682041,779028736,1.6342921257019043,-0.0038141608238220215,568.217529296875 +1769682041,813942784,1.662163496017456,-0.0033930540084838867,568.2257690429688 +1769682041,858355200,1.6992520093917847,-0.002874016761779785,568.23779296875 +1769682041,870343936,1.7179925441741943,-0.002626776695251465,568.244140625 +1769682041,911939584,1.755455493927002,-0.002307116985321045,568.257080078125 +1769682041,958129408,1.7926301956176758,-0.0019795894622802734,568.2703857421875 +1769682041,970277376,1.8110836744308472,-0.0017562508583068848,568.277099609375 +1769682042,13817856,1.8479464054107666,-0.0015311241149902344,568.2906494140625 +1769682042,95481856,1.8846153020858765,-0.0013523101806640625,568.3041381835938 +1769682042,97551616,1.9119657278060913,-0.001221001148223877,568.3141479492188 +1769682042,116605952,1.9391804933547974,-0.001114487648010254,568.3240356445312 +1769682042,145895936,1.9752777814865112,-0.0009805560111999512,568.3370971679688 +1769682042,165394944,1.9934489727020264,-0.000908970832824707,568.343505859375 +1769682042,211656192,2.0294389724731445,-0.0008262395858764648,568.35595703125 +1769682042,260762624,2.064894914627075,-0.000735163688659668,568.367919921875 +1769682042,269780480,2.0824875831604004,-0.0006489157676696777,568.3737182617188 +1769682042,315244544,2.1176998615264893,-0.0008147954940795898,568.385009765625 +1769682042,347353088,2.1535491943359375,-0.0018912553787231445,568.39306640625 +1769682042,379076864,2.171339273452759,-0.0025583505630493164,568.3956909179688 +1769682042,411797504,2.206681251525879,-0.0038840770721435547,568.3984985351562 +1769682042,449799680,2.2413272857666016,-0.005098462104797363,568.39892578125 +1769682042,466523648,2.2584991455078125,-0.0056067705154418945,568.3984375 +1769682042,516496384,2.292602777481079,-0.006503939628601074,568.3965454101562 +1769682042,556445440,2.32637619972229,-0.007175445556640625,568.3937377929688 +1769682042,578158592,2.3514597415924072,-0.00756072998046875,568.3911743164062 +1769682042,611541248,2.376433849334717,-0.007854580879211426,568.3883056640625 +1769682042,660338432,2.4093241691589355,-0.008067607879638672,568.3840942382812 +1769682042,672816640,2.432866096496582,-0.007409095764160156,568.3806762695312 +1769682042,700648448,2.4472761154174805,-0.005617737770080566,568.3777465820312 +1769682042,745887232,2.4825785160064697,0.0024118423461914062,568.3687133789062 +1769682042,781462272,2.5036370754241943,0.0074405670166015625,568.3624267578125 +1769682042,812183040,2.5244300365448,0.01211249828338623,568.3553466796875 +1769682042,847670016,2.5515079498291016,0.017657756805419922,568.3445434570312 +1769682042,878487808,2.5714962482452393,0.021200060844421387,568.3353271484375 +1769682042,917139456,2.5912203788757324,0.024257302284240723,568.3250122070312 +1769682042,966272000,2.617124080657959,0.027497172355651855,568.3096313476562 +1769682042,968481280,2.6299169063568115,0.028715968132019043,568.3012084960938 +1769682043,11511040,2.655245065689087,0.030772805213928223,568.2831420898438 +1769682043,67840768,2.681384801864624,0.03201770782470703,568.2633056640625 +1769682043,70118656,2.6943676471710205,0.03277850151062012,568.2528686523438 +1769682043,111958016,2.7202506065368652,0.034311532974243164,568.2311401367188 +1769682043,148183040,2.7463486194610596,0.03529226779937744,568.2086181640625 +1769682043,195165440,2.7657434940338135,0.03591787815093994,568.1913452148438 +1769682043,215124480,2.7850289344787598,0.036327362060546875,568.1736450195312 +1769682043,248748288,2.810544729232788,0.036850929260253906,568.1494750976562 +1769682043,278433792,2.8294389247894287,0.03711342811584473,568.130859375 +1769682043,313307136,2.846691846847534,0.03813636302947998,568.1110229492188 +1769682043,361468672,2.868544578552246,0.034267306327819824,568.0743408203125 +1769682043,372197120,2.8868932723999023,0.02955341339111328,568.039306640625 +1769682043,401984000,2.906811237335205,0.024353504180908203,567.9990844726562 +1769682043,445390336,2.9331274032592773,0.018687844276428223,567.94091796875 +1769682043,483368448,2.9528613090515137,0.015070319175720215,567.8953247070312 +1769682043,499819008,2.965916633605957,0.012682676315307617,567.8643188476562 +1769682043,551989248,2.9972639083862305,0.009011268615722656,567.7858276367188 +1769682043,564772864,3.00848388671875,0.007616996765136719,567.75439453125 +1769682043,611680512,3.029468297958374,0.006034731864929199,567.69189453125 +1769682043,657885696,3.0526559352874756,0.004914999008178711,567.6300048828125 +1769682043,675071744,3.0711963176727295,0.004257321357727051,567.5841064453125 +1769682043,712078848,3.086829900741577,0.007685542106628418,567.5426025390625 +1769682043,747796736,3.107546806335449,0.015810847282409668,567.5018310546875 +1769682043,768950784,3.11784291267395,0.019959449768066406,567.4865112304688 +1769682043,811926016,3.1379878520965576,0.02837967872619629,567.46337890625 +1769682043,849540608,3.1577584743499756,0.03563892841339111,567.4473266601562 +1769682043,879020288,3.1724205017089844,0.04027247428894043,567.4384765625 +1769682043,913063424,3.186965227127075,0.044182538986206055,567.4313354492188 +1769682043,949061632,3.206042766571045,0.04839324951171875,567.4234619140625 +1769682043,966035712,3.2153513431549072,0.050161004066467285,567.419921875 +1769682044,12407296,3.2339730262756348,0.053163886070251465,567.4127197265625 +1769682044,50103296,3.2522966861724854,0.055362582206726074,567.4046020507812 +1769682044,67810560,3.2613744735717773,0.05619454383850098,567.400146484375 +1769682044,102300160,3.279111623764038,0.05755198001861572,567.3895874023438 +1769682044,145571328,3.296623468399048,0.05846524238586426,567.3770751953125 +1769682044,180396544,3.3096354007720947,0.05890297889709473,567.3662719726562 +1769682044,212736256,3.321204900741577,0.060240864753723145,567.3544311523438 +1769682044,247711232,3.3331029415130615,0.05831122398376465,567.3389892578125 +1769682044,295187712,3.346223831176758,0.05327796936035156,567.325927734375 +1769682044,315016704,3.360208749771118,0.04832637310028076,567.3103637695312 +1769682044,370644992,3.378556966781616,0.042992472648620605,567.2869873046875 +1769682044,380610816,3.3920412063598633,0.03977036476135254,567.2678833007812 +1769682044,400387328,3.4010367393493652,0.03779792785644531,567.2545166015625 +1769682044,465364736,3.4233741760253906,0.03470015525817871,567.2191772460938 +1769682044,476030464,3.4366633892059326,0.033376216888427734,567.197021484375 +1769682044,512783616,3.450204372406006,0.032190918922424316,567.1739501953125 +1769682044,547010560,3.4681215286254883,0.03120732307434082,567.1428833007812 +1769682044,578514688,3.481471300125122,0.030863404273986816,567.119384765625 +1769682044,601770240,3.49027681350708,0.03051912784576416,567.1038208007812 +1769682044,651642112,3.511965274810791,0.030910253524780273,567.06494140625 +1769682044,680984320,3.5248661041259766,0.03119349479675293,567.0415649414062 +1769682044,712105728,3.5376298427581787,0.03158605098724365,567.0180053710938 +1769682044,757519872,3.5545053482055664,0.03217923641204834,566.9862670898438 +1769682044,770516736,3.5628750324249268,0.03226888179779053,566.9700927734375 +1769682044,811846144,3.5791854858398438,0.03335368633270264,566.937744140625 +1769682044,846281728,3.595226764678955,0.03429865837097168,566.9052734375 +1769682044,866573568,3.603182554244995,0.034646034240722656,566.8890380859375 +1769682044,911918080,3.6190192699432373,0.035561561584472656,566.8563232421875 +1769682044,951529984,3.6346333026885986,0.03628361225128174,566.8233032226562 +1769682044,980705024,3.646233320236206,0.03670632839202881,566.7982177734375 +1769682045,12041984,3.657719373703003,0.03707993030548096,566.7728271484375 +1769682045,50991360,3.6733124256134033,0.03698611259460449,566.7385864257812 +1769682045,79975680,3.6851449012756348,0.03544604778289795,566.71337890625 +1769682045,112021760,3.696821689605713,0.03339362144470215,566.6884155273438 +1769682045,164908032,3.7084431648254395,0.03129231929779053,566.6635131835938 +1769682045,176037888,3.7236363887786865,0.028737783432006836,566.6305541992188 +1769682045,212458752,3.7349205017089844,0.0270920991897583,566.6058959960938 +1769682045,261744640,3.7498161792755127,0.02533853054046631,566.572998046875 +1769682045,284670976,3.761073589324951,0.024005532264709473,566.5481567382812 +1769682045,300549632,3.7686429023742676,0.022936701774597168,566.53125 +1769682045,345761280,3.787191867828369,0.021947026252746582,566.4882202148438 +1769682045,378803200,3.798164129257202,0.021484851837158203,566.461669921875 +1769682045,417686016,3.8089916706085205,0.021206259727478027,566.4346313476562 +1769682045,457991680,3.8230628967285156,0.02108287811279297,566.3978881835938 +1769682045,480091648,3.833554267883301,0.022078275680541992,566.3700561523438 +1769682045,513604096,3.843986988067627,0.023878931999206543,566.3373413085938 +1769682045,557847040,3.8557395935058594,0.02397751808166504,566.2887573242188 +1769682045,570942976,3.861461877822876,0.024606943130493164,566.2672729492188 +1769682045,613651712,3.8726251125335693,0.027421951293945312,566.2293701171875 +1769682045,646283264,3.883631706237793,0.02976059913635254,566.1966552734375 +1769682045,682118400,3.891744613647461,0.03130507469177246,566.1742553710938 +1769682045,711978240,3.8997344970703125,0.03261971473693848,566.1530151367188 +1769682045,752786944,3.910036087036133,0.03405261039733887,566.125732421875 +1769682045,778814976,3.9179770946502686,0.03449201583862305,566.1055297851562 +1769682045,854370816,3.92648983001709,0.033423423767089844,566.0828247070312 +1769682045,869930496,3.937844753265381,0.03046107292175293,566.0473022460938 +1769682045,878065920,3.9461348056793213,0.02802753448486328,566.0177001953125 +1769682045,898816256,3.951589345932007,0.02613067626953125,565.9968872070312 +1769682045,945864192,3.964977979660034,0.023003578186035156,565.9420166015625 +1769682045,976008960,3.9702885150909424,0.021611452102661133,565.9191284179688 +1769682046,12620544,3.9807443618774414,0.019765377044677734,565.8724365234375 +1769682046,61007872,3.99104642868042,0.02033388614654541,565.8256225585938 +1769682046,68631808,3.996232509613037,0.020983099937438965,565.805419921875 +1769682046,113640192,4.0064263343811035,0.023018956184387207,565.7713012695312 +1769682046,149580800,4.016508102416992,0.024843573570251465,565.743408203125 +1769682046,179179264,4.023982048034668,0.02593207359313965,565.7258911132812 +1769682046,212154112,4.031404495239258,0.02689385414123535,565.7105102539062 +1769682046,258001920,4.037348747253418,0.027190566062927246,565.6937255859375 +1769682046,267260928,4.040812015533447,0.025765299797058105,565.68359375 +1769682046,314063104,4.047585964202881,0.025990009307861328,565.6588134765625 +1769682046,346455808,4.054066181182861,0.026410341262817383,565.6300048828125 +1769682046,380577024,4.058816432952881,0.026594877243041992,565.6063842773438 +1769682046,412298496,4.0636467933654785,0.026669979095458984,565.5813598632812 +1769682046,451208704,4.069852828979492,0.02662825584411621,565.5459594726562 +1769682046,479071744,4.074426651000977,0.026500463485717773,565.518310546875 +1769682046,515865088,4.078993797302246,0.026346206665039062,565.4900512695312 +1769682046,557315840,4.085013389587402,0.026101112365722656,565.4517822265625 +1769682046,578951936,4.089424133300781,0.025868535041809082,565.4229125976562 +1769682046,612138496,4.093221664428711,0.026149511337280273,565.3943481445312 +1769682046,660419840,4.097960472106934,0.026001930236816406,565.3558959960938 +1769682046,669570816,4.100430488586426,0.02552175521850586,565.336669921875 +1769682046,732354048,4.105408191680908,0.025967001914978027,565.2994384765625 +1769682046,745286144,4.109155654907227,0.026145219802856445,565.2724609375 +1769682046,783028224,4.114088535308838,0.0263596773147583,565.237548828125 +1769682046,814584832,4.117780685424805,0.026470661163330078,565.2122192382812 +1769682046,848018688,4.1229400634765625,0.026105761528015137,565.1791381835938 +1769682046,878808576,4.126623153686523,0.025595903396606445,565.154296875 +1769682046,914306816,4.130241870880127,0.02513587474822998,565.1292114257812 +1769682046,956212736,4.134918212890625,0.024702072143554688,565.0953979492188 +1769682046,980557824,4.138339042663574,0.024663686752319336,565.0689697265625 +1769682047,12516864,4.141712665557861,0.02467811107635498,565.0410766601562 +1769682047,63593728,4.146069526672363,0.024861812591552734,565.0014038085938 +1769682047,70677760,4.148210048675537,0.024527311325073242,564.98046875 +1769682047,112284160,4.1524457931518555,0.025234460830688477,564.9365234375 +1769682047,148902144,4.156565189361572,0.02543199062347412,564.8903198242188 +1769682047,180317696,4.159597873687744,0.02555394172668457,564.854736328125 +1769682047,213522688,4.1625847816467285,0.025530219078063965,564.8189086914062 +1769682047,246730496,4.166325092315674,0.025347590446472168,564.7713012695312 +1769682047,278658304,4.168543815612793,0.025312066078186035,564.737060546875 +1769682047,316735232,4.170607566833496,0.024740219116210938,564.7044067382812 +1769682047,355026944,4.173379421234131,0.023559927940368652,564.6630859375 +1769682047,378764800,4.175529956817627,0.023039817810058594,564.6336059570312 +1769682047,412215040,4.1776580810546875,0.022657275199890137,564.6051635742188 +1769682047,461144576,4.180296897888184,0.022256016731262207,564.5685424804688 +1769682047,468588544,4.181539058685303,0.02190089225769043,564.5506591796875 +1769682047,514174976,4.184012413024902,0.021915912628173828,564.5155029296875 +1769682047,547620352,4.1864848136901855,0.02167665958404541,564.4810180664062 +1769682047,580640000,4.188299179077148,0.021495580673217773,564.4556884765625 +1769682047,612830464,4.19020414352417,0.021311044692993164,564.4307861328125 +1769682047,650044928,4.192318916320801,0.021210312843322754,564.3986206054688 +1769682047,679170816,4.193150520324707,0.021851301193237305,564.3756103515625 +1769682047,715373568,4.194004058837891,0.02196979522705078,564.35302734375 +1769682047,753117952,4.195098876953125,0.021847963333129883,564.323486328125 +1769682047,779933696,4.1959099769592285,0.021718263626098633,564.3019409179688 +1769682047,812268544,4.19690465927124,0.021599769592285156,564.281005859375 +1769682047,853391616,4.198173522949219,0.021713972091674805,564.2545166015625 +1769682047,878942720,4.199093818664551,0.021889686584472656,564.2356567382812 +1769682047,913470208,4.200050354003906,0.02198314666748047,564.2172241210938 +1769682047,946193664,4.201620578765869,0.02165675163269043,564.1929321289062 +1769682047,982782976,4.202847480773926,0.021148204803466797,564.1744384765625 +1769682048,14572032,4.204078674316406,0.0205538272857666,564.1558837890625 +1769682048,50237952,4.205708026885986,0.01972055435180664,564.1315307617188 +1769682048,78789120,4.206752300262451,0.01916027069091797,564.11376953125 +1769682048,114801152,4.207761764526367,0.01862049102783203,564.0965576171875 +1769682048,157180672,4.20902681350708,0.018013715744018555,564.0745239257812 +1769682048,181497600,4.209922790527344,0.01761794090270996,564.05859375 +1769682048,212483072,4.210794925689697,0.017326831817626953,564.0430908203125 +1769682048,262789120,4.211825370788574,0.017038345336914062,564.02294921875 +1769682048,272144640,4.212526321411133,0.016884326934814453,564.0082397460938 +1769682048,312760320,4.2127685546875,0.01685643196105957,563.9939575195312 +1769682048,346990592,4.2119879722595215,0.01775527000427246,563.9765014648438 +1769682048,380958208,4.211404800415039,0.017842769622802734,563.9642333984375 +1769682048,413112320,4.210732460021973,0.017771244049072266,563.952392578125 +1769682048,446789376,4.209704399108887,0.017471790313720703,563.9374389648438 +1769682048,479081728,4.209051132202148,0.017323017120361328,563.9266357421875 +1769682048,514873856,4.208368301391602,0.017329931259155273,563.9161376953125 +1769682048,551580160,4.207359790802002,0.0174102783203125,563.9027099609375 +1769682048,579194368,4.2066121101379395,0.017459630966186523,563.892822265625 +1769682048,612219136,4.205761909484863,0.017543315887451172,563.8829956054688 +1769682048,665549056,4.204461097717285,0.0176241397857666,563.8701171875 +1769682048,674948352,4.2034993171691895,0.01765918731689453,563.8605346679688 +1769682048,713172736,4.202261447906494,0.017366647720336914,563.8506469726562 +1769682048,747332608,4.200480937957764,0.016733884811401367,563.8372192382812 +1769682048,779828224,4.199080467224121,0.016196012496948242,563.8270874023438 +1769682048,815375104,4.197627067565918,0.015674829483032227,563.8170776367188 +1769682048,857703424,4.195523738861084,0.015038728713989258,563.8041381835938 +1769682048,879006208,4.193978309631348,0.014568805694580078,563.7947387695312 +1769682048,918449664,4.192525863647461,0.014478206634521484,563.7861938476562 +1769682048,957292800,4.190433502197266,0.014816761016845703,563.7765502929688 +1769682048,966370304,4.189335346221924,0.014992952346801758,563.7722778320312 +1769682049,12512256,4.187084674835205,0.015546560287475586,563.7645263671875 +1769682049,57135872,4.18485164642334,0.01592540740966797,563.7572631835938 +1769682049,70739456,4.183720111846924,0.015976428985595703,563.7537231445312 +1769682049,112535808,4.181390285491943,0.016228914260864258,563.7464599609375 +1769682049,148153088,4.179024696350098,0.016368865966796875,563.7391357421875 +1769682049,183330560,4.1772379875183105,0.016422510147094727,563.7335815429688 +1769682049,213285376,4.175423622131348,0.01645207405090332,563.7279663085938 +1769682049,248441344,4.173005104064941,0.016460418701171875,563.7205810546875 +1769682049,278966528,4.171380043029785,0.016465067863464355,563.7149047851562 +1769682049,315721472,4.169729709625244,0.01647162437438965,563.7091674804688 +1769682049,354636032,4.16762638092041,0.016436219215393066,563.7013549804688 +1769682049,366982144,4.166538715362549,0.01619899272918701,563.6973266601562 +1769682049,412634880,4.164391040802002,0.015594840049743652,563.6885986328125 +1769682049,467223040,4.162379264831543,0.014871478080749512,563.6793823242188 +1769682049,477637120,4.160983085632324,0.014238357543945312,563.6724243164062 +1769682049,513163520,4.159653186798096,0.013615608215332031,563.6653442382812 +1769682049,547455488,4.158037185668945,0.012789249420166016,563.6559448242188 +1769682049,582628608,4.1570658683776855,0.012456655502319336,563.6486206054688 +1769682049,612826624,4.156185626983643,0.012521624565124512,563.6412353515625 +1769682049,650750720,4.1551361083984375,0.01272284984588623,563.6312255859375 +1769682049,665786880,4.154613971710205,0.012830972671508789,563.6261596679688 +1769682049,716996608,4.153698921203613,0.01325845718383789,563.6160278320312 +1769682049,758616320,4.152861595153809,0.01373910903930664,563.6058349609375 +1769682049,770572032,4.152435302734375,0.013906598091125488,563.6006469726562 +1769682049,812935168,4.1518378257751465,0.014425039291381836,563.5902099609375 +1769682049,858780672,4.1513190269470215,0.01477968692779541,563.5795288085938 +1769682049,869361664,4.15109395980835,0.01485741138458252,563.5741577148438 +1769682049,913240832,4.150834560394287,0.015190958976745605,563.5631713867188 +1769682049,948748800,4.150712490081787,0.015375375747680664,563.5520629882812 +1769682049,981979904,4.15069055557251,0.015471100807189941,563.5435791015625 +1769682050,13075200,4.150779724121094,0.015617609024047852,563.5352172851562 +1769682050,47935488,4.150992393493652,0.01577615737915039,563.5241088867188 +1769682050,80387328,4.151206016540527,0.015880227088928223,563.5156860351562 +1769682050,117346304,4.15147066116333,0.015935063362121582,563.5071411132812 +1769682050,151248128,4.152073860168457,0.015792012214660645,563.4954223632812 +1769682050,167585792,4.15242862701416,0.0156552791595459,563.4892578125 +1769682050,212498944,4.153222560882568,0.015407443046569824,563.4765625 +1769682050,261270528,4.154099464416504,0.015123844146728516,563.4635009765625 +1769682050,282713344,4.15478515625,0.014914274215698242,563.4534912109375 +1769682050,298893056,4.15524959564209,0.014702796936035156,563.44677734375 +1769682050,346640896,4.1564202308654785,0.014592409133911133,563.4298095703125 +1769682050,385464064,4.157111644744873,0.014584541320800781,563.4195556640625 +1769682050,412561408,4.157834053039551,0.014628410339355469,563.409423828125 +1769682050,449086464,4.158836841583252,0.01469874382019043,563.3958129882812 +1769682050,479600128,4.159584045410156,0.014835119247436523,563.3855590820312 +1769682050,513479424,4.160299777984619,0.014932632446289062,563.375244140625 +1769682050,565041664,4.161308288574219,0.015012860298156738,563.3615112304688 +1769682050,574185984,4.16207218170166,0.01502680778503418,563.35107421875 +1769682050,600536320,4.16259241104126,0.014889836311340332,563.3441162109375 +1769682050,655124224,4.1639299392700195,0.015088558197021484,563.3263549804688 +1769682050,664968704,4.164468765258789,0.015084505081176758,563.3192138671875 +1769682050,703808512,4.165510177612305,0.015182971954345703,563.3046875 +1769682050,746115840,4.16650915145874,0.015073776245117188,563.2900390625 +1769682050,813399552,4.167248725891113,0.015023231506347656,563.27880859375 +1769682050,815405312,4.167989730834961,0.014940738677978516,563.267578125 +1769682050,856118016,4.168946743011475,0.014818906784057617,563.25244140625 +1769682050,867082752,4.169411659240723,0.01467442512512207,563.244873046875 +1769682050,912577280,4.170374870300293,0.014640331268310547,563.2297973632812 +1769682050,960900608,4.171321392059326,0.014576911926269531,563.2147827148438 +1769682050,971985408,4.171795845031738,0.014383316040039062,563.207275390625 +1769682051,13146368,4.172763347625732,0.01448202133178711,563.1923828125 +1769682051,49617664,4.173783779144287,0.014446258544921875,563.1775512695312 +1769682051,82192128,4.174562454223633,0.01460886001586914,563.1665649414062 +1769682051,113383936,4.175354480743408,0.014806270599365234,563.1558837890625 +1769682051,149676544,4.1763997077941895,0.015088081359863281,563.1415405273438 +1769682051,179318784,4.177175521850586,0.015308618545532227,563.1306762695312 +1769682051,218904064,4.177992820739746,0.015498876571655273,563.11962890625 +1769682051,258593536,4.1790690422058105,0.015660524368286133,563.1043090820312 +1769682051,271832832,4.179605007171631,0.015588998794555664,563.096435546875 +1769682051,313824000,4.180692672729492,0.01584482192993164,563.080322265625 +1769682051,366234624,4.181752681732178,0.01587367057800293,563.063720703125 +1769682051,375255552,4.182466506958008,0.015907764434814453,563.0509643554688 +1769682051,412683008,4.183189392089844,0.0157926082611084,563.0381469726562 +1769682051,446617088,4.184149265289307,0.015573263168334961,563.0208740234375 +1769682051,482458624,4.184597015380859,0.015416622161865234,563.01220703125 +1769682051,514071040,4.185489654541016,0.015306711196899414,562.994873046875 +1769682051,548770048,4.18634033203125,0.015180349349975586,562.9773559570312 +1769682051,579417856,4.186956405639648,0.015113115310668945,562.964111328125 +1769682051,613974528,4.18763542175293,0.01496267318725586,562.9507446289062 +1769682051,655878656,4.188584327697754,0.014614582061767578,562.932861328125 +1769682051,667120384,4.18869686126709,0.014642000198364258,562.9239501953125 +1769682051,713379584,4.188459396362305,0.015819311141967773,562.9066772460938 +1769682051,764219648,4.188289642333984,0.016541481018066406,562.8892822265625 +1769682051,774435328,4.188170433044434,0.016990184783935547,562.8763427734375 +1769682051,813387264,4.188140869140625,0.017351627349853516,562.86328125 +1769682051,846701056,4.188111305236816,0.0177304744720459,562.845947265625 +1769682051,896316160,4.188131809234619,0.017952442169189453,562.8330688476562 +1769682051,904815104,4.188231468200684,0.01814889907836914,562.8201904296875 +1769682051,949968384,4.188362121582031,0.01833629608154297,562.8030395507812 +1769682051,980195072,4.188355445861816,0.01842784881591797,562.7901611328125 +1769682052,17475584,4.188534736633301,0.018584012985229492,562.7769775390625 +1769682052,57369088,4.188856601715088,0.018726825714111328,562.7589111328125 +1769682052,68577792,4.189055442810059,0.018685579299926758,562.7496337890625 +1769682052,113992960,4.189376354217529,0.018932104110717773,562.7305908203125 +1769682052,167117824,4.189579963684082,0.01871180534362793,562.71533203125 +1769682052,176087552,4.1900715827941895,0.018419742584228516,562.69384765625 +1769682052,213473024,4.190450191497803,0.018166542053222656,562.6771240234375 +1769682052,246986240,4.191046714782715,0.017746925354003906,562.6542358398438 +1769682052,267534848,4.191413402557373,0.01740264892578125,562.6426391601562 +1769682052,313297152,4.192339897155762,0.0168914794921875,562.6189575195312 +1769682052,356490240,4.192314147949219,0.017270565032958984,562.5955810546875 +1769682052,379903488,4.191965579986572,0.01786327362060547,562.5791015625 +1769682052,413816064,4.191655158996582,0.018204927444458008,562.5629272460938 +1769682052,450856960,4.191390037536621,0.01855921745300293,562.5419311523438 +1769682052,479402752,4.191270351409912,0.01876211166381836,562.5263671875 +1769682052,512912384,4.19123649597168,0.01893019676208496,562.5108032226562 +1769682052,543763456,4.191231727600098,0.019197463989257812,562.4951782226562 +1769682052,581809664,4.191267013549805,0.019458532333374023,562.4732055664062 +1769682052,613082112,4.1913323402404785,0.01953744888305664,562.4559326171875 +1769682052,647926784,4.191321849822998,0.019685745239257812,562.4320678710938 +1769682052,681369088,4.191032409667969,0.02028679847717285,562.4136962890625 +1769682052,707258112,4.19072151184082,0.02081298828125,562.3948364257812 +1769682052,746780416,4.190391540527344,0.0213470458984375,562.3692016601562 +1769682052,779888128,4.190052509307861,0.021711349487304688,562.3497314453125 +1769682052,816970240,4.189701080322266,0.02176356315612793,562.3304443359375 +1769682052,863544320,4.189236164093018,0.021643638610839844,562.3050537109375 +1769682052,870492160,4.188998699188232,0.02132248878479004,562.29248046875 +1769682052,912952576,4.188547134399414,0.021346330642700195,562.2677001953125 +1769682052,962562560,4.188141822814941,0.021132230758666992,562.2433471679688 +1769682052,969624832,4.187953472137451,0.020817279815673828,562.2313232421875 +1769682053,12921856,4.187603950500488,0.020841598510742188,562.2071533203125 +1769682053,47228928,4.187267303466797,0.020681142807006836,562.1831665039062 +1769682053,84679168,4.187021255493164,0.020591020584106445,562.1652221679688 +1769682053,113415168,4.186787128448486,0.020448684692382812,562.1474609375 +1769682053,152318720,4.186506271362305,0.020376205444335938,562.1241455078125 +1769682053,179801088,4.186172962188721,0.020419836044311523,562.1072387695312 +1769682053,215281408,4.1858625411987305,0.02004694938659668,562.0906982421875 +1769682053,254822144,4.185458660125732,0.019495725631713867,562.069091796875 +1769682053,280374784,4.1851606369018555,0.019094228744506836,562.053466796875 +1769682053,313722624,4.184797286987305,0.018759489059448242,562.038330078125 +1769682053,367775232,4.184133529663086,0.018945932388305664,562.0242309570312 +1769682053,375652096,4.183226585388184,0.019479990005493164,562.0067138671875 +1769682053,398673920,4.182774066925049,0.019611835479736328,561.9984130859375 +1769682053,446735872,4.181668758392334,0.020303010940551758,561.9780883789062 +1769682053,470117376,4.181244373321533,0.02037811279296875,561.9701538085938 +1769682053,513214208,4.180416584014893,0.02077794075012207,561.954345703125 +1769682053,548423936,4.179623603820801,0.020945072174072266,561.9389038085938 +1769682053,579841024,4.179043292999268,0.02098679542541504,561.9278564453125 +1769682053,613508864,4.178481578826904,0.02096247673034668,561.917236328125 +1769682053,656248576,4.177671432495117,0.020970821380615234,561.904052734375 +1769682053,681604608,4.177046775817871,0.020906448364257812,561.8948364257812 +1769682053,746566656,4.176432132720947,0.020708084106445312,561.8862915039062 +1769682053,757186048,4.175629615783691,0.020441293716430664,561.8759155273438 +1769682053,790216960,4.17507266998291,0.020168066024780273,561.8688354492188 +1769682053,802708992,4.174530982971191,0.019892454147338867,561.8622436523438 +1769682053,854195712,4.173650741577148,0.019692659378051758,561.854248046875 +1769682053,870630400,4.173181533813477,0.01936650276184082,561.8505859375 +1769682053,913496832,4.172264575958252,0.018922090530395508,561.8434448242188 +1769682053,957946624,4.171338081359863,0.01841425895690918,561.8363647460938 +1769682053,980729344,4.1706342697143555,0.01807570457458496,561.8312377929688 +1769682054,13307392,4.16990852355957,0.017746925354003906,561.8262329101562 +1769682054,65911296,4.169192790985107,0.017419099807739258,561.821533203125 +1769682054,77360896,4.168177604675293,0.017003774642944336,561.8157958984375 +1769682054,98236672,4.16767692565918,0.016727924346923828,561.8134155273438 +1769682054,148131840,4.166458606719971,0.016228437423706055,561.8092041015625 +1769682054,172758272,4.16598653793335,0.016015291213989258,561.808349609375 +1769682054,213833216,4.164936065673828,0.01566171646118164,561.807861328125 +1769682054,247373824,4.163911819458008,0.01543569564819336,561.8088989257812 +1769682054,279609344,4.163131237030029,0.015288352966308594,561.8106079101562 +1769682054,301277696,4.162541389465332,0.015280008316040039,561.8121337890625 +1769682054,354496000,4.1609787940979,0.015273094177246094,561.8172607421875 +1769682054,382098176,4.160072326660156,0.015168905258178711,561.8209838867188 +1769682054,413325568,4.159130573272705,0.015027284622192383,561.8251342773438 +1769682054,473005312,4.157844543457031,0.014801740646362305,561.8312377929688 +1769682054,476545792,4.156888961791992,0.014641046524047852,561.8363037109375 +1769682054,512791552,4.155839920043945,0.014481782913208008,561.8416748046875 +1769682054,547693312,4.154429912567139,0.014247655868530273,561.8495483398438 +1769682054,577133056,4.1533684730529785,0.013967037200927734,561.8560180664062 +1769682054,614980096,4.152307510375977,0.013628005981445312,561.8632202148438 +1769682054,651858688,4.151018142700195,0.013065576553344727,561.8741455078125 +1769682054,696475136,4.150005340576172,0.012659549713134766,561.8836669921875 +1769682054,717174016,4.148970603942871,0.012359380722045898,561.8944702148438 +1769682054,755551232,4.147538661956787,0.011941194534301758,561.9107666015625 +1769682054,768438272,4.146852970123291,0.01182866096496582,561.9196166992188 +1769682054,812902400,4.145491600036621,0.011077165603637695,561.9385375976562 +1769682054,860368896,4.144148349761963,0.010504722595214844,561.958740234375 +1769682054,881249024,4.143162727355957,0.010173797607421875,561.9743041992188 +1769682054,914954496,4.142194747924805,0.00995635986328125,561.9900512695312 +1769682054,947552256,4.140897750854492,0.009759902954101562,562.010986328125 +1769682054,980881920,4.1399455070495605,0.009663820266723633,562.0266723632812 +1769682055,13556992,4.139039516448975,0.009574174880981445,562.0423583984375 +1769682055,66318080,4.137889385223389,0.009326934814453125,562.0635375976562 +1769682055,74805504,4.137066841125488,0.00902104377746582,562.0801391601562 +1769682055,115724288,4.13626766204834,0.008708000183105469,562.0977172851562 +1769682055,155936512,4.135237216949463,0.008201122283935547,562.1231689453125 +1769682055,167533312,4.1347336769104,0.008147716522216797,562.1367797851562 +1769682055,212900096,4.133748531341553,0.0075037479400634766,562.1660766601562 +1769682055,264670208,4.132837295532227,0.007154226303100586,562.1973876953125 +1769682055,274976768,4.132336616516113,0.007002353668212891,562.2220458984375 +1769682055,315524096,4.131967544555664,0.007044434547424316,562.247314453125 +1769682055,349193984,4.1315412521362305,0.007302403450012207,562.281494140625 +1769682055,385501440,4.131252288818359,0.007490992546081543,562.3072509765625 +1769682055,413230592,4.130997180938721,0.007667183876037598,562.3331298828125 +1769682055,457533952,4.130800724029541,0.0076596736907958984,562.3675537109375 +1769682055,479934720,4.1307291984558105,0.0074073076248168945,562.3931274414062 +1769682055,515001088,4.130681037902832,0.007068037986755371,562.4188232421875 +1769682055,554034176,4.130651950836182,0.006532073020935059,562.4537963867188 +1769682055,579654912,4.130748271942139,0.006037473678588867,562.4810180664062 +1769682055,613309440,4.131231307983398,0.005080103874206543,562.5089721679688 +1769682055,664353024,4.132042407989502,0.004150271415710449,562.5484008789062 +1769682055,674896128,4.1326727867126465,0.003638744354248047,562.579833984375 +1769682055,714321152,4.133341312408447,0.003205418586730957,562.61279296875 +1769682055,749692928,4.134259223937988,0.002779364585876465,562.6587524414062 +1769682055,779669760,4.134964942932129,0.002512812614440918,562.694580078125 +1769682055,802892544,4.135447025299072,0.0028362274169921875,562.7188720703125 +1769682055,848489984,4.13677978515625,0.001838088035583496,562.7809448242188 +1769682055,880450048,4.137588024139404,0.0015027523040771484,562.8189697265625 +1769682055,913732608,4.138416290283203,0.001179337501525879,562.8572387695312 +1769682055,964580864,4.139636039733887,0.0007370710372924805,562.9088134765625 +1769682055,972111616,4.140576362609863,0.0005621910095214844,562.9481201171875 +1769682056,14317824,4.1415181159973145,0.00042879581451416016,562.9879760742188 +1769682056,46597632,4.1427531242370605,0.0002409219741821289,563.042236328125 +1769682056,67171328,4.143361568450928,0.0003682374954223633,563.0700073242188 +1769682056,113809920,4.144571781158447,-8.26120376586914e-05,563.126708984375 +1769682056,154315264,4.1457438468933105,-0.00026679039001464844,563.1849365234375 +1769682056,179687936,4.14660120010376,-0.00037682056427001953,563.2294921875 +1769682056,200707072,4.147165298461914,-2.7298927307128906e-05,563.259521484375 +1769682056,250380800,4.148653984069824,-0.0005561113357543945,563.3356323242188 +1769682056,279937792,4.150027275085449,-0.0009884834289550781,563.38134765625 +1769682056,313201664,4.151525497436523,-0.0012011528015136719,563.4270629882812 +1769682056,358365952,4.153567314147949,-0.0011914968490600586,563.488525390625 +1769682056,372567040,4.154560565948486,-0.0006167888641357422,563.5194702148438 +1769682056,414071808,4.156496524810791,-0.001040339469909668,563.5823974609375 +1769682056,452221440,4.158383846282959,-0.0010044574737548828,563.6466674804688 +1769682056,473571072,4.159811019897461,-0.001091599464416504,563.6958618164062 +1769682056,514221568,4.161227226257324,-0.00133514404296875,563.745849609375 +1769682056,546858752,4.163002014160156,-0.0017812252044677734,563.8136596679688 +1769682056,581662720,4.164300441741943,-0.002150297164916992,563.865234375 +1769682056,599966976,4.16518497467041,-0.0017762184143066406,563.89990234375 +1769682056,648674048,4.167646408081055,-0.0030400753021240234,563.9876098632812 +1769682056,679799808,4.169057846069336,-0.0032674074172973633,564.0406494140625 +1769682056,715134464,4.170395851135254,-0.003458738327026367,564.0940551757812 +1769682056,758697472,4.1717071533203125,-0.0034922361373901367,564.1474609375 +1769682056,773699584,4.173270225524902,-0.003676772117614746,564.2188110351562 +1769682056,814786816,4.174384593963623,-0.00375211238861084,564.2723388671875 +1769682056,848944384,4.175787925720215,-0.0038421154022216797,564.3438720703125 +1769682056,869116672,4.176473140716553,-0.0035408735275268555,564.3797607421875 +1769682056,914283264,4.1777472496032715,-0.004140615463256836,564.451904296875 +1769682056,949842432,4.178915023803711,-0.004355907440185547,564.5245971679688 +1769682056,979694848,4.179811477661133,-0.004558563232421875,564.5795288085938 +1769682057,1165056,4.18040657043457,-0.003996729850769043,564.6162719726562 +1769682057,49928448,4.181728363037109,-0.004617094993591309,564.708984375 +1769682057,82654720,4.18246603012085,-0.00461578369140625,564.7650146484375 +1769682057,113686272,4.18310546875,-0.004612565040588379,564.8214111328125 +1769682057,156605696,4.183743953704834,-0.004439115524291992,564.8780517578125 +1769682057,173906944,4.18451452255249,-0.00440216064453125,564.9537353515625 +1769682057,213960960,4.185051918029785,-0.004263520240783691,565.0104370117188 +1769682057,248739072,4.185696601867676,-0.004122138023376465,565.0857543945312 +1769682057,269765376,4.186061859130859,-0.0034852027893066406,565.1231079101562 +1769682057,313939712,4.1871562004089355,-0.003938198089599609,565.1970825195312 +1769682057,344190464,4.187981128692627,-0.003662705421447754,565.251953125 +1769682057,379965952,4.1890363693237305,-0.0034188032150268555,565.3243408203125 +1769682057,399985408,4.1895318031311035,-0.0027004480361938477,565.3602294921875 +1769682057,449126656,4.190718650817871,-0.00287473201751709,565.4490356445312 +1769682057,479861504,4.191400527954102,-0.0027276277542114258,565.5018920898438 +1769682057,513154048,4.192052841186523,-0.0026150941848754883,565.5546875 +1769682057,551585024,4.192923069000244,-0.0026415586471557617,565.625 +1769682057,580937728,4.193653583526611,-0.002751946449279785,565.6777954101562 +1769682057,613256192,4.194465637207031,-0.002876877784729004,565.7306518554688 +1769682057,659779072,4.195511817932129,-0.0029932260513305664,565.8013916015625 +1769682057,668171520,4.196019172668457,-0.002568840980529785,565.8367919921875 +1769682057,715226624,4.196986675262451,-0.002979278564453125,565.9073486328125 +1769682057,749886976,4.197903633117676,-0.002787947654724121,565.97705078125 +1769682057,782616320,4.198573112487793,-0.002594590187072754,566.028564453125 +1769682057,813457920,4.199201583862305,-0.0024088621139526367,566.0790405273438 +1769682057,852817408,4.199928283691406,-0.0019685029983520508,566.1450805664062 +1769682057,879958016,4.200441360473633,-0.0016756057739257812,566.1937255859375 +1769682057,916292096,4.20092248916626,-0.0014309883117675781,566.2418212890625 +1769682057,954301440,4.201496124267578,-0.001283407211303711,566.3056640625 +1769682057,967324160,4.201781272888184,-0.0009976625442504883,566.3378295898438 +1769682058,14029824,4.202343940734863,-0.0013282299041748047,566.4028930664062 +1769682058,62226432,4.202853202819824,-0.0012935400009155273,566.4693603515625 +1769682058,69837056,4.203096389770508,-0.0006999969482421875,566.5028686523438 +1769682058,113513472,4.203560829162598,-0.0010524988174438477,566.5701904296875 +1769682058,148193024,4.203979969024658,-0.0007914304733276367,566.6371459960938 +1769682058,180116224,4.204273700714111,-0.000504612922668457,566.6866455078125 +1769682058,214280960,4.204503059387207,-0.00014388561248779297,566.7351684570312 +1769682058,248427520,4.204927444458008,9.250640869140625e-05,566.7977294921875 +1769682058,280199424,4.20536470413208,0.0002645254135131836,566.8428955078125 +1769682058,314978304,4.205765247344971,0.0004137754440307617,566.8868408203125 +1769682058,354050048,4.206273078918457,0.0005890130996704102,566.9435424804688 +1769682058,381347840,4.206638336181641,0.0006119012832641602,566.9849243164062 +1769682058,413302784,4.206976890563965,0.0006396770477294922,567.0258178710938 +1769682058,460816640,4.207563877105713,0.00037789344787597656,567.0805053710938 +1769682058,469719040,4.207903861999512,0.0007015466690063477,567.1082763671875 +1769682058,513359360,4.208507537841797,1.3232231140136719e-05,567.1655883789062 +1769682058,552913152,4.209056854248047,-4.887580871582031e-06,567.2251586914062 +1769682058,584314880,4.209444999694824,6.520748138427734e-05,567.2708740234375 +1769682058,613788160,4.209793567657471,0.00010991096496582031,567.3171997070312 +1769682058,651547136,4.210165023803711,0.00013780593872070312,567.3795776367188 +1769682058,679862784,4.210339069366455,0.00029730796813964844,567.4267578125 +1769682058,718589952,4.210482120513916,0.0006514787673950195,567.4741821289062 +1769682058,757982976,4.210622787475586,0.0012350082397460938,567.53759765625 +1769682058,781096704,4.210718154907227,0.0017032623291015625,567.5847778320312 +1769682058,814370304,4.210782527923584,0.002251744270324707,567.6312866210938 +1769682058,856766720,4.210797309875488,0.0027489662170410156,567.6768188476562 +1769682058,873972992,4.210745811462402,0.0033911466598510742,567.7359008789062 +1769682058,913719808,4.21064567565918,0.003691434860229492,567.7789306640625 +1769682058,948434432,4.2104058265686035,0.004110574722290039,567.83447265625 +1769682058,980267008,4.210208892822266,0.004469037055969238,567.8746337890625 +1769682059,1182208,4.210064888000488,0.005096316337585449,567.9006958007812 +1769682059,47191296,4.2094268798828125,0.005057692527770996,567.962646484375 +1769682059,80137472,4.208998680114746,0.005090117454528809,567.9974975585938 +1769682059,113349120,4.208715438842773,0.005139470100402832,568.0308227539062 +1769682059,153651200,4.208502769470215,0.005257606506347656,568.0731201171875 +1769682059,181076992,4.2083234786987305,0.005250811576843262,568.1033935546875 +1769682059,213810432,4.208101749420166,0.005251765251159668,568.1327514648438 +1769682059,248177408,4.207828998565674,0.005377531051635742,568.1705322265625 +1769682059,269803264,4.207777976989746,0.005721926689147949,568.1890258789062 +1769682059,313592320,4.207664489746094,0.005702614784240723,568.2247924804688 +1769682059,347969024,4.207369327545166,0.0062558650970458984,568.2596435546875 +1769682059,381296896,4.207152366638184,0.006799459457397461,568.2853393554688 +1769682059,399421184,4.206992149353027,0.007396817207336426,568.3023071289062 +1769682059,450341632,4.2065324783325195,0.008048653602600098,568.3436279296875 +1769682059,480048384,4.206157207489014,0.008765339851379395,568.36767578125 +1769682059,513385984,4.205756664276123,0.00953972339630127,568.3911743164062 +1769682059,561232384,4.20522928237915,0.010531306266784668,568.4213256835938 +1769682059,572342272,4.2049713134765625,0.011277556419372559,568.4359130859375 +1769682059,599644928,4.204568862915039,0.011881709098815918,568.4569091796875 +1769682059,660341760,4.203891754150391,0.012647867202758789,568.4898071289062 +1769682059,667473920,4.203570365905762,0.013164520263671875,568.502197265625 +1769682059,713912576,4.202822208404541,0.013479351997375488,568.5255737304688 +1769682059,748224000,4.202054023742676,0.013638496398925781,568.5471801757812 +1769682059,783379200,4.201481342315674,0.013662576675415039,568.562255859375 +1769682059,813771264,4.200859546661377,0.013745427131652832,568.5765380859375 +1769682059,848695808,4.1999430656433105,0.013553977012634277,568.5939331054688 +1769682059,880334336,4.19926643371582,0.013282418251037598,568.605712890625 +1769682059,917319168,4.198610305786133,0.01302647590637207,568.6166381835938 +1769682059,950429184,4.198025703430176,0.012764811515808105,568.6301879882812 +1769682059,981544448,4.197602272033691,0.012653946876525879,568.6396484375 +1769682060,14040832,4.197175979614258,0.012509822845458984,568.6485595703125 +1769682060,64281088,4.196596622467041,0.012405753135681152,568.6596069335938 +1769682060,72653568,4.196215629577637,0.012417793273925781,568.6674194335938 +1769682060,114437632,4.195827007293701,0.01245129108428955,568.6747436523438 +1769682060,147695872,4.195148468017578,0.012819647789001465,568.6841430664062 +1769682060,186797056,4.194638252258301,0.013246417045593262,568.691162109375 +1769682060,214180864,4.194119930267334,0.013713836669921875,568.697998046875 +1769682060,249932032,4.1934099197387695,0.014309525489807129,568.706787109375 +1769682060,280314112,4.1928300857543945,0.014875650405883789,568.713134765625 +1769682060,319189248,4.192249774932861,0.015432953834533691,568.7190551757812 +1769682060,347176704,4.191666126251221,0.016012072563171387,568.7246704101562 +1769682060,380893952,4.19087553024292,0.01668417453765869,568.7315063476562 +1769682060,413378816,4.19028377532959,0.017139673233032227,568.7361450195312 +1769682060,464007936,4.189517498016357,0.017650485038757324,568.7415161132812 +1769682060,472012288,4.188866138458252,0.018063902854919434,568.744873046875 +1769682060,514445568,4.188173770904541,0.018196940422058105,568.74755859375 +1769682060,547838464,4.187272548675537,0.01819002628326416,568.7501831054688 +1769682060,586208000,4.186614990234375,0.018154621124267578,568.7515258789062 +1769682060,614739968,4.185913562774658,0.01809549331665039,568.7522583007812 +1769682060,651792896,4.1849684715271,0.017760872840881348,568.7523193359375 +1769682060,680190976,4.184286117553711,0.017442941665649414,568.7518920898438 +1769682060,716379904,4.183622360229492,0.017134785652160645,568.7510986328125 +1769682060,761746944,4.182849407196045,0.016791820526123047,568.7498779296875 +1769682060,767018496,4.182487487792969,0.01661670207977295,568.7492065429688 +1769682060,814868736,4.181773662567139,0.016389966011047363,568.747802734375 +1769682060,858628864,4.181092739105225,0.016232848167419434,568.7461547851562 +1769682060,867433216,4.180763244628906,0.016170263290405273,568.7453002929688 +1769682060,916541696,4.179967880249023,0.01613438129425049,568.7432250976562 +1769682060,949941248,4.179082870483398,0.016359806060791016,568.7407836914062 +1769682060,979578368,4.178654670715332,0.016544699668884277,568.7394409179688 +1769682061,13642240,4.177828788757324,0.016983509063720703,568.7367553710938 +1769682061,51209216,4.177051067352295,0.01743948459625244,568.7337646484375 +1769682061,80934912,4.17645788192749,0.017773866653442383,568.7313232421875 +1769682061,115453696,4.175912380218506,0.01811063289642334,568.7286987304688 +1769682061,156457728,4.175219535827637,0.01847219467163086,568.7250366210938 +1769682061,180419584,4.174743175506592,0.018735527992248535,568.7221069335938 +1769682061,214588416,4.174288272857666,0.018935799598693848,568.7190551757812 +1769682061,262387456,4.173717975616455,0.0191420316696167,568.7147216796875 +1769682061,270138624,4.1734161376953125,0.01920294761657715,568.7125244140625 +1769682061,313791232,4.17280387878418,0.01928400993347168,568.7078857421875 +1769682061,348814336,4.1722564697265625,0.01916372776031494,568.7030639648438 +1769682061,383746560,4.171880722045898,0.019031643867492676,568.6994018554688 +1769682061,414536448,4.171517372131348,0.01886296272277832,568.6956176757812 +1769682061,447649792,4.171041011810303,0.018625974655151367,568.6904296875 +1769682061,480537856,4.1707024574279785,0.018431782722473145,568.6864013671875 +1769682061,515348992,4.170391082763672,0.018262267112731934,568.682373046875 +1769682061,555273728,4.169923305511475,0.01806652545928955,568.6768798828125 +1769682061,581720832,4.169499397277832,0.017877578735351562,568.6727294921875 +1769682061,613607424,4.169107913970947,0.017802953720092773,568.6685180664062 +1769682061,665144320,4.168590068817139,0.017802119255065918,568.6627807617188 +1769682061,672868608,4.16820764541626,0.017858505249023438,568.658203125 +1769682061,717009408,4.167524814605713,0.017828822135925293,568.6533813476562 +1769682061,764410880,4.166530132293701,0.017900943756103516,568.6463623046875 +1769682061,784433664,4.165811538696289,0.018085241317749023,568.6406860351562 +1769682061,802458368,4.1651225090026855,0.018287062644958496,568.6348266601562 +1769682061,848143872,4.164240837097168,0.018526196479797363,568.62646484375 +1769682061,880794624,4.163623332977295,0.01865208148956299,568.6201171875 +1769682061,915338752,4.163033485412598,0.018715500831604004,568.613525390625 +1769682061,950948352,4.16231107711792,0.01875889301300049,568.604736328125 +1769682061,980390400,4.161780834197998,0.018799543380737305,568.5979614257812 +1769682062,14970368,4.161313533782959,0.018811345100402832,568.5911865234375 +1769682062,47149824,4.160863399505615,0.018778085708618164,568.5844116210938 +1769682062,82233600,4.160271167755127,0.018831372261047363,568.5753784179688 +1769682062,113977344,4.159863471984863,0.018748998641967773,568.5687255859375 +1769682062,147067904,4.159337997436523,0.01858961582183838,568.56005859375 +1769682062,169875200,4.15908670425415,0.018470048904418945,568.5558471679688 +1769682062,213924864,4.158655643463135,0.018407583236694336,568.5476684570312 +1769682062,260404224,4.1582932472229,0.018283843994140625,568.539794921875 +1769682062,269936640,4.158161163330078,0.018204450607299805,568.5360107421875 +1769682062,305787904,4.157916069030762,0.018263578414916992,568.5285034179688 +1769682062,349896448,4.157738208770752,0.018300890922546387,568.52099609375 +1769682062,380531200,4.157233238220215,0.018282055854797363,568.5153198242188 +1769682062,419505920,4.156682014465332,0.018299341201782227,568.5094604492188 +1769682062,457651712,4.156045436859131,0.018387675285339355,568.5015258789062 +1769682062,480967424,4.155597686767578,0.01841115951538086,568.4955444335938 +1769682062,513658112,4.155177116394043,0.018462061882019043,568.489501953125 +1769682062,564667648,4.154603481292725,0.01846134662628174,568.4814453125 +1769682062,575426560,4.153718948364258,0.018233418464660645,568.47509765625 +1769682062,614250752,4.152880668640137,0.01813828945159912,568.4686889648438 +1769682062,650865920,4.151790618896484,0.018070340156555176,568.4599609375 +1769682062,687969024,4.1509904861450195,0.01796090602874756,568.4534301757812 +1769682062,714141184,4.1502251625061035,0.01789546012878418,568.4469604492188 +1769682062,751724800,4.149318695068359,0.01767861843109131,568.438720703125 +1769682062,780698624,4.148670196533203,0.01745307445526123,568.4326782226562 +1769682062,816321280,4.148065090179443,0.017200469970703125,568.4268798828125 +1769682062,854191872,4.147304534912109,0.016939997673034668,568.4194946289062 +1769682062,880635392,4.146759986877441,0.01677572727203369,568.4142456054688 +1769682062,913986048,4.146247863769531,0.016582250595092773,568.4092407226562 +1769682062,959348992,4.145628929138184,0.016451478004455566,568.40283203125 +1769682062,969540096,4.145341396331787,0.016367316246032715,568.3997802734375 +1769682063,13849088,4.144805908203125,0.016354680061340332,568.3939819335938 +1769682063,53877504,4.144311904907227,0.016275882720947266,568.3886108398438 +1769682063,82809600,4.14396858215332,0.016290664672851562,568.384765625 +1769682063,114776576,4.143648624420166,0.016299962997436523,568.3810424804688 +1769682063,149914624,4.1433515548706055,0.01629185676574707,568.376220703125 +1769682063,180378880,4.143153190612793,0.01642298698425293,568.3729248046875 +1769682063,216374528,4.143003463745117,0.01656818389892578,568.3697509765625 +1769682063,253140992,4.142021656036377,0.01662743091583252,568.36572265625 +1769682063,282906880,4.141222953796387,0.0167618989944458,568.3628540039062 +1769682063,314044160,4.140470504760742,0.016869068145751953,568.3602294921875 +1769682063,358467840,4.139730453491211,0.01698589324951172,568.357666015625 +1769682063,367727872,4.13901424407959,0.01709270477294922,568.355224609375 +1769682063,414195712,4.138187408447266,0.017107248306274414,568.351806640625 +1769682063,447902720,4.1374616622924805,0.016916751861572266,568.3479614257812 +1769682063,480674304,4.136939525604248,0.016770005226135254,568.3449096679688 +1769682063,501182464,4.1365461349487305,0.016623973846435547,568.3427734375 +1769682063,544245504,4.135778903961182,0.016431570053100586,568.3383178710938 +1769682063,580770304,4.135085105895996,0.01622188091278076,568.3338012695312 +1769682063,598607616,4.134748935699463,0.01608562469482422,568.3316040039062 +1769682063,643909376,4.13413667678833,0.015932798385620117,568.3273315429688 +1769682063,681155328,4.133667945861816,0.015641450881958008,568.3233642578125 +1769682063,699520256,4.133459568023682,0.015415072441101074,568.3215942382812 +1769682063,748111360,4.132964611053467,0.015082120895385742,568.3175048828125 +1769682063,777096704,4.132808208465576,0.014929652214050293,568.3161010742188 +1769682063,814356736,4.132556915283203,0.014709115028381348,568.3132934570312 +1769682063,847813376,4.1323981285095215,0.014644384384155273,568.310791015625 +1769682063,880473856,4.132285118103027,0.014656782150268555,568.3090209960938 +1769682063,914877952,4.13219690322876,0.014683127403259277,568.307373046875 +1769682063,949054208,4.132116794586182,0.014777541160583496,568.3052978515625 +1769682063,980675584,4.132068634033203,0.014805793762207031,568.3038330078125 +1769682064,13985792,4.132037162780762,0.014852404594421387,568.3024291992188 +1769682064,61853696,4.132004737854004,0.014983773231506348,568.300537109375 +1769682064,71576064,4.131988525390625,0.015020608901977539,568.2994995117188 +1769682064,114404608,4.132039546966553,0.015154838562011719,568.2975463867188 +1769682064,159447808,4.132091999053955,0.015330791473388672,568.296142578125 +1769682064,169240064,4.132080554962158,0.015454530715942383,568.2948608398438 +1769682064,215631360,4.131962299346924,0.015653133392333984,568.2932739257812 +1769682064,247736576,4.131853103637695,0.015763401985168457,568.2918701171875 +1769682064,280741120,4.131793022155762,0.01583731174468994,568.291015625 +1769682064,314532608,4.1317138671875,0.015857577323913574,568.2903442382812 +1769682064,352566016,4.131709098815918,0.015781283378601074,568.28955078125 +1769682064,380857344,4.131716728210449,0.015607714653015137,568.288818359375 +1769682064,415113984,4.131699562072754,0.015416860580444336,568.2881469726562 +1769682064,453730816,4.131688117980957,0.015195012092590332,568.2872924804688 +1769682064,467225600,4.131798267364502,0.015072941780090332,568.2869262695312 +1769682064,514315776,4.132203102111816,0.014885783195495605,568.2861938476562 +1769682064,548129280,4.132607460021973,0.014659643173217773,568.2858276367188 +1769682064,569302016,4.132811546325684,0.01455998420715332,568.2858276367188 +1769682064,614464512,4.1331939697265625,0.014369368553161621,568.2860717773438 +1769682064,651727104,4.133577346801758,0.014174103736877441,568.2867431640625 +1769682064,680829440,4.133859157562256,0.013998031616210938,568.28759765625 +1769682064,702491904,4.134036540985107,0.013916373252868652,568.2883911132812 +1769682064,747862016,4.134456157684326,0.013664960861206055,568.291015625 +1769682064,781231872,4.1347527503967285,0.013514518737792969,568.29296875 +1769682064,814491136,4.13503360748291,0.01346290111541748,568.2952270507812 +1769682064,857095168,4.135305404663086,0.013471603393554688,568.2978515625 +1769682064,873168896,4.135654449462891,0.013447999954223633,568.3019409179688 +1769682064,914005504,4.135895252227783,0.013395190238952637,568.305419921875 +1769682064,949130752,4.136204719543457,0.013364076614379883,568.3106689453125 +1769682064,970479872,4.136356353759766,0.013358712196350098,568.3136596679688 +1769682065,14709760,4.136651992797852,0.013189911842346191,568.3200073242188 +1769682065,47994112,4.1369428634643555,0.01310122013092041,568.3271484375 +1769682065,80567552,4.137172698974609,0.012938141822814941,568.3331298828125 +1769682065,115559936,4.137399196624756,0.012810945510864258,568.3396606445312 +1769682065,154182656,4.137982368469238,0.012611865997314453,568.349365234375 +1769682065,181062656,4.138625144958496,0.012468218803405762,568.357421875 +1769682065,214059008,4.139266490936279,0.012279868125915527,568.3660278320312 +1769682065,262322176,4.140128135681152,0.012107133865356445,568.3783569335938 +1769682065,274235136,4.140777587890625,0.011954903602600098,568.38818359375 +1769682065,314696448,4.141427516937256,0.011804699897766113,568.3985595703125 +1769682065,348035584,4.142282009124756,0.011590003967285156,568.4129638671875 +1769682065,369675264,4.142704010009766,0.011546134948730469,568.42041015625 +1769682065,414943232,4.143571853637695,0.011250138282775879,568.4359130859375 +1769682065,448075520,4.1445136070251465,0.01102137565612793,568.4520874023438 +1769682065,480837888,4.145419597625732,0.010835409164428711,568.4646606445312 +1769682065,514375424,4.146342754364014,0.010710597038269043,568.4777221679688 +1769682065,550452736,4.147549629211426,0.010544419288635254,568.4957885742188 +1769682065,580829184,4.148440361022949,0.01041865348815918,568.5098266601562 +1769682065,614770176,4.149351596832275,0.010288357734680176,568.5242309570312 +1769682065,659575552,4.150253772735596,0.01024007797241211,568.5390014648438 +1769682065,668365056,4.151134014129639,0.010169029235839844,568.55419921875 +1769682065,714225408,4.152326583862305,0.009917378425598145,568.5751342773438 +1769682065,749758464,4.153506755828857,0.00969386100769043,568.5970458984375 +1769682065,770484224,4.154090404510498,0.009720444679260254,568.6083984375 +1769682065,815541248,4.155261993408203,0.00931549072265625,568.6319580078125 +1769682065,852698368,4.1564130783081055,0.00908970832824707,568.6568603515625 +1769682065,881190656,4.1572675704956055,0.008929610252380371,568.6763916015625 +1769682065,910875392,4.158118724822998,0.008785009384155273,568.6964721679688 +1769682065,943861760,4.1589555740356445,0.00870668888092041,568.7171630859375 +1769682065,967109376,4.159796237945557,0.008692502975463867,568.7382202148438 +1769682066,14290176,4.160904884338379,0.008457064628601074,568.7669067382812 +1769682066,63024384,4.161952495574951,0.008324742317199707,568.7959594726562 +1769682066,73069568,4.162705421447754,0.008243560791015625,568.8180541992188 +1769682066,114075648,4.163453102111816,0.008115291595458984,568.8403930664062 +1769682066,154531584,4.164548397064209,0.007990360260009766,568.863037109375 +1769682066,168929280,4.165599822998047,0.008008956909179688,568.8859252929688 +1769682066,214477824,4.166983604431152,0.007618904113769531,568.9171752929688 +1769682066,248013056,4.168336868286133,0.0074253082275390625,568.94921875 +1769682066,286177792,4.169305801391602,0.007330060005187988,568.9738159179688 +1769682066,314553856,4.170207500457764,0.007181286811828613,568.9987182617188 +1769682066,345135872,4.171095371246338,0.007147073745727539,569.0242919921875 +1769682066,381076224,4.172212600708008,0.006920456886291504,569.0589599609375 +1769682066,413126656,4.172723293304443,0.007094740867614746,569.0765380859375 +1769682066,454018560,4.174212455749512,0.006597042083740234,569.1217041015625 +1769682066,483487232,4.175103664398193,0.006420731544494629,569.149658203125 +1769682066,514403072,4.175966262817383,0.006279587745666504,569.17822265625 +1769682066,567284992,4.177079200744629,0.0060585737228393555,569.21728515625 +1769682066,569068800,4.177634239196777,0.006146550178527832,569.2372436523438 +1769682066,617111296,4.178612232208252,0.005785822868347168,569.2777709960938 +1769682066,649472768,4.179520606994629,0.00565648078918457,569.3191528320312 +1769682066,680935168,4.180186748504639,0.005626797676086426,569.3504638671875 +1769682066,701111808,4.180624008178711,0.005956172943115234,569.3713989257812 +1769682066,746557696,4.181352138519287,0.0056591033935546875,569.4134521484375 +1769682066,780993792,4.182016372680664,0.005591392517089844,569.455322265625 +1769682066,816033280,4.1824259757995605,0.005566596984863281,569.48681640625 +1769682066,850039552,4.1828083992004395,0.005495786666870117,569.5183715820312 +1769682066,868927488,4.183155059814453,0.005594372749328613,569.5501708984375 +1769682066,901311488,4.183426380157471,0.005646705627441406,569.5823974609375 +1769682066,947947776,4.183791160583496,0.004996538162231445,569.6370849609375 +1769682066,973438976,4.18389892578125,0.005329012870788574,569.659423828125 +1769682067,15433728,4.184055805206299,0.004715085029602051,569.7047119140625 +1769682067,49593088,4.1841278076171875,0.004497408866882324,569.7509155273438 +1769682067,80812288,4.184147834777832,0.004317760467529297,569.7863159179688 +1769682067,103344896,4.184306621551514,0.004679560661315918,569.8101806640625 +1769682067,152287488,4.184629917144775,0.0039664506912231445,569.8707275390625 +1769682067,181079808,4.184789657592773,0.0038776397705078125,569.907470703125 +1769682067,200367616,4.184875965118408,0.004205226898193359,569.9320678710938 +1769682067,261174016,4.185062408447266,0.003710150718688965,569.993896484375 +1769682067,274970880,4.185141563415527,0.004171013832092285,570.0186157226562 +1769682067,314279680,4.185269832611084,0.0036391019821166992,570.0684204101562 +1769682067,349071104,4.185365200042725,0.0035556554794311523,570.1184692382812 +1769682067,370141696,4.185408592224121,0.0038357973098754883,570.1436157226562 +1769682067,414462720,4.18565559387207,0.00345456600189209,570.1944580078125 +1769682067,449681664,4.185939311981201,0.003344893455505371,570.2457885742188 +1769682067,468385280,4.186080455780029,0.0036334991455078125,570.271728515625 +1769682067,515214080,4.186349868774414,0.0032873153686523438,570.3236083984375 +1769682067,545065728,4.18654727935791,0.003332972526550293,570.36279296875 +1769682067,566954240,4.186720371246338,0.003449678421020508,570.402099609375 +1769682067,617158400,4.186954498291016,0.003087639808654785,570.455078125 +1769682067,655393024,4.187159538269043,0.0029598474502563477,570.508544921875 +1769682067,681432832,4.1873064041137695,0.002829313278198242,570.549072265625 +1769682067,714423296,4.187454700469971,0.0027266740798950195,570.5900268554688 +1769682067,762486016,4.187633037567139,0.0025103092193603516,570.6455078125 +1769682067,771517952,4.1877217292785645,0.0029349327087402344,570.673583984375 +1769682067,815333376,4.187908172607422,0.0021780729293823242,570.7304077148438 +1769682067,849368832,4.188084125518799,0.001964569091796875,570.7882690429688 +1769682067,882511872,4.188170433044434,0.002110004425048828,570.8174438476562 +1769682067,905104896,4.188345909118652,0.0017406940460205078,570.8763427734375 +1769682067,948936192,4.1885223388671875,0.0016552209854125977,570.9356079101562 +1769682067,981090816,4.1886491775512695,0.0015538930892944336,570.9802856445312 +1769682068,16572160,4.188767433166504,0.0014982223510742188,571.025146484375 +1769682068,56020480,4.188936233520508,0.0013984441757202148,571.085205078125 +1769682068,81352448,4.189277172088623,0.0012912750244140625,571.13037109375 +1769682068,99205120,4.189506530761719,0.001654505729675293,571.1607055664062 +1769682068,158244096,4.189956188201904,0.001015305519104004,571.2219848632812 +1769682068,171246080,4.190290927886963,0.0014356374740600586,571.2684326171875 +1769682068,214585600,4.190738677978516,0.0005146265029907227,571.3314819335938 +1769682068,250013952,4.19117546081543,0.0002638101577758789,571.3956909179688 +1769682068,279236096,4.1913909912109375,0.0005067586898803711,571.4282836914062 +1769682068,316584192,4.191810131072998,3.063678741455078e-05,571.4942016601562 +1769682068,365579264,4.192214488983154,-9.1552734375e-05,571.5607299804688 +1769682068,372844288,4.192646026611328,-0.00013935565948486328,571.6110229492188 +1769682068,419213056,4.193073272705078,-0.0001933574676513672,571.6614990234375 +1769682068,451103488,4.193629741668701,-0.00026917457580566406,571.7290649414062 +1769682068,467048192,4.193868160247803,-2.6464462280273438e-05,571.7630004882812 +1769682068,514458880,4.1943254470825195,-0.0003911256790161133,571.8309936523438 +1769682068,566394880,4.194711685180664,-0.0005159378051757812,571.8995361328125 +1769682068,580505344,4.194967746734619,-0.0006258487701416016,571.951416015625 +1769682068,599015424,4.195128440856934,-0.0001493692398071289,571.9862670898438 +1769682068,648369664,4.195492267608643,-0.0009198188781738281,572.07421875 +1769682068,681583616,4.195628643035889,-0.0007140636444091797,572.1097412109375 +1769682068,714601216,4.195856094360352,-0.0010925531387329102,572.1813354492188 +1769682068,749221888,4.196023464202881,-0.0012055635452270508,572.25341796875 +1769682068,781149696,4.196142196655273,-0.0013386011123657227,572.307861328125 +1769682068,819035136,4.196176052093506,-0.0014598369598388672,572.3627319335938 +1769682068,852977664,4.196213245391846,-0.0015822649002075195,572.436279296875 +1769682068,881375744,4.1962432861328125,-0.001653909683227539,572.4917602539062 +1769682068,914645248,4.196188926696777,-0.001707911491394043,572.5474243164062 +1769682068,957542656,4.196115493774414,-0.0017496347427368164,572.6033325195312 +1769682068,970825984,4.196033954620361,-0.001146554946899414,572.6593627929688 +1769682069,15070464,4.195810794830322,-0.0020525455474853516,572.7346801757812 +1769682069,50324736,4.1957807540893555,-0.0022096633911132812,572.810791015625 +1769682069,82860032,4.195736885070801,-0.0018056631088256836,572.8489379882812 +1769682069,114750208,4.195598602294922,-0.0023761987686157227,572.9259643554688 +1769682069,150793728,4.1953840255737305,-0.0024346113204956055,573.0031127929688 +1769682069,167028992,4.195268630981445,-0.002051234245300293,573.0418090820312 +1769682069,216375040,4.1949849128723145,-0.0023958683013916016,573.1189575195312 +1769682069,247660288,4.194744110107422,-0.002285003662109375,573.1766967773438 +1769682069,281521408,4.194352626800537,-0.0023561716079711914,573.2536010742188 +1769682069,314412032,4.1940202713012695,-0.0023349523544311523,573.3112182617188 +1769682069,355877120,4.19380521774292,-0.0023130178451538086,573.3690185546875 +1769682069,370053376,4.193586349487305,-0.0017361640930175781,573.4269409179688 +1769682069,414650112,4.193247318267822,-0.0024051666259765625,573.5043334960938 +1769682069,449050368,4.1929144859313965,-0.002514362335205078,573.582275390625 +1769682069,482533888,4.192675590515137,-0.002665996551513672,573.6411743164062 +1769682069,515686144,4.192417144775391,-0.0027942657470703125,573.7005615234375 +1769682069,550145024,4.192047119140625,-0.0029261112213134766,573.780517578125 +1769682069,581084672,4.191760540008545,-0.0030101537704467773,573.8408813476562 +1769682069,617913088,4.191457271575928,-0.003057122230529785,573.9015502929688 +1769682069,658400256,4.1910400390625,-0.0032044649124145508,573.982666015625 +1769682069,667300352,4.190828323364258,-0.0029098987579345703,574.0234985351562 +1769682069,714787840,4.190386772155762,-0.0034737586975097656,574.1055908203125 +1769682069,758777856,4.190051078796387,-0.003596186637878418,574.1676025390625 +1769682069,768638976,4.189711093902588,-0.0032657384872436523,574.2300415039062 +1769682069,814742272,4.189250469207764,-0.003800511360168457,574.3136596679688 +1769682069,850177792,4.188776969909668,-0.0038089752197265625,574.3974609375 +1769682069,881589248,4.188419818878174,-0.0037267208099365234,574.460205078125 +1769682069,906855424,4.188045024871826,-0.003708958625793457,574.522705078125 +1769682069,949740544,4.187558650970459,-0.003701925277709961,574.6055908203125 +1769682069,981500416,4.187239646911621,-0.003750920295715332,574.667724609375 +1769682070,15254272,4.187047958374023,-0.003756880760192871,574.72998046875 +1769682070,48009984,4.186857223510742,-0.0036220550537109375,574.7923583984375 +1769682070,82887168,4.1865997314453125,-0.0038870573043823242,574.8758544921875 +1769682070,114863872,4.1863908767700195,-0.003953456878662109,574.9387817382812 +1769682070,149761280,4.186101913452148,-0.004079103469848633,575.0231323242188 +1769682070,172778240,4.1859564781188965,-0.0032945871353149414,575.0654907226562 +1769682070,200310528,4.1857171058654785,-0.0036411285400390625,575.12939453125 +1769682070,245834240,4.185397624969482,-0.0042917728424072266,575.2153930664062 +1769682070,266622976,4.1851487159729,-0.004059314727783203,575.2801513671875 +1769682070,301539328,4.184978008270264,-0.003730177879333496,575.3450317382812 +1769682070,349915392,4.184820652008057,-0.004361271858215332,575.453369140625 +1769682070,368837632,4.184757232666016,-0.0038661956787109375,575.4967041015625 +1769682070,399160576,4.184656620025635,-0.0037037134170532227,575.5615234375 +1769682070,466514176,4.184463024139404,-0.004410743713378906,575.6695556640625 +1769682070,468486912,4.1843791007995605,-0.004099726676940918,575.7129516601562 +1769682070,514979840,4.184192657470703,-0.004683494567871094,575.800048828125 +1769682070,555985408,4.184049129486084,-0.004824995994567871,575.8660888671875 +1769682070,569101568,4.183895587921143,-0.004232883453369141,575.9326171875 +1769682070,615422976,4.183703899383545,-0.0051392316818237305,576.0220947265625 +1769682070,649104128,4.183513164520264,-0.005257368087768555,576.1122436523438 +1769682070,683645952,4.183371067047119,-0.0053789615631103516,576.1802368164062 +1769682070,715425280,4.1832275390625,-0.005512714385986328,576.2485961914062 +1769682070,746943232,4.183083534240723,-0.0055353641510009766,576.3172607421875 +1769682070,766430208,4.182943344116211,-0.0052640438079833984,576.38623046875 +1769682070,818612736,4.182753562927246,-0.005775570869445801,576.4784545898438 +1769682070,850759424,4.182562351226807,-0.005871891975402832,576.5709228515625 +1769682070,870025472,4.182465076446533,-0.005307674407958984,576.6172485351562 +1769682070,899553280,4.182323932647705,-0.005287051200866699,576.6868286132812 +1769682070,960936448,4.182122230529785,-0.006136775016784668,576.8032836914062 +1769682070,967992832,4.182132244110107,-0.0055582523345947266,576.8501586914062 +1769682071,16378880,4.182232856750488,-0.006201028823852539,576.9442138671875 +1769682071,49905408,4.1823320388793945,-0.006240367889404297,577.0386352539062 +1769682071,79135488,4.182379722595215,-0.005836367607116699,577.0858764648438 +1769682071,115966720,4.182489395141602,-0.006289243698120117,577.180419921875 +1769682071,151068160,4.182600021362305,-0.006238579750061035,577.27490234375 +1769682071,181753088,4.182682037353516,-0.006202220916748047,577.3456420898438 +1769682071,216521728,4.182771682739258,-0.006114959716796875,577.4161376953125 +1769682071,252391424,4.182864189147949,-0.005888938903808594,577.486328125 +1769682071,281998080,4.1831841468811035,-0.005881547927856445,577.5796508789062 +1769682071,303087360,4.183516979217529,-0.0057572126388549805,577.6493530273438 +1769682071,360517376,4.183956623077393,-0.005669713020324707,577.741943359375 +1769682071,371122432,4.184177875518799,-0.004775404930114746,577.7881469726562 +1769682071,414597632,4.1846160888671875,-0.005556702613830566,577.8805541992188 +1769682071,449271552,4.185047149658203,-0.005543351173400879,577.97265625 +1769682071,478933248,4.185261249542236,-0.005035519599914551,578.0186767578125 +1769682071,515336448,4.185685634613037,-0.005462646484375,578.1103515625 +1769682071,550995712,4.186096668243408,-0.00542902946472168,578.201904296875 +1769682071,566112000,4.18629789352417,-0.00513458251953125,578.2476196289062 +1769682071,620880640,4.1866912841796875,-0.005531668663024902,578.3391723632812 +1769682071,653779712,4.187067985534668,-0.00555872917175293,578.4310913085938 +1769682071,668657920,4.18725061416626,-0.005071282386779785,578.4771118164062 +1769682071,715506944,4.187608242034912,-0.005420804023742676,578.5687866210938 +1769682071,759819008,4.187948226928711,-0.005269408226013184,578.6597290039062 +1769682071,769222144,4.188111782073975,-0.0045588016510009766,578.7048950195312 +1769682071,800335872,4.188345432281494,-0.004474997520446777,578.772216796875 +1769682071,842871808,4.188640117645264,-0.0050814151763916016,578.861572265625 +1769682071,877930240,4.188851356506348,-0.00478816032409668,578.9285278320312 +1769682071,899504896,4.189055442810059,-0.004502773284912109,578.99560546875 +1769682071,949795072,4.1896538734436035,-0.005077719688415527,579.1077880859375 +1769682071,967629824,4.189963340759277,-0.004609465599060059,579.1527099609375 +1769682072,10460672,4.1904168128967285,-0.00430905818939209,579.2200927734375 +1769682072,54783488,4.191205978393555,-0.004940629005432129,579.3319091796875 +1769682072,66489344,4.191522121429443,-0.004664301872253418,579.3765869140625 +1769682072,114806016,4.192187309265137,-0.0051174163818359375,579.4661865234375 +1769682072,157072128,4.1926727294921875,-0.005160093307495117,579.5337524414062 +1769682072,170668288,4.193148612976074,-0.004317045211791992,579.6016235351562 +1769682072,216721408,4.193789482116699,-0.005225419998168945,579.692138671875 +1769682072,249006336,4.194643974304199,-0.005170106887817383,579.7826538085938 +1769682072,283408640,4.195481777191162,-0.005042433738708496,579.8505249023438 +1769682072,299251200,4.196060657501221,-0.004392862319946289,579.8958129882812 +1769682072,345141760,4.197205066680908,-0.005012989044189453,579.9862670898438 +1769682072,367441664,4.198060512542725,-0.00462949275970459,580.05419921875 +1769682072,416032000,4.199195384979248,-0.005214333534240723,580.1448974609375 +1769682072,450740224,4.200336456298828,-0.0053255558013916016,580.236083984375 +1769682072,468844288,4.200899600982666,-0.004909992218017578,580.28173828125 +1769682072,515966720,4.202045917510986,-0.005597352981567383,580.3737182617188 +1769682072,552508416,4.203188419342041,-0.005832672119140625,580.4663696289062 +1769682072,565940992,4.2037529945373535,-0.005614638328552246,580.51318359375 +1769682072,614816000,4.204898834228516,-0.0062819719314575195,580.6076049804688 +1769682072,655382784,4.205740928649902,-0.006369948387145996,580.67919921875 +1769682072,670737920,4.206578254699707,-0.005569815635681152,580.751220703125 +1769682072,700968960,4.207402229309082,-0.005922555923461914,580.8235473632812 +1769682072,747522816,4.208494663238525,-0.006695389747619629,580.9202270507812 +1769682072,781414144,4.209237575531006,-0.0065767765045166016,580.9931640625 +1769682072,798556416,4.209969520568848,-0.006365418434143066,581.0664672851562 +1769682072,847474688,4.210899829864502,-0.007187008857727051,581.1648559570312 +1769682072,866779136,4.2114763259887695,-0.00671076774597168,581.2389526367188 +1769682072,912120064,4.212096214294434,-0.006321072578430176,581.3131103515625 +1769682072,953753600,4.2134318351745605,-0.006819605827331543,581.4364624023438 +1769682072,981623296,4.214207172393799,-0.006730437278747559,581.510009765625 +1769682072,999549696,4.2146711349487305,-0.005976438522338867,581.5588989257812 +1769682073,66892800,4.215674877166748,-0.0068721771240234375,581.6812133789062 +1769682073,70413312,4.216065883636475,-0.006504654884338379,581.7302856445312 +1769682073,115046144,4.216668605804443,-0.007178187370300293,581.8291625976562 +1769682073,146255616,4.217054843902588,-0.007035613059997559,581.9039916992188 +1769682073,181789952,4.2175703048706055,-0.007472991943359375,582.004638671875 +1769682073,201197312,4.217803001403809,-0.006695151329040527,582.0552368164062 +1769682073,251465728,4.218221187591553,-0.007699489593505859,582.1826171875 +1769682073,266733568,4.218364715576172,-0.007288575172424316,582.23388671875 +1769682073,315121920,4.218571186065674,-0.007876038551330566,582.3368530273438 +1769682073,346483456,4.218470573425293,-0.007947444915771484,582.4144287109375 +1769682073,366639616,4.218329429626465,-0.007524609565734863,582.4920654296875 +1769682073,415031552,4.21807861328125,-0.007832050323486328,582.5950317382812 +1769682073,465183744,4.217496395111084,-0.007716178894042969,582.6973876953125 +1769682073,479224320,4.2171173095703125,-0.00731503963470459,582.748291015625 +1769682073,498164736,4.216344356536865,-0.006863236427307129,582.8245239257812 +1769682073,543885056,4.2152228355407715,-0.007625222206115723,582.92578125 +1769682073,581686784,4.213772773742676,-0.007708191871643066,583.0272827148438 +1769682073,620846592,4.212557315826416,-0.007752537727355957,583.1035766601562 +1769682073,648460288,4.211234092712402,-0.007669806480407715,583.1802368164062 +1769682073,668643840,4.2096757888793945,-0.007716178894042969,583.2572021484375 +1769682073,698392576,4.20802116394043,-0.007761478424072266,583.335693359375 +1769682073,763804160,4.2051191329956055,-0.00869452953338623,583.4684448242188 +1769682073,771027200,4.203922271728516,-0.007645130157470703,583.5218505859375 +1769682073,799203328,4.201949119567871,-0.007941722869873047,583.6017456054688 +1769682073,841850368,4.199221611022949,-0.00850832462310791,583.7076416015625 +1769682073,877791488,4.197037696838379,-0.00799560546875,583.7860717773438 +1769682073,899057664,4.194931507110596,-0.00739288330078125,583.86376953125 +1769682073,952027904,4.191201686859131,-0.007869839668273926,583.9915771484375 +1769682073,966100992,4.189603805541992,-0.00740206241607666,584.042236328125 +1769682074,12899840,4.187165260314941,-0.007055163383483887,584.1179809570312 +1769682074,48603136,4.183715343475342,-0.007681608200073242,584.2186279296875 +1769682074,67603200,4.180952072143555,-0.007050752639770508,584.2938232421875 +1769682074,98534656,4.178104400634766,-0.006636142730712891,584.3685302734375 +1769682074,165488128,4.173147201538086,-0.007066488265991211,584.49169921875 +1769682074,174172672,4.170074462890625,-0.006924152374267578,584.5647583007812 +1769682074,199211008,4.167909145355225,-0.006181955337524414,584.6132202148438 +1769682074,244058624,4.163429260253906,-0.006745815277099609,584.709716796875 +1769682074,278135296,4.159875392913818,-0.006691455841064453,584.7821044921875 +1769682074,299054848,4.156299591064453,-0.006867527961730957,584.8533935546875 +1769682074,345435648,4.151305198669434,-0.008075952529907227,584.9468383789062 +1769682074,365844224,4.147459506988525,-0.008180499076843262,585.015869140625 +1769682074,412423680,4.143434524536133,-0.00822305679321289,585.0841064453125 +1769682074,447955456,4.137831687927246,-0.009315133094787598,585.174072265625 +1769682074,466330368,4.133478164672852,-0.009390592575073242,585.2411499023438 +1769682074,498725376,4.128988265991211,-0.009403347969055176,585.3082275390625 +1769682074,556762368,4.122771263122559,-0.010358691215515137,585.39794921875 +1769682074,573445632,4.116201400756836,-0.010545730590820312,585.4877319335938 +1769682074,599120640,4.112854957580566,-0.00996100902557373,585.5325317382812 +1769682074,645220352,4.106037139892578,-0.010564684867858887,585.6219482421875 +1769682074,677621504,4.100883960723877,-0.010276079177856445,585.6886596679688 +1769682074,699107072,4.095534324645996,-0.009868144989013672,585.7550048828125 +1769682074,748446976,4.088310241699219,-0.010175466537475586,585.8427734375 +1769682074,765392384,4.082660675048828,-0.009865283966064453,585.9081420898438 +1769682074,814113792,4.076900482177734,-0.009393930435180664,585.972900390625 +1769682074,852877312,4.069037437438965,-0.009728789329528809,586.058349609375 +1769682074,869879552,4.062946319580078,-0.009050965309143066,586.1219482421875 +1769682074,898738176,4.05682373046875,-0.008828043937683105,586.1849365234375 +1769682074,957598720,4.0484747886657715,-0.008957505226135254,586.2683715820312 +1769682074,969064704,4.042116165161133,-0.008414983749389648,586.3303833007812 +1769682074,999699712,4.035589694976807,-0.008048176765441895,586.3920288085938 +1769682075,42727936,4.026700973510742,-0.008327364921569824,586.4734497070312 +1769682075,65705984,4.019878387451172,-0.007816433906555176,586.5338134765625 +1769682075,105495296,4.0105509757995605,-0.007796168327331543,586.6134643554688 +1769682075,143508480,4.003475189208984,-0.007550358772277832,586.67236328125 +1769682075,168238592,3.9962711334228516,-0.0070656538009643555,586.7308349609375 +1769682075,198727168,3.9890353679656982,-0.006759285926818848,586.7886962890625 +1769682075,260673536,3.979132652282715,-0.006937742233276367,586.865478515625 +1769682075,269021952,3.971513509750366,-0.0067250728607177734,586.9229125976562 +1769682075,298668288,3.9637067317962646,-0.006561398506164551,586.9804077148438 +1769682075,344341760,3.953214168548584,-0.006924867630004883,587.056884765625 +1769682075,369783040,3.9451732635498047,-0.0064307451248168945,587.1142578125 +1769682075,401612800,3.9370944499969482,-0.006275534629821777,587.17138671875 +1769682075,447039488,3.9262218475341797,-0.0068024396896362305,587.247314453125 +1769682075,465972224,3.9177982807159424,-0.006543278694152832,587.3042602539062 +1769682075,502754304,3.9093360900878906,-0.006148219108581543,587.361328125 +1769682075,547833344,3.8977386951446533,-0.006767988204956055,587.4376831054688 +1769682075,567052288,3.8890280723571777,-0.006535053253173828,587.494873046875 +1769682075,598856192,3.8801143169403076,-0.0061719417572021484,587.5516357421875 +1769682075,648934912,3.868189573287964,-0.00639498233795166,587.62646484375 +1769682075,667184896,3.859071731567383,-0.0058928728103637695,587.6817626953125 +1769682075,698534400,3.8499093055725098,-0.005638480186462402,587.7362060546875 +1769682075,742691584,3.837531089782715,-0.005956411361694336,587.8079833984375 +1769682075,768362240,3.828037977218628,-0.005570173263549805,587.8613891601562 +1769682075,799247104,3.818523406982422,-0.0053424835205078125,587.9144287109375 +1769682075,844755712,3.8056764602661133,-0.00573575496673584,587.98486328125 +1769682075,866050048,3.795849084854126,-0.005421042442321777,588.0374755859375 +1769682075,901052416,3.7858331203460693,-0.005037426948547363,588.0899047851562 +1769682075,942098688,3.772491931915283,-0.005578517913818359,588.1593017578125 +1769682075,967003136,3.7622334957122803,-0.005406022071838379,588.2112426757812 +1769682075,999022080,3.751743793487549,-0.0052525997161865234,588.2635498046875 +1769682076,62257664,3.7374918460845947,-0.005680203437805176,588.333740234375 +1769682076,69206016,3.726581573486328,-0.005238652229309082,588.3865356445312 +1769682076,98892288,3.71557354927063,-0.005063652992248535,588.4393920898438 +1769682076,145333504,3.700779914855957,-0.005177974700927734,588.5090942382812 +1769682076,173582336,3.6858983039855957,-0.00484919548034668,588.577392578125 +1769682076,198850816,3.6783087253570557,-0.004267692565917969,588.6109008789062 +1769682076,243947264,3.662936210632324,-0.004408597946166992,588.6766967773438 +1769682076,266127104,3.651284694671631,-0.00403594970703125,588.7252807617188 +1769682076,301276928,3.639477252960205,-0.0036622285842895508,588.7734375 +1769682076,345529088,3.6234519481658936,-0.003915190696716309,588.8370361328125 +1769682076,368822016,3.611250638961792,-0.003407597541809082,588.8843994140625 +1769682076,398687744,3.598926067352295,-0.0031266212463378906,588.9310913085938 +1769682076,447529728,3.582329750061035,-0.0032311677932739258,588.9925537109375 +1769682076,466496256,3.5698013305664062,-0.0029299259185791016,589.0382690429688 +1769682076,499601920,3.5570433139801025,-0.0026096105575561523,589.0836181640625 +1769682076,544204800,3.53993821144104,-0.0028535127639770508,589.1436157226562 +1769682076,573030400,3.5269885063171387,-0.0022454261779785156,589.188232421875 +1769682076,599908864,3.51387882232666,-0.0022220611572265625,589.232421875 +1769682076,644513024,3.496248483657837,-0.0021823644638061523,589.2903442382812 +1769682076,666193664,3.4829189777374268,-0.0017189979553222656,589.332763671875 +1769682076,701225984,3.469552516937256,-0.0011949539184570312,589.3739013671875 +1769682076,747330304,3.4514286518096924,-0.0011930465698242188,589.427001953125 +1769682076,766080256,3.4378066062927246,-0.0010006427764892578,589.466064453125 +1769682076,799465728,3.42394757270813,-0.0008064508438110352,589.5049438476562 +1769682076,857316864,3.405374050140381,-0.0011661052703857422,589.5567626953125 +1769682076,870541056,3.391258716583252,-0.0008579492568969727,589.595947265625 +1769682076,898984704,3.377142906188965,-0.0008771419525146484,589.6351928710938 +1769682076,946434304,3.358144998550415,-0.0010868310928344727,589.6875 +1769682076,968635904,3.3438243865966797,-0.0007789134979248047,589.726318359375 +1769682077,27904,3.3293814659118652,-0.0005127191543579102,589.7644653320312 +1769682077,47987968,3.3099286556243896,-0.0006040334701538086,589.814453125 +1769682077,66199808,3.2952938079833984,-0.0004382133483886719,589.8513793945312 +1769682077,104909568,3.275602340698242,-0.0006515979766845703,589.900390625 +1769682077,145499648,3.2606725692749023,-0.0005383491516113281,589.9373779296875 +1769682077,166623744,3.2455835342407227,-0.0005205869674682617,589.9743041992188 +1769682077,198927616,3.2304532527923584,-0.0002894401550292969,590.0113525390625 +1769682077,249500672,3.2101030349731445,-0.0003802776336669922,590.0604858398438 +1769682077,265816064,3.194671869277954,-6.61611557006836e-05,590.0967407226562 +1769682077,300425216,3.1791915893554688,0.00024247169494628906,590.132568359375 +1769682077,342724864,3.1583657264709473,8.749961853027344e-05,590.1796264648438 +1769682077,369484544,3.1426985263824463,0.00035858154296875,590.2145385742188 +1769682077,399605760,3.1269125938415527,0.0003528594970703125,590.24951171875 +1769682077,443421440,3.105788469314575,0.00011873245239257812,590.296142578125 +1769682077,465841408,3.089869737625122,0.0003142356872558594,590.3311157226562 +1769682077,501730560,3.073869228363037,0.0006177425384521484,590.3658447265625 +1769682077,548642560,3.052337169647217,0.0005269050598144531,590.4114990234375 +1769682077,565800448,3.0359840393066406,0.0008976459503173828,590.4450073242188 +1769682077,599364096,3.0195798873901367,0.0012630224227905273,590.4776611328125 +1769682077,654803200,2.997558832168579,0.0012549161911010742,590.5201416015625 +1769682077,672459008,2.9809820652008057,0.0016093254089355469,590.5514526367188 +1769682077,698854144,2.964381217956543,0.0014842748641967773,590.5828247070312 +1769682077,747120128,2.942112922668457,0.001217961311340332,590.625 +1769682077,771056384,2.9253954887390137,0.0013726353645324707,590.6571044921875 +1769682077,799675904,2.908473253250122,0.0013495683670043945,590.6895141601562 +1769682077,843685376,2.885756492614746,0.0011844038963317871,590.7327880859375 +1769682077,866616320,2.8685944080352783,0.001368880271911621,590.7649536132812 +1769682077,901520896,2.851433277130127,0.001608431339263916,590.7966918945312 +1769682077,944873216,2.828479290008545,0.001515209674835205,590.8380737304688 +1769682077,967207936,2.811250686645508,0.0015491843223571777,590.8687133789062 +1769682077,999149824,2.7938265800476074,0.0015645623207092285,590.8995971679688 +1769682078,57702656,2.770555019378662,0.001164078712463379,590.9412841796875 +1769682078,75052032,2.747084617614746,0.0009219050407409668,590.9840087890625 +1769682078,101091072,2.735304117202759,0.0011570453643798828,591.0055541992188 +1769682078,143450368,2.711620330810547,0.0008941888809204102,591.0489501953125 +1769682078,169424896,2.6937339305877686,0.001168966293334961,591.0812377929688 +1769682078,199733504,2.6759402751922607,0.001351773738861084,591.113037109375 +1769682078,244115968,2.652113676071167,0.0013980269432067871,591.1541748046875 +1769682078,266550528,2.634300947189331,0.0017309784889221191,591.18408203125 +1769682078,301199616,2.6161577701568604,0.0020498037338256836,591.2131958007812 +1769682078,345520128,2.591951370239258,0.0019249916076660156,591.2511596679688 +1769682078,366061568,2.573807716369629,0.0019366741180419922,591.2794189453125 +1769682078,400481792,2.555602788925171,0.0018674731254577637,591.3082275390625 +1769682078,457517824,2.5312647819519043,0.0013788342475891113,591.347900390625 +1769682078,475522304,2.506880283355713,0.0011649131774902344,591.3888549804688 +1769682078,499165696,2.494589328765869,0.00130385160446167,591.4097290039062 +1769682078,544359168,2.470067262649536,0.001069486141204834,591.45166015625 +1769682078,572763392,2.451509952545166,0.001365065574645996,591.4829711914062 +1769682078,600336384,2.432663917541504,0.0014480352401733398,591.5137329101562 +1769682078,650249216,2.407529830932617,0.0014781355857849121,591.5540771484375 +1769682078,666296832,2.38869047164917,0.0017490386962890625,591.5835571289062 +1769682078,705250816,2.36344838142395,0.0017737746238708496,591.6221313476562 +1769682078,745967616,2.344533920288086,0.0017898082733154297,591.6507568359375 +1769682078,769036288,2.3255958557128906,0.0016932487487792969,591.6795654296875 +1769682078,799285248,2.30655837059021,0.0014348626136779785,591.709228515625 +1769682078,843120128,2.2811262607574463,0.0008445382118225098,591.7506103515625 +1769682078,866555392,2.2620935440063477,0.00063323974609375,591.7828979492188 +1769682078,899917056,2.243002414703369,0.0005003213882446289,591.8159790039062 +1769682078,943532288,2.2174227237701416,0.0002630949020385742,591.8606567382812 +1769682078,968904448,2.1982226371765137,0.0004406571388244629,591.8939819335938 +1769682078,999407616,2.1789088249206543,0.0005714893341064453,591.9266967773438 +1769682079,44838912,2.1531412601470947,0.0007125735282897949,591.9691162109375 +1769682079,66569216,2.133791446685791,0.0010474920272827148,591.9996948242188 +1769682079,104676096,2.10789155960083,0.0012598037719726562,592.0392456054688 +1769682079,145717504,2.0883920192718506,0.0012917518615722656,592.0682983398438 +1769682079,166095360,2.0687739849090576,0.0012053251266479492,592.0973510742188 +1769682079,200240896,2.049302101135254,0.001022934913635254,592.1272583007812 +1769682079,256679936,2.0234181880950928,0.0004200935363769531,592.1690673828125 +1769682079,276887552,1.997336745262146,2.5391578674316406e-05,592.2129516601562 +1769682079,299166976,1.9842828512191772,2.8371810913085938e-05,592.235595703125 +1769682079,344809728,1.9582207202911377,-0.00026857852935791016,592.2813720703125 +1769682079,371389440,1.9385483264923096,-2.962350845336914e-05,592.315673828125 +1769682079,399197440,1.9188884496688843,7.50422477722168e-05,592.349365234375 +1769682079,444941568,1.892671823501587,0.00024318695068359375,592.3928833007812 +1769682079,466256384,1.8729960918426514,0.0005960464477539062,592.42431640625 +1769682079,501239552,1.8532066345214844,0.0009570717811584473,592.4546508789062 +1769682079,545191424,1.8267825841903687,0.0011410117149353027,592.49365234375 +1769682079,566128384,1.8070611953735352,0.0013917088508605957,592.5220947265625 +1769682079,599267584,1.7873258590698242,0.001500546932220459,592.5501708984375 +1769682079,647830272,1.7611498832702637,0.0010425448417663574,592.588134765625 +1769682079,668014592,1.741471529006958,0.000593721866607666,592.6180419921875 +1769682079,700271360,1.7215913534164429,5.245208740234375e-05,592.6498413085938 +1769682079,741437440,1.695224642753601,-0.0008902549743652344,592.6954956054688 +1769682079,773125888,1.6755683422088623,-0.001216113567352295,592.731689453125 +1769682079,799643648,1.6558912992477417,-0.0016397833824157715,592.7689819335938 +1769682079,847722240,1.6297696828842163,-0.0020233988761901855,592.8194580078125 +1769682079,866426368,1.6101940870285034,-0.0018866658210754395,592.8570556640625 +1769682079,902607360,1.5839922428131104,-0.001711428165435791,592.9055786132812 +1769682079,944298240,1.5643203258514404,-0.0014390349388122559,592.9406127929688 +1769682079,966833920,1.5447907447814941,-0.0010887384414672852,592.9744262695312 +1769682079,999010048,1.5252881050109863,-0.0007354915142059326,593.0072021484375 +1769682080,48476416,1.4992746114730835,-0.0004596114158630371,593.0493774414062 +1769682080,68208128,1.4796994924545288,-0.00013813376426696777,593.0801391601562 +1769682080,99308544,1.4600245952606201,6.768107414245605e-05,593.1104736328125 +1769682080,145345280,1.4338608980178833,0.00020971894264221191,593.150390625 +1769682080,170112000,1.4143909215927124,0.00040602684020996094,593.1802368164062 +1769682080,200375040,1.394817590713501,0.00026223063468933105,593.2101440429688 +1769682080,247193088,1.3686723709106445,-0.0004240870475769043,593.25146484375 +1769682080,265980416,1.3490740060806274,-0.0010549426078796387,593.2843017578125 +1769682080,304724480,1.323011875152588,-0.0021929144859313965,593.3317260742188 +1769682080,347127808,1.3035321235656738,-0.002901136875152588,593.3698120117188 +1769682080,368714496,1.284227967262268,-0.0034177303314208984,593.4096069335938 +1769682080,399017216,1.2648298740386963,-0.0037469565868377686,593.4503784179688 +1769682080,449048064,1.239260196685791,-0.004049181938171387,593.5051879882812 +1769682080,466889728,1.220069169998169,-0.0039028525352478027,593.545654296875 +1769682080,499586560,1.2008570432662964,-0.0036132633686065674,593.5847778320312 +1769682080,541713664,1.1752135753631592,-0.0032916367053985596,593.634765625 +1769682080,571107840,1.1560606956481934,-0.002805769443511963,593.6705322265625 +1769682080,599867392,1.1369574069976807,-0.002345860004425049,593.705078125 +1769682080,648229632,1.1115604639053345,-0.0019066035747528076,593.7493286132812 +1769682080,666833920,1.0925883054733276,-0.0015231668949127197,593.7815551757812 +1769682080,704327936,1.0671459436416626,-0.001134335994720459,593.823486328125 +1769682080,744271104,1.0481703281402588,-0.0008683204650878906,593.8543701171875 +1769682080,766461440,1.029191493988037,-0.0006545186042785645,593.8849487304688 +1769682080,799199744,1.0102519989013672,-0.00041687488555908203,593.915283203125 +1769682080,850404352,0.9850910305976868,-0.00024521350860595703,593.9553833007812 +1769682080,866630400,0.966398298740387,-0.00013127923011779785,593.985107421875 +1769682080,899343872,0.9476224780082703,-8.255243301391602e-06,594.0147094726562 +1769682080,947525888,0.9232548475265503,-0.00028640031814575195,594.0540161132812 +1769682080,969284096,0.9051414132118225,-0.0006743669509887695,594.0842895507812 +1769682081,18048256,0.880479633808136,-0.001440674066543579,594.1265869140625 +1769682081,43672832,0.8559046983718872,-0.0021407604217529297,594.171630859375 +1769682081,68006400,0.8436317443847656,-0.0024844706058502197,594.195068359375 +1769682081,100709632,0.82558274269104,-0.002933979034423828,594.2312622070312 +1769682081,146224384,0.8017092943191528,-0.00343891978263855,594.280517578125 +1769682081,166243072,0.7842144966125488,-0.00356099009513855,594.3176879882812 +1769682081,212734720,0.7664812207221985,-0.0035378187894821167,594.3544921875 +1769682081,246182144,0.7434143424034119,-0.0034394264221191406,594.4022827148438 +1769682081,267719424,0.7258698344230652,-0.003162100911140442,594.4369506835938 +1769682081,299233792,0.7083708047866821,-0.0027969926595687866,594.4705200195312 +1769682081,359303680,0.685350239276886,-0.0023061931133270264,594.513427734375 +1769682081,367841280,0.6686122417449951,-0.0018102973699569702,594.5441284179688 +1769682081,400422144,0.6516522765159607,-0.0012771934270858765,594.5736083984375 +1769682081,443119360,0.6294525861740112,-0.0006031394004821777,594.611083984375 +1769682081,467625984,0.613219678401947,-2.0951032638549805e-05,594.6377563476562 +1769682081,500161536,0.5970613360404968,0.0005404055118560791,594.663330078125 +1769682081,544897280,0.5760552883148193,0.0012618601322174072,594.6956176757812 +1769682081,566088192,0.5605496168136597,0.0018070191144943237,594.718505859375 +1769682081,610213376,0.5450475811958313,0.0023380815982818604,594.7404174804688 +1769682081,647767808,0.5243770480155945,0.002983078360557556,594.7678833007812 +1769682081,666550016,0.5088746547698975,0.003436446189880371,594.7874145507812 +1769682081,700019712,0.49337315559387207,0.003894522786140442,594.8057250976562 +1769682081,756771840,0.47394269704818726,0.004456192255020142,594.8287963867188 +1769682081,770513408,0.4621501863002777,0.0048857927322387695,594.8449096679688 +1769682081,801997824,0.45221227407455444,0.0051904767751693726,594.860107421875 +1769682081,846141696,0.43576693534851074,0.0055833905935287476,594.8789672851562 +1769682081,878963712,0.4202668070793152,0.005906000733375549,594.8925170898438 +1769682081,899416832,0.40600425004959106,0.0062892138957977295,594.9053344726562 +1769682081,946738688,0.3853442072868347,0.006692469120025635,594.9215087890625 +1769682081,966739712,0.3717249035835266,0.006970919668674469,594.9327392578125 +1769682082,13280512,0.3587343394756317,0.007301591336727142,594.9431762695312 +1769682082,48775424,0.34057632088661194,0.007609367370605469,594.9559936523438 +1769682082,68647168,0.32699865102767944,0.007843121886253357,594.9649658203125 +1769682082,100448000,0.3140687346458435,0.008091777563095093,594.9732666015625 +1769682082,159311360,0.2959785759449005,0.008372589945793152,594.9834594726562 +1769682082,170823936,0.2817043662071228,0.008591748774051666,594.9906616210938 +1769682082,200621568,0.2693038880825043,0.008776649832725525,594.9972534179688 +1769682082,243671296,0.24863706529140472,0.00910796970129013,595.00537109375 +1769682082,278266880,0.23506715893745422,0.009312920272350311,595.0108642578125 +1769682082,301583616,0.22400572896003723,0.009492412209510803,595.0158081054688 +1769682082,343454720,0.21113230288028717,0.009676314890384674,595.0215454101562 +1769682082,366455040,0.2016228884458542,0.00980159267783165,595.0252075195312 +1769682082,410631424,0.19211407005786896,0.009974218904972076,595.0285034179688 +1769682082,448695296,0.1794353872537613,0.010126959532499313,595.0321655273438 +1769682082,469931776,0.16992421448230743,0.01025613397359848,595.0346069335938 +1769682082,499282432,0.16041310131549835,0.010413475334644318,595.0368041992188 +1769682082,556253696,0.14773161709308624,0.010538484901189804,595.039306640625 +1769682082,572815104,0.13504646718502045,0.010673053562641144,595.0413818359375 +1769682082,600840960,0.12870414555072784,0.010747265070676804,595.0421752929688 +1769682082,646148608,0.1160198226571083,0.010897040367126465,595.043701171875 +1769682082,681526528,0.10650379210710526,0.010980073362588882,595.0444946289062 +1769682082,699470592,0.09698845446109772,0.011085037142038345,595.0451049804688 +1769682082,743712256,0.08431248366832733,0.011204002425074577,595.0455932617188 +1769682082,766361856,0.07480286061763763,0.011233502998948097,595.0457763671875 +1769682082,811415808,0.06529336422681808,0.01129429042339325,595.0457763671875 +1769682082,846758656,0.052614111453294754,0.01142625417560339,595.0455322265625 +1769682082,868135936,0.043102484196424484,0.011495397426187992,595.0452270507812 +1769682082,899344640,0.0,-0.0,595.0459594726562 +1769682082,959241216,0.0,-0.0,595.0459594726562 +1769682082,967655424,0.0,-0.0,595.0459594726562 +1769682083,653568,0.0,-0.0,595.0459594726562 +1769682083,44847616,0.0,-0.0,595.0459594726562 +1769682083,66499328,0.0,-0.0,595.0459594726562 +1769682083,100040192,0.0,-0.0,595.0459594726562 +1769682083,144382208,0.0,-0.0,595.0459594726562 +1769682083,166351616,0.0,-0.0,595.0459594726562 +1769682083,210019328,0.0,-0.0,595.0459594726562 +1769682083,252273408,0.0,-0.0,595.0459594726562 +1769682083,268891392,0.0,-0.0,595.0459594726562 +1769682083,299468800,0.0,-0.0,595.0459594726562 +1769682083,355685120,0.0,-0.0,595.0459594726562 +1769682083,370723840,0.0,-0.0,595.0459594726562 +1769682083,400806656,0.0,-0.0,595.0459594726562 +1769682083,444600320,0.0,-0.0,595.0459594726562 +1769682083,484027648,0.0,-0.0,595.0459594726562 +1769682083,499753216,0.0,-0.0,595.0459594726562 +1769682083,552578048,0.0,-0.0,595.0459594726562 +1769682083,567736832,0.0,-0.0,595.0459594726562 +1769682083,609743360,0.0,-0.0,595.0459594726562 +1769682083,650066944,0.0,-0.0,595.0459594726562 +1769682083,669276672,0.0,-0.0,595.0459594726562 +1769682083,699639552,0.0,-0.0,595.0459594726562 +1769682083,748513024,0.0,-0.0,595.0459594726562 +1769682083,766773248,0.0,-0.0,595.0459594726562 +1769682083,799625728,0.0,-0.0,595.0459594726562 +1769682083,845560064,0.0,-0.0,595.0459594726562 +1769682083,873488384,0.0,-0.0,595.0459594726562 +1769682083,900744192,0.0,-0.0,595.0459594726562 +1769682083,944880640,0.0,-0.0,595.0459594726562 +1769682083,966494976,0.0,-0.0,595.0459594726562 +1769682084,1017088,0.0,-0.0,595.0459594726562 +1769682084,53259008,0.0,-0.0,595.0460205078125 +1769682084,69108736,0.0,-0.0,595.0460205078125 +1769682084,99521024,0.0,-0.0,595.0460205078125 +1769682084,146659584,0.0,-0.0,595.0460205078125 +1769682084,166736128,0.0,-0.0,595.0460205078125 +1769682084,199493632,0.0,-0.0,595.0460205078125 +1769682084,244625152,0.0,-0.0,595.0460205078125 +1769682084,268357632,0.0,-0.0,595.0460205078125 +1769682084,301943808,0.0,-0.0,595.0460205078125 +1769682084,343927808,0.0,-0.0,595.0460205078125 +1769682084,376743168,0.0,-0.0,595.0460205078125 +1769682084,400738816,0.0,-0.0,595.0460205078125 +1769682084,444682240,0.0,-0.0,595.0460205078125 +1769682084,466789376,0.0,-0.0,595.0460205078125 +1769682084,515276544,0.0,-0.0,595.0460205078125 +1769682084,550225408,0.0,-0.0,595.0460205078125 +1769682084,568155648,0.0,-0.0,595.0460205078125 +1769682084,599814144,0.0,-0.0,595.0460205078125 +1769682084,657167616,0.0,-0.0,595.0460205078125 +1769682084,670425344,0.0,-0.0,595.0460205078125 +1769682084,701838848,0.0,-0.0,595.0460205078125 +1769682084,744483840,0.0,-0.0,595.0460205078125 +1769682084,777924352,0.0,-0.0,595.0460205078125 +1769682084,799596544,0.0,-0.0,595.0460205078125 +1769682084,849946624,0.0,-0.0,595.0460205078125 +1769682084,868508672,0.0,-0.0,595.0460205078125 +1769682084,910160896,0.0,-0.0,595.0460205078125 +1769682084,949344768,0.0,-0.0,595.0460205078125 +1769682084,967320320,0.0,-0.0,595.0460205078125 +1769682084,999742208,0.0,-0.0,595.0460205078125 +1769682085,56089856,0.0,-0.0,595.0460205078125 +1769682085,69967360,0.0,-0.0,595.0460205078125 +1769682085,101258496,0.0,-0.0,595.0460205078125 +1769682085,144666624,0.0,-0.0,595.0460205078125 +1769682085,178153216,0.0,-0.0,595.0460205078125 +1769682085,200668416,0.0,-0.0,595.0460205078125 +1769682085,242048000,0.0,-0.0,595.0460205078125 +1769682085,267771136,0.0,-0.0,595.0460205078125 +1769682085,308499712,0.0,-0.0,595.0460205078125 +1769682085,344192000,0.0,-0.0,595.0460205078125 +1769682085,367932672,0.0,-0.0,595.0460205078125 +1769682085,399806976,0.0,-0.0,595.0460205078125 +1769682085,456473600,0.0,-0.0,595.0460205078125 +1769682085,469579008,0.0,-0.0,595.0460205078125 +1769682085,500752896,0.0,-0.0,595.0460205078125 +1769682085,543247360,0.0,-0.0,595.0460205078125 +1769682085,578151168,0.0,-0.0,595.0460205078125 +1769682085,600925184,0.0,-0.0,595.0460205078125 +1769682085,653026048,0.0,-0.0,595.0460205078125 +1769682085,667531264,0.0,-0.0,595.0460205078125 +1769682085,715071488,0.0,-0.0,595.0460205078125 +1769682085,752646912,0.0,-0.0,595.0460205078125 +1769682085,767166464,0.0,-0.0,595.0460205078125 +1769682085,800109568,0.0,-0.0,595.0460205078125 +1769682085,853917952,0.0,-0.0,595.0460205078125 +1769682085,867773184,0.0,-0.0,595.0460205078125 +1769682085,901641472,0.0,-0.0,595.0460205078125 +1769682085,945278720,0.0,-0.0,595.0460205078125 +1769682085,977356800,0.0,-0.0,595.0460205078125 +1769682086,3714304,0.0,-0.0,595.0460205078125 +1769682086,45648128,0.0,-0.0,595.0460205078125 +1769682086,66493696,0.0,-0.0,595.0460205078125 +1769682086,113440512,0.0,-0.0,595.0460205078125 +1769682086,149990912,0.0,-0.0,595.0460205078125 +1769682086,168994816,0.0,-0.0,595.0460205078125 +1769682086,199829248,0.0,-0.0,595.0460205078125 +1769682086,263319040,0.0,-0.0,595.0460205078125 +1769682086,270981120,0.0,-0.0,595.0460205078125 +1769682086,300742400,0.0,-0.0,595.0460205078125 +1769682086,344598272,0.0,-0.0,595.0460205078125 +1769682086,367198208,0.0,-0.0,595.0460205078125 +1769682086,406346240,0.0,-0.0,595.0460205078125 +1769682086,452542976,0.0,-0.0,595.0460205078125 +1769682086,468201984,0.0,-0.0,595.0460205078125 +1769682086,499777792,0.0,-0.0,595.0460205078125 +1769682086,559496448,0.0,-0.0,595.0460205078125 +1769682086,575485440,0.0,-0.0,595.0460205078125 +1769682086,600046592,0.0,-0.0,595.0460205078125 +1769682086,642333184,0.0,-0.0,595.0460205078125 +1769682086,670466304,0.0,-0.0,595.0460205078125 +1769682086,701947136,0.0,-0.0,595.0460205078125 +1769682086,746746880,0.0,-0.0,595.0460205078125 +1769682086,766935296,0.0,-0.0,595.0460205078125 +1769682086,800072960,0.0,-0.0,595.0460205078125 +1769682086,847519232,0.0,-0.0,595.0460205078125 +1769682086,866787840,0.0,-0.0,595.0460205078125 +1769682086,900205312,0.0,-0.0,595.0460205078125 +1769682086,962212352,0.0,-0.0,595.0460205078125 +1769682086,968286464,0.0,-0.0,595.0460205078125 +1769682087,1990656,0.0,-0.0,595.0460205078125 +1769682087,45661440,0.0,-0.0,595.0460205078125 +1769682087,70301952,0.0,-0.0,595.0460205078125 +1769682087,101434624,0.0,-0.0,595.0460205078125 +1769682087,144342784,0.0,-0.0,595.0460205078125 +1769682087,167131904,0.0,-0.0,595.0460205078125 +1769682087,200808704,0.0,-0.0,595.0460205078125 +1769682087,242951168,0.0,-0.0,595.0460205078125 +1769682087,267593984,0.0,-0.0,595.0460205078125 +1769682087,300301568,0.0,-0.0,595.0460205078125 +1769682087,349877760,0.0,-0.0,595.0460205078125 +1769682087,369783808,0.0,-0.0,595.0460205078125 +1769682087,400265472,0.0,-0.0,595.0460205078125 +1769682087,460486144,0.0,-0.0,595.0460205078125 +1769682087,466914048,0.0,-0.0,595.0460205078125 +1769682087,501124096,0.0,-0.0,595.0460205078125 +1769682087,542052864,0.0,-0.0,595.0460205078125 +1769682087,566753024,0.0,-0.0,595.0460205078125 +1769682087,600514560,0.0,-0.0,595.0460205078125 +1769682087,646750720,0.0,-0.0,595.0460205078125 +1769682087,666792704,0.0,-0.0,595.0460205078125 +1769682087,711515392,0.0,-0.0,595.0460205078125 +1769682087,747710976,0.0,-0.0,595.0460205078125 +1769682087,768873728,0.0,-0.0,595.0460205078125 +1769682087,799913472,0.0,-0.0,595.0460205078125 +1769682087,861070848,0.0,-0.0,595.0460205078125 +1769682087,868840704,0.0,-0.0,595.0460205078125 +1769682087,901200896,0.0,-0.0,595.0460205078125 +1769682087,942525184,0.0,-0.0,595.0460205078125 +1769682087,966996736,0.0,-0.0,595.0460205078125 +1769682088,758528,0.0,-0.0,595.0460205078125 +1769682088,57256448,0.0,-0.0,595.0460205078125 +1769682088,66032640,0.0,-0.0,595.0460205078125 +1769682088,115894016,0.0,-0.0,595.0460205078125 +1769682088,143513344,0.0,-0.0,595.0460205078125 +1769682088,167181568,0.0,-0.0,595.0460205078125 +1769682088,199896064,0.0,-0.0,595.0460205078125 +1769682088,253044480,0.0,-0.0,595.0460205078125 +1769682088,266701312,0.0,-0.0,595.0460205078125 +1769682088,300723200,0.0,-0.0,595.0460205078125 +1769682088,345487104,0.0,-0.0,595.0460205078125 +1769682088,380301312,0.0,-0.0,595.0460205078125 +1769682088,400850688,0.0,-0.0,595.0460205078125 +1769682088,444826880,0.0,-0.0,595.0460205078125 +1769682088,466938368,0.0,-0.0,595.0460205078125 +1769682088,510375168,0.0,-0.0,595.0460205078125 +1769682088,550420480,0.0,-0.0,595.0460205078125 +1769682088,570011392,0.0,-0.0,595.0460205078125 +1769682088,600254720,0.0,-0.0,595.0460205078125 +1769682088,655870208,0.0,-0.0,595.0460205078125 +1769682088,670202624,0.0,-0.0,595.0460205078125 +1769682088,701188608,0.0,-0.0,595.0460205078125 +1769682088,744651520,0.0,-0.0,595.0460205078125 +1769682088,777669120,0.0,-0.0,595.0460205078125 +1769682088,800749568,0.0,-0.0,595.0460205078125 +1769682088,846280704,0.0,-0.0,595.0460205078125 +1769682088,867312896,0.0,-0.0,595.0460205078125 +1769682088,914400256,0.0,-0.0,595.0460205078125 +1769682088,946911232,0.0,-0.0,595.0460205078125 +1769682088,968318208,0.0,-0.0,595.0460205078125 +1769682089,359424,0.0,-0.0,595.0460205078125 +1769682089,59989248,0.0,-0.0,595.0460205078125 +1769682089,71097856,0.0,-0.0,595.0460205078125 +1769682089,101735424,0.0,-0.0,595.0460205078125 +1769682089,142663424,0.0,-0.0,595.0460205078125 +1769682089,168030720,0.0,-0.0,595.0460205078125 +1769682089,201004288,0.0,-0.0,595.0460205078125 +1769682089,244797184,0.0,-0.0,595.0460205078125 +1769682089,267593216,0.0,-0.0,595.0460205078125 +1769682089,299961088,0.0,-0.0,595.0460205078125 +1769682089,359496704,0.0,-0.0,595.0460205078125 +1769682089,372410880,0.0,-0.0,595.0460205078125 +1769682089,400912640,0.0,-0.0,595.0460205078125 +1769682089,443479552,0.0,-0.0,595.0460205078125 +1769682089,468326144,0.0,-0.0,595.0460205078125 +1769682089,502152448,0.0,-0.0,595.0460205078125 +1769682089,544260864,0.0,-0.0,595.0460205078125 +1769682089,577681920,0.0,-0.0,595.0460205078125 +1769682089,601679872,0.0,-0.0,595.0460205078125 +1769682089,646577152,0.0,-0.0,595.0460205078125 +1769682089,667211520,0.0,-0.0,595.0460205078125 +1769682089,712577792,0.0,-0.0,595.0460205078125 +1769682089,748062464,0.0,-0.0,595.0460205078125 +1769682089,767920384,0.0,-0.0,595.0460205078125 +1769682089,800861696,0.0,-0.0,595.0460205078125 +1769682089,858436864,0.0,-0.0,595.0460205078125 +1769682089,868858112,0.0,-0.0,595.0460205078125 +1769682089,901336320,0.0,-0.0,595.0460205078125 +1769682089,944389376,0.0,-0.0,595.0460205078125 +1769682089,967881472,0.0,-0.0,595.0460205078125 +1769682090,257280,0.0,-0.0,595.0460205078125 +1769682090,42771968,0.0,-0.0,595.0460205078125 +1769682090,67807744,0.0,-0.0,595.0460205078125 +1769682090,110488832,0.0,-0.0,595.0460205078125 +1769682090,148538368,0.0,-0.0,595.0460205078125 +1769682090,168489216,0.0,-0.0,595.0460205078125 +1769682090,200728064,0.0,-0.0,595.0460205078125 +1769682090,261348096,0.0,-0.0,595.0460205078125 +1769682090,270057472,0.0,-0.0,595.0460205078125 +1769682090,302282496,0.0,-0.0,595.0460205078125 +1769682090,345687808,0.0,-0.0,595.0460205078125 +1769682090,366953472,0.0,-0.0,595.0460205078125 +1769682090,402300160,0.0,-0.0,595.0460205078125 +1769682090,448028416,0.0,-0.0,595.0460205078125 +1769682090,468740352,0.0,-0.0,595.0460205078125 +1769682090,500964352,0.0,-0.0,595.0460205078125 +1769682090,549586688,0.0,-0.0,595.0460205078125 +1769682090,567851520,0.0,-0.0,595.0460205078125 +1769682090,601137920,0.0,-0.0,595.0460205078125 +1769682090,655128832,0.0,-0.0,595.0460205078125 +1769682090,667663104,0.0,-0.0,595.0460205078125 +1769682090,700353024,0.0,-0.0,595.0460205078125 +1769682090,746530816,0.0,-0.0,595.0460205078125 +1769682090,779245568,0.0,-0.0,595.0460205078125 +1769682090,801247744,0.0,-0.0,595.0460205078125 +1769682090,845111552,0.0,-0.0,595.0460205078125 +1769682090,867724032,0.0,-0.0,595.0460205078125 +1769682090,912970240,0.0,-0.0,595.0460205078125 +1769682090,949839616,0.0,-0.0,595.0460205078125 +1769682090,969208320,0.0,-0.0,595.0460205078125 +1769682091,702976,0.0,-0.0,595.0460205078125 +1769682091,59461376,0.0,-0.0,595.0460205078125 +1769682091,70676736,0.0,-0.0,595.0460205078125 +1769682091,102295040,0.0,-0.0,595.0460205078125 +1769682091,146952448,0.0,-0.0,595.0460205078125 +1769682091,178936064,0.0,-0.0,595.0460205078125 +1769682091,200229888,0.0,-0.0,595.0460205078125 +1769682091,247408640,0.0,-0.0,595.0460205078125 +1769682091,267329536,0.0,-0.0,595.0460205078125 +1769682091,315355136,0.0,-0.0,595.0460205078125 +1769682091,348527872,0.0,-0.0,595.0460205078125 +1769682091,367772416,0.0,-0.0,595.0460205078125 +1769682091,402522112,0.0,-0.0,595.0460205078125 +1769682091,463196672,0.0,-0.0,595.0460205078125 +1769682091,471121408,0.0,-0.0,595.0460205078125 +1769682091,501043712,0.0,-0.0,595.0460205078125 +1769682091,542918400,0.0,-0.0,595.0460205078125 +1769682091,567469824,0.0,-0.0,595.0460205078125 +1769682091,601739008,0.0,-0.0,595.0460205078125 +1769682091,644812032,0.0,-0.0,595.0460205078125 +1769682091,668060416,0.0,-0.0,595.0460205078125 +1769682091,700255232,0.0,-0.0,595.0460205078125 +1769682091,747239936,0.0,-0.0,595.0460205078125 +1769682091,767849728,0.0,-0.0,595.0460205078125 +1769682091,800330240,0.0,-0.0,595.0460205078125 +1769682091,842411520,0.0,-0.0,595.0460205078125 +1769682091,872898048,0.0,-0.0,595.0460205078125 +1769682091,902231808,0.0,-0.0,595.0460205078125 +1769682091,946402560,0.0,-0.0,595.0460205078125 +1769682091,967419392,0.0,-0.0,595.0460205078125 +1769682092,2174208,0.0,-0.0,595.0460205078125 +1769682092,48662784,0.0,-0.0,595.0460205078125 +1769682092,69630976,0.0,-0.0,595.0460205078125 +1769682092,100746240,0.0,-0.0,595.0460205078125 +1769682092,149553152,0.0,-0.0,595.0460205078125 +1769682092,168215552,0.0,-0.0,595.0460205078125 +1769682092,201261568,0.0,-0.0,595.0460205078125 +1769682092,244874752,0.0,-0.0,595.0460205078125 +1769682092,269065216,0.0,-0.0,595.0460205078125 +1769682092,301879808,0.0,-0.0,595.0460205078125 +1769682092,345524224,0.0,-0.0,595.0460205078125 +1769682092,379899136,0.0,-0.0,595.0460205078125 +1769682092,400440576,0.0,-0.0,595.0460205078125 +1769682092,445587968,0.0,-0.0,595.0460205078125 +1769682092,467280384,0.0,-0.0,595.0460205078125 +1769682092,512416768,0.0,-0.0,595.0460205078125 +1769682092,549800448,0.0,-0.0,595.0460205078125 +1769682092,568284928,0.0,-0.0,595.0460205078125 +1769682092,600460544,0.0,-0.0,595.0460205078125 +1769682092,654857984,0.0,-0.0,595.0460205078125 +1769682092,667777536,0.0,-0.0,595.0460205078125 +1769682092,701326080,0.0,-0.0,595.0460205078125 +1769682092,747479808,0.0,-0.0,595.0460205078125 +1769682092,784129024,0.0,-0.0,595.0460205078125 +1769682092,800947456,0.0,-0.0,595.0460205078125 +1769682092,846666496,0.0,-0.0,595.0460205078125 +1769682092,867120384,0.0,-0.0,595.0460205078125 +1769682092,900412672,0.0,-0.0,595.0460205078125 +1769682092,950244096,0.0,-0.0,595.0460205078125 +1769682092,968660736,0.0,-0.0,595.0460205078125 +1769682093,1161472,0.0,-0.0,595.0460205078125 +1769682093,45659136,0.0,-0.0,595.0460205078125 +1769682093,68429056,0.0,-0.0,595.0460205078125 +1769682093,101346304,0.0,-0.0,595.0460205078125 +1769682093,146858240,0.0,-0.0,595.0460205078125 +1769682093,170796032,0.0,-0.0,595.0460205078125 +1769682093,201356544,0.0,-0.0,595.0460205078125 +1769682093,244364800,0.0,-0.0,595.0460205078125 +1769682093,281857792,0.0,-0.0,595.0460205078125 +1769682093,301108736,0.0,-0.0,595.0460205078125 +1769682093,346138880,0.0,-0.0,595.0460205078125 +1769682093,367251200,0.0,-0.0,595.0460205078125 +1769682093,415964672,0.0,-0.0,595.0460205078125 +1769682093,448157952,0.0,-0.0,595.0460205078125 +1769682093,467810560,0.0,-0.0,595.0460205078125 +1769682093,502105856,0.0,-0.0,595.0460205078125 +1769682093,553842432,0.0,-0.0,595.0460205078125 +1769682093,568423424,0.0,-0.0,595.0460205078125 +1769682093,601573632,0.0,-0.0,595.0460205078125 +1769682093,649358080,0.0,-0.0,595.0460205078125 +1769682093,678871040,0.0,-0.0,595.0460205078125 +1769682093,701318912,0.0,-0.0,595.0460205078125 +1769682093,748847360,0.0,-0.0,595.0460205078125 +1769682093,767556864,0.0,-0.0,595.0460205078125 +1769682093,812131072,0.0,-0.0,595.0460205078125 +1769682093,847674624,0.0,-0.0,595.0460205078125 +1769682093,868602880,0.0,-0.0,595.0460205078125 +1769682093,901357312,0.0,-0.0,595.0460205078125 +1769682093,962885120,0.0,-0.0,595.0460205078125 +1769682093,972430848,0.0,-0.0,595.0460205078125 +1769682094,1585152,0.0,-0.0,595.0460205078125 +1769682094,47435776,0.0,-0.0,595.0460205078125 +1769682094,67964160,0.0,-0.0,595.0460205078125 +1769682094,103548416,0.0,-0.0,595.0460205078125 +1769682094,147037696,0.0,-0.0,595.0460205078125 +1769682094,167775744,0.0,-0.0,595.0460205078125 +1769682094,201607680,0.0,-0.0,595.0460205078125 +1769682094,251003904,0.0,-0.0,595.0460205078125 +1769682094,268652544,0.0,-0.0,595.0460205078125 +1769682094,301113344,0.0,-0.0,595.0460205078125 +1769682094,349791488,0.0,-0.0,595.0460205078125 +1769682094,375056384,0.0,-0.0,595.0460205078125 +1769682094,402107392,0.0,-0.0,595.0460205078125 +1769682094,444923136,0.0,-0.0,595.0460205078125 +1769682094,467968256,0.0,-0.0,595.0460205078125 +1769682094,502096896,0.0,-0.0,595.0460205078125 +1769682094,547809536,0.0,-0.0,595.0460205078125 +1769682094,568917504,0.0,-0.0,595.0460205078125 +1769682094,600631296,0.0,-0.0,595.0460205078125 +1769682094,646519552,0.0,-0.0,595.0460205078125 +1769682094,667739648,0.0,-0.0,595.0460205078125 +1769682094,703357952,0.0,-0.0,595.0460205078125 +1769682094,744399360,0.0,-0.0,595.0460205078125 +1769682094,770948608,0.0,-0.0,595.0460205078125 +1769682094,802944256,0.0,-0.0,595.0460205078125 +1769682094,845568000,0.0,-0.0,595.0460205078125 +1769682094,883061248,0.0,-0.0,595.0460205078125 +1769682094,901376768,0.0,-0.0,595.0460205078125 +1769682094,944872704,0.0,-0.0,595.0460205078125 +1769682094,967782144,0.0,-0.0,595.0460205078125 +1769682095,11738624,0.0,-0.0,595.0460205078125 +1769682095,48809728,0.0,-0.0,595.0460205078125 +1769682095,69614592,0.0,-0.0,595.0460205078125 +1769682095,100644352,0.0,-0.0,595.0460205078125 +1769682095,157391104,0.0,-0.0,595.0460205078125 +1769682095,173179136,0.0,-0.0,595.0460205078125 +1769682095,201956864,0.0,-0.0,595.0460205078125 +1769682095,246407680,0.0,-0.0,595.0460205078125 +1769682095,278473728,0.0,-0.0,595.0460205078125 +1769682095,301786880,0.0,-0.0,595.0460205078125 +1769682095,349749504,0.0,-0.0,595.0460205078125 +1769682095,367815168,0.0,-0.0,595.0460205078125 +1769682095,414122240,0.0,-0.0,595.0460205078125 +1769682095,449124864,0.0,-0.0,595.0460205078125 +1769682095,469576960,0.0,-0.0,595.0460205078125 +1769682095,500763648,0.0,-0.0,595.0460205078125 +1769682095,561742592,0.0,-0.0,595.0460205078125 +1769682095,570810624,0.0,-0.0,595.0460205078125 +1769682095,602256128,0.0,-0.0,595.0460205078125 +1769682095,642893824,0.0,-0.0,595.0460205078125 +1769682095,667728640,0.0,-0.0,595.0460205078125 +1769682095,705484032,0.0,-0.0,595.0460205078125 +1769682095,745607936,0.0,-0.0,595.0460205078125 +1769682095,767791872,0.0,-0.0,595.0460205078125 +1769682095,801393152,0.0,-0.0,595.0460205078125 +1769682095,849348864,0.0,-0.0,595.0460205078125 +1769682095,869302528,0.0,-0.0,595.0460205078125 +1769682095,900881408,0.0,-0.0,595.0460205078125 +1769682095,943066368,0.0,-0.0,595.0460205078125 +1769682095,969249792,0.0,-0.0,595.0460205078125 +1769682096,2141952,0.0,-0.0,595.0460205078125 +1769682096,45041408,0.0,-0.0,595.0460205078125 +1769682096,68201984,0.0,-0.0,595.0460205078125 +1769682096,105097728,0.0,-0.0,595.0460205078125 +1769682096,144802304,0.0,-0.0,595.0460205078125 +1769682096,168890112,0.0,-0.0,595.0460205078125 +1769682096,200909312,0.0,-0.0,595.0460205078125 +1769682096,247878912,0.0,-0.0,595.0460205078125 +1769682096,267697408,0.0,-0.0,595.0460205078125 +1769682096,301723136,0.0,-0.0,595.0460205078125 +1769682096,346430464,0.0,-0.0,595.0460205078125 +1769682096,368822528,0.0,-0.0,595.0460205078125 +1769682096,400844800,0.0,-0.0,595.0460205078125 +1769682096,448357120,0.0,-0.0,595.0460205078125 +1769682096,482990336,0.0,-0.0,595.0460205078125 +1769682096,501094912,0.0,-0.0,595.0460205078125 +1769682096,551904000,0.0,-0.0,595.0460205078125 +1769682096,567766784,0.0,-0.0,595.0460205078125 +1769682096,611592960,0.0,-0.0,595.0460205078125 +1769682096,649420288,0.0,-0.0,595.0460205078125 +1769682096,668521216,0.0,-0.0,595.0460205078125 +1769682096,701349632,0.0,-0.0,595.0460205078125 +1769682096,755279360,0.0,-0.0,595.0460205078125 +1769682096,769503488,0.0,-0.0,595.0460205078125 +1769682096,804146944,0.0,-0.0,595.0460205078125 +1769682096,846772224,0.0,-0.0,595.0460205078125 +1769682096,884144896,0.0,-0.0,595.0460205078125 +1769682096,901284352,0.0,-0.0,595.0460205078125 +1769682096,946731008,0.0,-0.0,595.0460205078125 +1769682096,968095744,0.0,-0.0,595.0460205078125 +1769682097,3885056,0.0,-0.0,595.0460205078125 +1769682097,49071872,0.0,-0.0,595.0460205078125 +1769682097,69111296,0.0,-0.0,595.0460205078125 +1769682097,101014016,0.0,-0.0,595.0460205078125 +1769682097,160533248,0.0,-0.0,595.0460205078125 +1769682097,170844928,0.0,-0.0,595.0460205078125 +1769682097,204320512,0.0,-0.0,595.0460205078125 +1769682097,242968832,0.0,-0.0,595.0460205078125 +1769682097,268383744,0.0,-0.0,595.0460205078125 +1769682097,352696576,0.0,-0.0,595.0460205078125 +1769682097,376715008,0.0,-0.0,595.0460205078125 +1769682097,403256832,0.0049320789985358715,0.002631816081702709,595.0457153320312 +1769682097,407344640,0.008216639049351215,0.0036606278736144304,595.0449829101562 +1769682097,445301248,0.020822471007704735,0.0057698399759829044,595.0416259765625 +1769682097,468347904,0.027033133432269096,0.006564016919583082,595.0399169921875 +1769682097,500918016,0.036981917917728424,0.0076746586710214615,595.0369873046875 +1769682097,550244864,0.0516270287334919,0.008916933089494705,595.0328369140625 +1769682097,568303872,0.062894307076931,0.009678525850176811,595.0294799804688 +1769682097,600920320,0.07452550530433655,0.010344527661800385,595.0262451171875 +1769682097,644671488,0.09059477597475052,0.010990619659423828,595.021728515625 +1769682097,669554432,0.1029520109295845,0.01132669672369957,595.0183715820312 +1769682097,701483776,0.11540769040584564,0.011550016701221466,595.0150756835938 +1769682097,754420480,0.13272912800312042,0.011684630066156387,595.010498046875 +1769682097,770087680,0.14578783512115479,0.011737365275621414,595.0070190429688 +1769682097,802273024,0.15920542180538177,0.01171024888753891,595.0036010742188 +1769682097,846266624,0.17718958854675293,0.011606939136981964,594.9989624023438 +1769682097,868522752,0.1909317672252655,0.011469483375549316,594.9954833984375 +1769682097,912895232,0.20489896833896637,0.011343549937009811,594.9920654296875 +1769682097,951317504,0.2244510054588318,0.011120446026325226,594.987548828125 +1769682097,970429184,0.24007059633731842,0.010999634861946106,594.9841918945312 +1769682098,1095936,0.2557103633880615,0.010856874287128448,594.9807739257812 +1769682098,62896128,0.27806758880615234,0.010717004537582397,594.9761352539062 +1769682098,70066432,0.2954789102077484,0.010609932243824005,594.9727172851562 +1769682098,102552064,0.3128618896007538,0.010485470294952393,594.9691772460938 +1769682098,144433664,0.3371620774269104,0.01036575436592102,594.9645385742188 +1769682098,168598528,0.356563001871109,0.010275378823280334,594.9610595703125 +1769682098,204949760,0.38289400935173035,0.010221593081951141,594.9562377929688 +1769682098,244752128,0.4032175540924072,0.010161414742469788,594.9525756835938 +1769682098,268771584,0.4246063530445099,0.010140478610992432,594.9488525390625 +1769682098,301198848,0.4466049373149872,0.010103955864906311,594.9449462890625 +1769682098,357329920,0.47627389430999756,0.010067105293273926,594.9395751953125 +1769682098,372897024,0.5058357119560242,0.010088860988616943,594.93408203125 +1769682098,401200384,0.5208737850189209,0.01007068157196045,594.9312133789062 +1769682098,446879744,0.5520234107971191,0.010115101933479309,594.9254150390625 +1769682098,472500224,0.5762444138526917,0.010112643241882324,594.9208374023438 +1769682098,502857728,0.6005131006240845,0.010153144598007202,594.916015625 +1769682098,546362112,0.6336164474487305,0.010229811072349548,594.9093627929688 +1769682098,568072704,0.658031165599823,0.010280370712280273,594.904052734375 +1769682098,604231168,0.6902313828468323,0.010375261306762695,594.8967895507812 +1769682098,651403008,0.7147569060325623,0.010434076189994812,594.8909912109375 +1769682098,668508416,0.7367784976959229,0.010482192039489746,594.8851318359375 +1769682098,702321664,0.7581244111061096,0.010566860437393188,594.8792724609375 +1769682098,748941056,0.7876003980636597,0.01067332923412323,594.871337890625 +1769682098,768552960,0.8112553954124451,0.010687261819839478,594.864990234375 +1769682098,801513216,0.8350254893302917,0.010577648878097534,594.8579711914062 +1769682098,850055680,0.8671908974647522,0.010465681552886963,594.8477172851562 +1769682098,882299648,0.8999540209770203,0.010342597961425781,594.8366088867188 +1769682098,902184704,0.9162105321884155,0.010274529457092285,594.830810546875 +1769682098,945991424,0.9493237137794495,0.0102195143699646,594.81884765625 +1769682098,968878336,0.9739096760749817,0.010106950998306274,594.8095703125 +1769682099,8193792,1.0059418678283691,0.010089516639709473,594.796875 +1769682099,49642752,1.0299853086471558,0.010055631399154663,594.7872314453125 +1769682099,68685568,1.0522366762161255,0.010035157203674316,594.7774658203125 +1769682099,101197056,1.0742249488830566,0.009999275207519531,594.7677001953125 +1769682099,157958400,1.1026889085769653,0.0100058913230896,594.7549438476562 +1769682099,170703104,1.1258100271224976,0.009961962699890137,594.745361328125 +1769682099,201378816,1.1490874290466309,0.00991135835647583,594.7356567382812 +1769682099,248626944,1.1809526681900024,0.009915471076965332,594.722412109375 +1769682099,269953024,1.2050083875656128,0.009861409664154053,594.71240234375 +1769682099,301219840,1.2291439771652222,0.009818673133850098,594.7024536132812 +1769682099,345339904,1.2618718147277832,0.009771913290023804,594.6890258789062 +1769682099,369197312,1.286189079284668,0.009670495986938477,594.6790161132812 +1769682099,404776192,1.3181917667388916,0.009601175785064697,594.6658935546875 +1769682099,450561024,1.3421523571014404,0.009501487016677856,594.65625 +1769682099,468618496,1.3667255640029907,0.009386062622070312,594.6467895507812 +1769682099,502465792,1.3912369012832642,0.009241193532943726,594.6375122070312 +1769682099,557707008,1.4240283966064453,0.009145617485046387,594.6253662109375 +1769682099,575600896,1.4568352699279785,0.009037405252456665,594.6135864257812 +1769682099,601224960,1.473239779472351,0.008910059928894043,594.607666015625 +1769682099,648866304,1.5062907934188843,0.008821874856948853,594.59619140625 +1769682099,671585280,1.5311124324798584,0.008687764406204224,594.5877075195312 +1769682099,702138112,1.5558031797409058,0.008557915687561035,594.5794067382812 +1769682099,745082368,1.5887391567230225,0.008415013551712036,594.5687866210938 +1769682099,768366336,1.6134248971939087,0.008197963237762451,594.5611572265625 +1769682099,805043200,1.6463834047317505,0.007985591888427734,594.5516357421875 +1769682099,848476416,1.6712499856948853,0.007754147052764893,594.545166015625 +1769682099,868908288,1.6957670450210571,0.007528066635131836,594.5391235351562 +1769682099,968993280,1.72834050655365,0.007221579551696777,594.5320434570312 +1769682099,983702528,1.760910987854004,0.006901562213897705,594.5260009765625 +1769682099,998075392,1.7771967649459839,0.006739258766174316,594.5233154296875 +1769682100,4782592,1.8089253902435303,0.006453573703765869,594.5186157226562 +1769682100,46955264,1.8414465188980103,0.006006836891174316,594.5153198242188 +1769682100,67509248,1.8578656911849976,0.005947530269622803,594.5147094726562 +1769682100,101534976,1.8826398849487305,0.0059476494789123535,594.5151977539062 +1769682100,150740736,1.9153931140899658,0.005934417247772217,594.5177001953125 +1769682100,169951488,1.9396491050720215,0.005942940711975098,594.52099609375 +1769682100,202056960,1.9637356996536255,0.0058997273445129395,594.5252075195312 +1769682100,244722944,1.9958676099777222,0.005802333354949951,594.5322875976562 +1769682100,272396032,2.0198512077331543,0.005736708641052246,594.53857421875 +1769682100,302440960,2.0437111854553223,0.005589962005615234,594.5455932617188 +1769682100,347283712,2.075336217880249,0.005287766456604004,594.5560913085938 +1769682100,368396544,2.0988540649414062,0.005075991153717041,594.5650024414062 +1769682100,404881408,2.1302671432495117,0.004683256149291992,594.5781860351562 +1769682100,444478720,2.153592824935913,0.004431188106536865,594.5889892578125 +1769682100,470222336,2.176737070083618,0.0041542649269104,594.600830078125 +1769682100,501590016,2.1998023986816406,0.0038924217224121094,594.6134033203125 +1769682100,563923200,2.2303106784820557,0.00347977876663208,594.6316528320312 +1769682100,572196608,2.252901792526245,0.0032376646995544434,594.646240234375 +1769682100,602554624,2.27506160736084,0.0028505921363830566,594.6615600585938 +1769682100,647092992,2.304507255554199,0.0018617510795593262,594.6826782226562 +1769682100,672747776,2.32635498046875,0.0011935234069824219,594.6990356445312 +1769682100,701491712,2.347964286804199,0.00048416852951049805,594.7161254882812 +1769682100,748240128,2.376702070236206,-0.0004622936248779297,594.7396850585938 +1769682100,769275648,2.398240327835083,-0.0009290575981140137,594.7582397460938 +1769682100,803454976,2.4264748096466064,-0.001671135425567627,594.7837524414062 +1769682100,844992768,2.447673797607422,-0.0020062923431396484,594.8035278320312 +1769682100,869718528,2.4688267707824707,-0.0023395419120788574,594.8240356445312 +1769682100,901328896,2.48984432220459,-0.0026891231536865234,594.84521484375 +1769682100,960475136,2.5174996852874756,-0.0032469630241394043,594.8748168945312 +1769682100,975734016,2.544877529144287,-0.0037483572959899902,594.9060668945312 +1769682101,4734464,2.565237283706665,-0.004038810729980469,594.9306030273438 +1769682101,44635392,2.585524797439575,-0.004262089729309082,594.9561767578125 +1769682101,75662848,2.6125617027282715,-0.00465768575668335,594.9915771484375 +1769682101,101708800,2.625924587249756,-0.004593789577484131,595.0099487304688 +1769682101,145141760,2.6521520614624023,-0.005278527736663818,595.04736328125 +1769682101,168491264,2.671685218811035,-0.0058730244636535645,595.0758666992188 +1769682101,204187904,2.697542190551758,-0.0069776177406311035,595.1144409179688 +1769682101,251167744,2.716792106628418,-0.0075577497482299805,595.1438598632812 +1769682101,269159168,2.7361905574798584,-0.008315622806549072,595.1737060546875 +1769682101,356330752,2.762026071548462,-0.008848905563354492,595.2141723632812 +1769682101,370320896,2.7878310680389404,-0.009052455425262451,595.255859375 +1769682101,392156160,2.806910276412964,-0.009187638759613037,595.287841796875 +1769682101,402064128,2.8195314407348633,-0.008955061435699463,595.3095703125 +1769682101,452373504,2.85107421875,-0.009431302547454834,595.3654174804688 +1769682101,467812864,2.8636579513549805,-0.009311914443969727,595.3883056640625 +1769682101,513837056,2.8824045658111572,-0.009296298027038574,595.4232788085938 +1769682101,552439808,2.907174825668335,-0.009701311588287354,595.4711303710938 +1769682101,569771776,2.925518035888672,-0.009654223918914795,595.5077514648438 +1769682101,601629440,2.943861961364746,-0.009675145149230957,595.5450439453125 +1769682101,662898944,2.9680848121643066,-0.010103702545166016,595.5955810546875 +1769682101,671115776,2.986194610595703,-0.010150790214538574,595.63427734375 +1769682101,702269440,3.0040605068206787,-0.010223567485809326,595.673583984375 +1769682101,748636672,3.028409957885742,-0.01075124740600586,595.7279052734375 +1769682101,768269056,3.04657244682312,-0.010348916053771973,595.770751953125 +1769682101,802727680,3.064631938934326,-0.00986337661743164,595.8150634765625 +1769682101,846295040,3.088637590408325,-0.009733736515045166,595.8759765625 +1769682101,869854720,3.106538772583008,-0.009295284748077393,595.922607421875 +1769682101,903175936,3.1301681995391846,-0.009233534336090088,595.98583984375 +1769682101,949105920,3.1478614807128906,-0.00889497995376587,596.0337524414062 +1769682101,970693120,3.165479898452759,-0.008623182773590088,596.0820922851562 +1769682102,1969152,3.182934284210205,-0.008436083793640137,596.1309204101562 +1769682102,63012864,3.206088066101074,-0.008794128894805908,596.1966552734375 +1769682102,71179520,3.223187208175659,-0.008657217025756836,596.2463989257812 +1769682102,103645696,3.2400565147399902,-0.00907433032989502,596.2962036132812 +1769682102,147812352,3.262444257736206,-0.010438680648803711,596.36279296875 +1769682102,168657920,3.2790069580078125,-0.011075258255004883,596.4130249023438 +1769682102,207585280,3.3010129928588867,-0.012391984462738037,596.4804077148438 +1769682102,249701120,3.3173511028289795,-0.012859225273132324,596.5313720703125 +1769682102,268774400,3.3335394859313965,-0.013227641582489014,596.5826416015625 +1769682102,302523904,3.349606513977051,-0.013454020023345947,596.63427734375 +1769682102,358572288,3.3708293437957764,-0.014299929141998291,596.7034301757812 +1769682102,372578816,3.3865318298339844,-0.01417684555053711,596.7556762695312 +1769682102,403827712,3.4073305130004883,-0.01503676176071167,596.8256225585938 +1769682102,444911104,3.4227380752563477,-0.01498568058013916,596.8783569335938 +1769682102,474463232,3.4382011890411377,-0.01460939645767212,596.9314575195312 +1769682102,501912320,3.4537460803985596,-0.01340484619140625,596.985595703125 +1769682102,555235840,3.4743356704711914,-0.011892199516296387,597.0592651367188 +1769682102,568701184,3.4896841049194336,-0.010506749153137207,597.1152954101562 +1769682102,602677504,3.5050320625305176,-0.00860607624053955,597.1715087890625 +1769682102,649789952,3.5251667499542236,-0.006827116012573242,597.246337890625 +1769682102,671535616,3.5400679111480713,-0.0050743818283081055,597.3024291992188 +1769682102,701983744,3.5547354221343994,-0.0038105249404907227,597.3587036132812 +1769682102,750961920,3.574009895324707,-0.0031620264053344727,597.4343872070312 +1769682102,768453888,3.5883195400238037,-0.002487659454345703,597.491943359375 +1769682102,801749504,3.6023240089416504,-0.001974344253540039,597.5504150390625 +1769682102,846136576,3.620668411254883,-0.002278566360473633,597.6298828125 +1769682102,874187008,3.638786554336548,-0.0024547576904296875,597.7106323242188 +1769682102,902550528,3.647622585296631,-0.001816391944885254,597.7514038085938 +1769682102,945885952,3.6645514965057373,-0.002247333526611328,597.8329467773438 +1769682102,968980992,3.676791191101074,-0.003084897994995117,597.8923950195312 +1769682103,3712256,3.6927483081817627,-0.0055915117263793945,597.9691772460938 +1769682103,47422720,3.704408645629883,-0.00689244270324707,598.0255126953125 +1769682103,69015552,3.715794563293457,-0.007888197898864746,598.0810546875 +1769682103,102829568,3.727091073989868,-0.008797287940979004,598.1356201171875 +1769682103,147860736,3.74176025390625,-0.010411500930786133,598.2071533203125 +1769682103,168784128,3.7525274753570557,-0.010937929153442383,598.2600708007812 +1769682103,201679104,3.762913703918457,-0.011388301849365234,598.3129272460938 +1769682103,244682240,3.7768795490264893,-0.012661337852478027,598.3843994140625 +1769682103,272453888,3.7875585556030273,-0.01182699203491211,598.44091796875 +1769682103,303179008,3.798072099685669,-0.01092541217803955,598.5006713867188 +1769682103,345483008,3.8116745948791504,-0.010236620903015137,598.5852661132812 +1769682103,369423616,3.8216543197631836,-0.0089263916015625,598.6517944335938 +1769682103,403687936,3.834772825241089,-0.008031845092773438,598.7428588867188 +1769682103,447930368,3.844386100769043,-0.0067147016525268555,598.8118286132812 +1769682103,469390848,3.853752374649048,-0.005372166633605957,598.8804931640625 +1769682103,502110464,3.862870931625366,-0.004178762435913086,598.9484252929688 +1769682103,550083072,3.874800682067871,-0.00371551513671875,599.0375366210938 +1769682103,569511424,3.8834915161132812,-0.0029453039169311523,599.103271484375 +1769682103,601851904,3.892157554626465,-0.002371668815612793,599.1685180664062 +1769682103,645400576,3.9033663272857666,-0.0026110410690307617,599.2550659179688 +1769682103,672011264,3.9108662605285645,-0.001653909683227539,599.3199462890625 +1769682103,702832128,3.917973041534424,-0.0021867752075195312,599.3853149414062 +1769682103,749979904,3.927135467529297,-0.0042684078216552734,599.472412109375 +1769682103,768527360,3.933896064758301,-0.005161762237548828,599.5376586914062 +1769682103,815198720,3.9404170513153076,-0.005935311317443848,599.6026611328125 +1769682103,852962560,3.9511256217956543,-0.008099079132080078,599.7105102539062 +1769682103,868480512,3.9553067684173584,-0.007988452911376953,599.7532958984375 +1769682103,901628928,3.961439609527588,-0.008165240287780762,599.8169555664062 +1769682103,958757632,3.9694294929504395,-0.009033560752868652,599.900634765625 +1769682103,966950144,3.975208044052124,-0.009063959121704102,599.9623413085938 +1769682104,5162240,3.980961799621582,-0.008535504341125488,600.023193359375 +1769682104,46654464,3.9883315563201904,-0.009008049964904785,600.10302734375 +1769682104,69804544,3.9937896728515625,-0.008572578430175781,600.162353515625 +1769682104,102163712,3.999180555343628,-0.00833439826965332,600.2213134765625 +1769682104,147991808,4.006170272827148,-0.008785843849182129,600.2999267578125 +1769682104,168426752,4.011309623718262,-0.008516073226928711,600.3591918945312 +1769682104,216006400,4.016340732574463,-0.008229732513427734,600.4188232421875 +1769682104,249928448,4.022889137268066,-0.008677005767822266,600.4989624023438 +1769682104,270161408,4.027659893035889,-0.008242487907409668,600.5592041015625 +1769682104,301925120,4.032520294189453,-0.007786273956298828,600.6193237304688 +1769682104,360555776,4.038869857788086,-0.0080183744430542,600.6989135742188 +1769682104,376667904,4.0449652671813965,-0.008032560348510742,600.7777709960938 +1769682104,404307712,4.04794454574585,-0.007176756858825684,600.8169555664062 +1769682104,448367616,4.053806781768799,-0.007527709007263184,600.8950805664062 +1769682104,481032960,4.058073043823242,-0.007168769836425781,600.9535522460938 +1769682104,502182656,4.062269687652588,-0.006783962249755859,601.0117797851562 +1769682104,544851968,4.067636966705322,-0.00716555118560791,601.0889892578125 +1769682104,569247488,4.071478843688965,-0.006773471832275391,601.1466064453125 +1769682104,613851392,4.075328826904297,-0.006405234336853027,601.2037963867188 +1769682104,651973888,4.080390930175781,-0.0067996978759765625,601.279541015625 +1769682104,673050112,4.084068775177002,-0.0063419342041015625,601.3363037109375 +1769682104,702175232,4.08763313293457,-0.006184935569763184,601.3929443359375 +1769682104,759228416,4.092249870300293,-0.006553292274475098,601.4685668945312 +1769682104,769324288,4.0955810546875,-0.006520986557006836,601.525390625 +1769682104,804167424,4.09880256652832,-0.006063342094421387,601.5822143554688 +1769682104,847000064,4.102931976318359,-0.006557106971740723,601.65771484375 +1769682104,870349056,4.105965614318848,-0.006254792213439941,601.7144775390625 +1769682104,902342912,4.10892915725708,-0.006096601486206055,601.7713012695312 +1769682104,946942464,4.112699508666992,-0.006624102592468262,601.8471069335938 +1769682104,969561344,4.115443229675293,-0.006347537040710449,601.9041137695312 +1769682105,12832000,4.118062973022461,-0.00614321231842041,601.9611206054688 +1769682105,52893440,4.121480464935303,-0.006625056266784668,602.0369262695312 +1769682105,70082560,4.12391996383667,-0.006360888481140137,602.0935668945312 +1769682105,105355776,4.127076148986816,-0.006891965866088867,602.1690063476562 +1769682105,160634112,4.129350185394287,-0.006752371788024902,602.2255249023438 +1769682105,169379584,4.131510257720947,-0.006752371788024902,602.2822875976562 +1769682105,203916544,4.133586406707764,-0.006486415863037109,602.3396606445312 +1769682105,248472320,4.136188507080078,-0.007196903228759766,602.416748046875 +1769682105,269719552,4.138103485107422,-0.0070111751556396484,602.4750366210938 +1769682105,303150336,4.140020847320557,-0.006777048110961914,602.53369140625 +1769682105,348079360,4.142515182495117,-0.0073157548904418945,602.6119995117188 +1769682105,368669952,4.144261360168457,-0.007027029991149902,602.6708984375 +1769682105,412418816,4.145978927612305,-0.0067490339279174805,602.7297973632812 +1769682105,448598784,4.148170471191406,-0.0072672367095947266,602.8085327148438 +1769682105,470086144,4.149669647216797,-0.0069353580474853516,602.8676147460938 +1769682105,502299904,4.151121616363525,-0.0065767765045166016,602.9265747070312 +1769682105,560584704,4.152917385101318,-0.0069460272789001465,603.0046997070312 +1769682105,566907136,4.154232501983643,-0.006782174110412598,603.0628662109375 +1769682105,602236160,4.155481815338135,-0.006157040596008301,603.1205444335938 +1769682105,645720832,4.157147407531738,-0.00638502836227417,603.196533203125 +1769682105,669733888,4.158300876617432,-0.006119906902313232,603.2530517578125 +1769682105,704808192,4.1594061851501465,-0.005563199520111084,603.3090209960938 +1769682105,746145280,4.1608171463012695,-0.005885183811187744,603.3832397460938 +1769682105,769086720,4.161767482757568,-0.005500733852386475,603.4384765625 +1769682105,802238464,4.162679672241211,-0.005125939846038818,603.493408203125 +1769682105,848857600,4.1637864112854,-0.0054852962493896484,603.5663452148438 +1769682105,868945920,4.164580821990967,-0.005120038986206055,603.6206665039062 +1769682105,914379264,4.16533899307251,-0.0047553181648254395,603.6746826171875 +1769682105,946623744,4.166254043579102,-0.005093216896057129,603.7459716796875 +1769682105,971231232,4.1668925285339355,-0.004739582538604736,603.7989501953125 +1769682106,2177280,4.167471408843994,-0.0044155120849609375,603.8516235351562 +1769682106,59700736,4.1681318283081055,-0.004772663116455078,603.9212036132812 +1769682106,68552192,4.168501853942871,-0.004694938659667969,603.9730834960938 +1769682106,104032768,4.168850421905518,-0.004236817359924316,604.0247192382812 +1769682106,149748480,4.169210433959961,-0.004743516445159912,604.0934448242188 +1769682106,169342464,4.169436931610107,-0.004545331001281738,604.1449584960938 +1769682106,202404096,4.169583797454834,-0.004337608814239502,604.1966552734375 +1769682106,244774144,4.169707775115967,-0.004899859428405762,604.2657470703125 +1769682106,270096640,4.169785499572754,-0.004686832427978516,604.3177490234375 +1769682106,311314432,4.1698689460754395,-0.004431247711181641,604.3697509765625 +1769682106,347475968,4.169906139373779,-0.004825711250305176,604.4391479492188 +1769682106,369283328,4.169814109802246,-0.004512190818786621,604.4910888671875 +1769682106,402232320,4.169704914093018,-0.004176735877990723,604.5428466796875 +1769682106,448170496,4.169504642486572,-0.004535198211669922,604.6115112304688 +1769682106,468888064,4.169397354125977,-0.004226028919219971,604.6627807617188 +1769682106,502027008,4.169130802154541,-0.003908216953277588,604.7137451171875 +1769682106,549248000,4.168745994567871,-0.004254698753356934,604.781494140625 +1769682106,572547840,4.168410301208496,-0.003740847110748291,604.8319091796875 +1769682106,603419392,4.168686389923096,-0.0032554268836975098,604.8822021484375 +1769682106,644678912,4.169469356536865,-0.00045734643936157227,604.951171875 +1769682106,669359616,4.170021057128906,0.0026813149452209473,605.0043334960938 +1769682106,703251200,4.170641899108887,0.005787074565887451,605.0763549804688 +1769682106,748047104,4.171043395996094,0.00838172435760498,605.130859375 +1769682106,769116160,4.171450614929199,0.010606944561004639,605.1859741210938 +1769682106,802766848,4.171756744384766,0.012452661991119385,605.2415161132812 +1769682106,850893056,4.172121524810791,0.013475120067596436,605.3165283203125 +1769682106,868869632,4.1722822189331055,0.014549314975738525,605.3734741210938 +1769682106,903162624,4.172410488128662,0.01539069414138794,605.4307250976562 +1769682106,945928448,4.172492504119873,0.01531982421875,605.5075073242188 +1769682111,449065984,0.0,-0.0,609.9276123046875 +1769682111,469393920,0.0,-0.0,609.9276123046875 +1769682111,507856640,0.0,-0.0,609.9276123046875 +1769682111,550883328,0.0,-0.0,609.9276123046875 +1769682111,569635584,0.0,-0.0,609.9276123046875 +1769682111,602757888,0.0,-0.0,609.9276123046875 +1769682111,653416448,0.0,-0.0,609.9276123046875 +1769682111,674659840,0.0,-0.0,609.9276123046875 +1769682111,707428352,0.0,-0.0,609.9276123046875 +1769682111,749065728,0.0,-0.0,609.9276123046875 +1769682111,779393024,0.0,-0.0,609.9276123046875 +1769682111,803398400,0.0,-0.0,609.9276123046875 +1769682111,850230272,0.0,-0.0,609.9276123046875 +1769682111,869469184,0.0,-0.0,609.9276123046875 +1769682111,904924160,0.0,-0.0,609.9276123046875 +1769682111,945897728,0.0,-0.0,609.9276123046875 +1769682111,969608192,0.0,-0.0,609.9276123046875 +1769682112,2809088,0.0,-0.0,609.9276123046875 +1769682112,53695232,0.0,-0.0,609.9276123046875 +1769682112,68948224,0.0,-0.0,609.9276123046875 +1769682112,102731776,0.0,-0.0,609.9276123046875 +1769682112,148591360,0.0,-0.0,609.9276123046875 +1769682112,173492736,0.0,-0.0,609.9276123046875 +1769682112,203752960,0.0,-0.0,609.9276123046875 +1769682112,248101888,0.0,-0.0,609.9276123046875 +1769682112,269510656,0.0,-0.0,609.9276123046875 +1769682112,305878528,0.0,-0.0,609.9276123046875 +1769682112,352089856,0.0,-0.0,609.9276123046875 +1769682112,371784960,0.0,-0.0,609.9276123046875 +1769682112,404763392,0.0,-0.0,609.9276123046875 +1769682112,447222272,0.0,-0.0,609.9276123046875 +1769682112,472760064,0.0,-0.0,609.9276123046875 +1769682112,504577792,0.0,-0.0,609.9276123046875 +1769682112,562524928,0.0,-0.0,609.9276123046875 +1769682112,570624000,0.021425053477287292,0.0048261526972055435,609.92529296875 +1769682112,603703040,0.05003639683127403,0.00824767630547285,609.9141845703125 +1769682112,646364160,0.07148133218288422,0.010499061085283756,609.903076171875 +1769682112,669923840,0.09293576329946518,0.012607511132955551,609.8916625976562 +1769682112,706390528,0.12158535420894623,0.015178972855210304,609.8779907226562 +1769682112,747114752,0.14326530694961548,0.016852721571922302,609.8693237304688 +1769682112,769897984,0.1648426353931427,0.018287185579538345,609.862060546875 +1769682112,803926272,0.19422240555286407,0.019790515303611755,609.854248046875 +1769682112,863863296,0.21630825102329254,0.020627260208129883,609.8494262695312 +1769682112,870029312,0.2392732948064804,0.021214686334133148,609.8450927734375 +1769682112,904009216,0.27075839042663574,0.021630726754665375,609.8397827148438 +1769682112,949665024,0.29531702399253845,0.021677739918231964,609.8360595703125 +1769682112,980986112,0.33025839924812317,0.02148391306400299,609.8311767578125 +1769682113,5756928,0.3561897575855255,0.021173037588596344,609.8279418945312 +1769682113,47343616,0.3832135498523712,0.02073352038860321,609.8251342773438 +1769682113,70828288,0.4108126163482666,0.020229697227478027,609.8228759765625 +1769682113,103871232,0.44889259338378906,0.019443854689598083,609.8212890625 +1769682113,152328960,0.47944578528404236,0.018803566694259644,609.8212280273438 +1769682113,170334208,0.5105106830596924,0.018095962703227997,609.8223266601562 +1769682113,203311616,0.5522214770317078,0.0171356201171875,609.825927734375 +1769682113,247476992,0.5839729309082031,0.01642581820487976,609.8304443359375 +1769682113,270371584,0.6169818639755249,0.01569991558790207,609.8364868164062 +1769682113,304508672,0.6619585752487183,0.014707103371620178,609.8472290039062 +1769682113,348187136,0.6960873007774353,0.014016866683959961,609.8572387695312 +1769682113,372208384,0.7297147512435913,0.013333573937416077,609.8690795898438 +1769682113,404450048,0.7748191356658936,0.012435615062713623,609.8876342773438 +1769682113,450283776,0.8091893196105957,0.011827558279037476,609.9034423828125 +1769682113,487960064,0.8535206317901611,0.011037439107894897,609.927001953125 +1769682113,513764096,0.8840944766998291,0.010555177927017212,609.9464721679688 +1769682113,546820608,0.9231767058372498,0.009989261627197266,609.9747314453125 +1769682113,569763840,0.9419249296188354,0.009804919362068176,609.9896850585938 +1769682113,604323328,0.9775552153587341,0.009323596954345703,610.0211181640625 +1769682113,651694080,1.002842903137207,0.009065717458724976,610.0459594726562 +1769682113,671136768,1.0319310426712036,0.008803680539131165,610.071533203125 +1769682113,703904512,1.072313904762268,0.008375152945518494,610.106201171875 +1769682113,752578048,1.1025687456130981,0.0080748051404953,610.1322021484375 +1769682113,776719872,1.1429942846298218,0.007401004433631897,610.1676025390625 +1769682113,803174656,1.1733438968658447,0.006872877478599548,610.1951904296875 +1769682113,851142144,1.20396888256073,0.006389141082763672,610.2241821289062 +1769682113,870157824,1.2349035739898682,0.0059130191802978516,610.2544555664062 +1769682113,905911296,1.275935411453247,0.005257055163383484,610.2967529296875 +1769682113,952868864,1.3068403005599976,0.004999563097953796,610.3297119140625 +1769682113,971589888,1.3378669023513794,0.004851087927818298,610.3634033203125 +1769682114,3428096,1.3792940378189087,0.004641667008399963,610.4085083007812 +1769682114,50317056,1.410713791847229,0.004727691411972046,610.4423217773438 +1769682114,71926016,1.4420069456100464,0.004998624324798584,610.4755249023438 +1769682114,103549952,1.4836273193359375,0.005227208137512207,610.5184936523438 +1769682114,146616576,1.5147194862365723,0.005729883909225464,610.5494995117188 +1769682114,174196480,1.5559993982315063,0.006268620491027832,610.5892333984375 +1769682114,205190400,1.5870829820632935,0.006675034761428833,610.61767578125 +1769682114,246671616,1.618085503578186,0.007137179374694824,610.6449584960938 +1769682114,282744320,1.6486736536026,0.0076257288455963135,610.6709594726562 +1769682114,303340544,1.6890077590942383,0.008074909448623657,610.7037353515625 +1769682114,346945792,1.7192975282669067,0.00854039192199707,610.72705078125 +1769682114,370027008,1.7496012449264526,0.008965551853179932,610.749267578125 +1769682114,403770624,1.7896137237548828,0.009403526782989502,610.7772827148438 +1769682114,446867456,1.8195483684539795,0.00983467698097229,610.797119140625 +1769682114,470970880,1.8493553400039673,0.010199248790740967,610.8160400390625 +1769682114,503507456,1.8887420892715454,0.010419219732284546,610.8399658203125 +1769682114,571137024,1.9181939363479614,0.010602682828903198,610.8572998046875 +1769682114,580840704,1.9571043252944946,0.010637789964675903,610.8802490234375 +1769682114,604333568,1.9860235452651978,0.01065528392791748,610.8973999023438 +1769682114,648685312,2.014747142791748,0.010728508234024048,610.9146118164062 +1769682114,670760960,2.0437021255493164,0.01084926724433899,610.931640625 +1769682114,708379392,2.0820467472076416,0.01095321774482727,610.9537963867188 +1769682114,752989952,2.110621452331543,0.011254489421844482,610.969482421875 +1769682114,771250688,2.138838291168213,0.01162499189376831,610.9841918945312 +1769682114,804359168,2.176272392272949,0.011926740407943726,611.0018310546875 +1769682114,847866880,2.2042598724365234,0.012405365705490112,611.0140380859375 +1769682114,871052288,2.2323474884033203,0.013044595718383789,611.0256958007812 +1769682114,905084416,2.269252300262451,0.01386973261833191,611.0399169921875 +1769682114,947174912,2.2967350482940674,0.014554470777511597,611.0494384765625 +1769682114,977465856,2.3331258296966553,0.01529201865196228,611.0606689453125 +1769682115,3199488,2.360161542892456,0.01576453447341919,611.068115234375 +1769682115,46818048,2.3870184421539307,0.01613214612007141,611.074951171875 +1769682115,70818816,2.4136345386505127,0.01638185977935791,611.0814819335938 +1769682115,104999680,2.4489293098449707,0.016558945178985596,611.090087890625 +1769682115,145208576,2.4751131534576416,0.016699641942977905,611.0965576171875 +1769682115,172675072,2.501270294189453,0.016835898160934448,611.1029663085938 +1769682115,204979968,2.5357236862182617,0.0169600248336792,611.111083984375 +1769682115,252291328,2.570006847381592,0.016846299171447754,611.1181030273438 +1769682115,269665792,2.586911916732788,0.016703754663467407,611.1207885742188 +1769682115,304941056,2.620558500289917,0.016286522150039673,611.124267578125 +1769682115,363435008,2.6456005573272705,0.01603102684020996,611.1253662109375 +1769682115,371908608,2.6703786849975586,0.015817254781723022,611.1256103515625 +1769682115,404556544,2.703157901763916,0.015582293272018433,611.1243896484375 +1769682115,448133120,2.7275216579437256,0.015441209077835083,611.12255859375 +1769682115,470009856,2.7517783641815186,0.015311896800994873,611.1202392578125 +1769682115,504098304,2.7837438583374023,0.01525142788887024,611.1165161132812 +1769682115,549628160,2.807427406311035,0.015218198299407959,611.1133422851562 +1769682115,572309504,2.830930233001709,0.015243947505950928,611.1098022460938 +1769682115,605186560,2.861807346343994,0.015413731336593628,611.1045532226562 +1769682115,653767424,2.8921937942504883,0.015568375587463379,611.0985107421875 +1769682115,670268160,2.9072792530059814,0.015598893165588379,611.09521484375 +1769682115,704889600,2.9368503093719482,0.015748411417007446,611.0882568359375 +1769682115,762705152,2.9588725566864014,0.015895307064056396,611.0827026367188 +1769682115,771343104,2.980652332305908,0.016026794910430908,611.0769653320312 +1769682115,803847424,3.0091938972473145,0.01626753807067871,611.0691528320312 +1769682115,846062080,3.030308961868286,0.01633542776107788,611.063232421875 +1769682115,870034944,3.051267147064209,0.016368210315704346,611.0573120117188 +1769682115,903709952,3.079167366027832,0.0164528489112854,611.0493774414062 +1769682115,947576320,3.099843740463257,0.016754746437072754,611.0433959960938 +1769682115,969684480,3.1204490661621094,0.017122089862823486,611.037353515625 +1769682116,6615552,3.147494316101074,0.017660140991210938,611.0289916992188 +1769682116,48478208,3.1675097942352295,0.01798689365386963,611.0223388671875 +1769682116,70466560,3.1872432231903076,0.018299520015716553,611.0151977539062 +1769682116,105127424,3.213179588317871,0.018727540969848633,611.0050659179688 +1769682116,149552384,3.2325055599212646,0.01889413595199585,610.9970703125 +1769682116,171353344,3.2515716552734375,0.01900261640548706,610.9888305664062 +1769682116,204036608,3.276580333709717,0.019138336181640625,610.977783203125 +1769682116,249876736,3.2951440811157227,0.019091546535491943,610.9696044921875 +1769682116,276459264,3.319565534591675,0.01908111572265625,610.9590454101562 +1769682116,303916800,3.3376686573028564,0.018984317779541016,610.9512939453125 +1769682116,348371712,3.355445623397827,0.018862009048461914,610.9434814453125 +1769682116,370183936,3.373098611831665,0.018731892108917236,610.9357299804688 +1769682116,404537600,3.3961856365203857,0.018688499927520752,610.9253540039062 +1769682116,452494080,3.413384199142456,0.018572628498077393,610.91748046875 +1769682116,471294208,3.430208921432495,0.01846003532409668,610.9096069335938 +1769682116,503266816,3.452479600906372,0.018388330936431885,610.8992309570312 +1769682116,552809984,3.46885085105896,0.0182497501373291,610.8916625976562 +1769682116,572253952,3.4845683574676514,0.018041372299194336,610.88427734375 +1769682116,604905728,3.5053296089172363,0.01805579662322998,610.874755859375 +1769682116,646738688,3.5206573009490967,0.017988383769989014,610.867919921875 +1769682116,676145152,3.540928840637207,0.01801055669784546,610.8589477539062 +1769682116,705147904,3.5558269023895264,0.018005311489105225,610.852294921875 +1769682116,753984256,3.5704712867736816,0.017956018447875977,610.8457641601562 +1769682116,770739200,3.5849173069000244,0.01789158582687378,610.8392333984375 +1769682116,803742976,3.6039865016937256,0.017901837825775146,610.8309326171875 +1769682116,849053440,3.618004560470581,0.017851948738098145,610.8248901367188 +1769682116,871011328,3.6317298412323,0.01779782772064209,610.819091796875 +1769682116,903371008,3.649094343185425,0.01760256290435791,610.8116455078125 +1769682116,950181120,3.661691904067993,0.017311573028564453,610.806396484375 +1769682116,975261184,3.674178123474121,0.016985714435577393,610.8011474609375 +1769682117,3959808,3.6904706954956055,0.016624271869659424,610.7941284179688 +1769682117,48541440,3.7025270462036133,0.016287505626678467,610.7888793945312 +1769682117,70566656,3.7144668102264404,0.015987694263458252,610.7838745117188 +1769682117,105230592,3.7300198078155518,0.015566825866699219,610.7774047851562 +1769682117,147080448,3.741469621658325,0.015249073505401611,610.772705078125 +1769682117,173295360,3.7566590309143066,0.0149727463722229,610.7667236328125 +1769682117,204511232,3.767854928970337,0.014792859554290771,610.762451171875 +1769682117,252366080,3.778834104537964,0.014644980430603027,610.7581176757812 +1769682117,270141696,3.789649486541748,0.014568746089935303,610.7539672851562 +1769682117,304258816,3.8037729263305664,0.014567852020263672,610.7483520507812 +1769682117,347211008,3.817661762237549,0.01454848051071167,610.7427368164062 +1769682117,370066432,3.8245179653167725,0.014504432678222656,610.7399291992188 +1769682117,405319680,3.838287591934204,0.014627635478973389,610.734619140625 +1769682117,459938048,3.8484315872192383,0.014876246452331543,610.731201171875 +1769682117,470240256,3.8583383560180664,0.01517486572265625,610.7282104492188 +1769682117,503837184,3.871425151824951,0.015571296215057373,610.724609375 +1769682117,545793792,3.8810415267944336,0.015825390815734863,610.721923828125 +1769682117,584605952,3.890632390975952,0.016046762466430664,610.7194213867188 +1769682117,604612096,3.903174638748169,0.016358673572540283,610.7159423828125 +1769682117,652919808,3.9117305278778076,0.016417503356933594,610.7131958007812 +1769682117,672007680,3.919809103012085,0.016254961490631104,610.7102661132812 +1769682117,703436032,3.9304418563842773,0.015915751457214355,610.7061157226562 +1769682117,753771264,3.9382615089416504,0.01557457447052002,610.702880859375 +1769682117,770730496,3.9458906650543213,0.015239357948303223,610.69970703125 +1769682117,804495104,3.9560985565185547,0.014868617057800293,610.6953125 +1769682117,866350592,3.9635653495788574,0.01458972692489624,610.6919555664062 +1769682117,877377792,3.9733948707580566,0.014292895793914795,610.6875 +1769682117,905881344,3.9805095195770264,0.014127671718597412,610.68408203125 +1769682117,950708480,3.9883763790130615,0.014010965824127197,610.6806640625 +1769682117,973591296,3.999324083328247,0.013902425765991211,610.6765747070312 +1769682118,8182784,4.007424831390381,0.013837158679962158,610.6739501953125 +1769682118,50194688,4.015482425689697,0.013789713382720947,610.6714477539062 +1769682118,74782208,4.023419380187988,0.01377558708190918,610.6691284179688 +1769682118,103597056,4.03406286239624,0.013797104358673096,610.6661987304688 +1769682118,168907264,4.04187536239624,0.013959348201751709,610.6641845703125 +1769682118,177031680,4.051950454711914,0.014303624629974365,610.6616821289062 +1769682118,203411456,4.05948543548584,0.014501512050628662,610.6600341796875 +1769682118,246632448,4.0669755935668945,0.014685451984405518,610.6585083007812 +1769682118,273766656,4.074259281158447,0.014818012714385986,610.6572265625 +1769682118,306194688,4.083858013153076,0.015019416809082031,610.6557006835938 +1769682118,347968512,4.09087610244751,0.01511847972869873,610.6547241210938 +1769682118,370217984,4.0977373123168945,0.015160977840423584,610.6536865234375 +1769682118,405861120,4.106701850891113,0.015238046646118164,610.6522216796875 +1769682118,448521728,4.113256931304932,0.015259802341461182,610.6513061523438 +1769682118,471012352,4.119734287261963,0.015245974063873291,610.6502685546875 +1769682118,503945216,4.128117084503174,0.01525568962097168,610.6488647460938 +1769682118,552830976,4.134304046630859,0.01522129774093628,610.6478271484375 +1769682118,570908928,4.140346527099609,0.01517939567565918,610.6467895507812 +1769682118,603938304,4.148255825042725,0.015170753002166748,610.6455078125 +1769682118,639926784,4.155272960662842,0.01514136791229248,610.64453125 +1769682118,671971584,4.1605987548828125,0.015068233013153076,610.6434326171875 +1769682118,704856320,4.166319370269775,0.015014410018920898,610.6420288085938 +1769682118,749539840,4.16876745223999,0.01499241590499878,610.6410522460938 +1769682118,781201152,4.174831390380859,0.01500612497329712,610.6401977539062 +1769682118,804487424,4.183836460113525,0.01504373550415039,610.6386108398438 +1769682118,850705408,4.190345287322998,0.015064001083374023,610.6373901367188 +1769682118,870364672,4.196753025054932,0.015098810195922852,610.6359252929688 +1769682118,904421120,4.205183982849121,0.015210509300231934,610.6339721679688 +1769682118,954224640,4.213500499725342,0.015298724174499512,610.6320190429688 +1769682118,970219520,4.217624187469482,0.015323519706726074,610.6309814453125 +1769682119,5037312,4.225666522979736,0.01538914442062378,610.628662109375 +1769682119,62780416,4.231413841247559,0.015418648719787598,610.6268310546875 +1769682119,70699008,4.235772609710693,0.015434026718139648,610.6249389648438 +1769682119,104476672,4.238792419433594,0.015448510646820068,610.6227416992188 +1769682119,148323072,4.242648601531982,0.015443801879882812,610.6212768554688 +1769682119,170119680,4.247612476348877,0.01533198356628418,610.619873046875 +1769682119,203844608,4.253958702087402,0.015174150466918945,610.618408203125 +1769682119,249590784,4.258516311645508,0.015031158924102783,610.6177978515625 +1769682119,270140416,4.262829303741455,0.01496046781539917,610.6176147460938 +1769682119,306027264,4.268542766571045,0.014906108379364014,610.61767578125 +1769682119,354000640,4.272590637207031,0.014915525913238525,610.6177978515625 +1769682119,372575232,4.276436805725098,0.014921247959136963,610.6179809570312 +1769682119,404311552,4.281325340270996,0.014949262142181396,610.6179809570312 +1769682119,454426368,4.2848734855651855,0.01498103141784668,610.6177978515625 +1769682119,471689728,4.288064479827881,0.01499718427658081,610.6176147460938 +1769682119,506781184,4.292318344116211,0.015002191066741943,610.6171875 +1769682119,547053056,4.295262813568115,0.014971733093261719,610.6170654296875 +1769682119,575538688,4.299244403839111,0.014943599700927734,610.6170654296875 +1769682119,603784192,4.302140235900879,0.01488727331161499,610.6172485351562 +1769682119,648208384,4.304839134216309,0.014848530292510986,610.61767578125 +1769682119,670841344,4.307455539703369,0.014786243438720703,610.6183471679688 +1769682119,705368064,4.310708999633789,0.014740526676177979,610.6195678710938 +1769682119,753122560,4.3130412101745605,0.014738082885742188,610.62060546875 +1769682119,772725760,4.31521463394165,0.01435542106628418,610.6220703125 +1769682119,805215488,4.318002223968506,0.014263331890106201,610.6255493164062 +1769682119,851597312,4.320021152496338,0.014011204242706299,610.6290893554688 +1769682119,872386816,4.321968078613281,0.013895034790039062,610.6336059570312 +1769682119,903763456,4.324450492858887,0.013662219047546387,610.6409301757812 +1769682119,953793280,4.326163291931152,0.01360940933227539,610.64697265625 +1769682119,972156672,4.3278021812438965,0.013538718223571777,610.6535034179688 +1769682120,3976192,4.329811096191406,0.013401389122009277,610.662353515625 +1769682120,47217664,4.331236362457275,0.01340174674987793,610.6690673828125 +1769682120,72975616,4.332493305206299,0.013434231281280518,610.6759033203125 +1769682120,105982464,4.334102630615234,0.013376414775848389,610.684814453125 +1769682120,153630976,4.335206508636475,0.013463914394378662,610.6912841796875 +1769682120,171102976,4.3361616134643555,0.01354140043258667,610.6976928710938 +1769682120,204411136,4.337342739105225,0.013540565967559814,610.705810546875 +1769682120,251578112,4.3381195068359375,0.013610482215881348,610.7118530273438 +1769682120,270716160,4.338845729827881,0.013698697090148926,610.7175903320312 +1769682120,303745536,4.339682579040527,0.013710081577301025,610.7249755859375 +1769682120,358140672,4.3402485847473145,0.013814985752105713,610.7304077148438 +1769682120,372923392,4.340709686279297,0.013890743255615234,610.7356567382812 +1769682120,404453632,4.341263294219971,0.013913154602050781,610.7423706054688 +1769682120,461247744,4.341594696044922,0.014001309871673584,610.747314453125 +1769682120,468995072,4.341836452484131,0.014090240001678467,610.7520751953125 +1769682120,505381888,4.342436790466309,0.014213919639587402,610.7579345703125 +1769682120,550785024,4.342798709869385,0.01434934139251709,610.7620239257812 +1769682120,570604800,4.343120098114014,0.01446157693862915,610.7656860351562 +1769682120,604522752,4.343482971191406,0.0145987868309021,610.77001953125 +1769682120,648904704,4.3437066078186035,0.014444589614868164,610.7726440429688 +1769682120,671539456,4.343870162963867,0.014457345008850098,610.7742309570312 +1769682120,703890176,4.344062328338623,0.013889968395233154,610.7741088867188 +1769682120,749053952,4.344171524047852,0.013462662696838379,610.7713012695312 +1769682120,770960896,4.344351291656494,0.013249337673187256,610.7691040039062 +1769682120,804228864,4.344688892364502,0.01291424036026001,610.7638549804688 +1769682120,861405696,4.344878196716309,0.012607574462890625,610.7592163085938 +1769682120,870776320,4.345042705535889,0.012361645698547363,610.754150390625 +1769682120,906231040,4.345209121704102,0.012148261070251465,610.7469482421875 +1769682120,950103808,4.3452887535095215,0.011958479881286621,610.7412719726562 +1769682120,970468096,4.345302581787109,0.01180875301361084,610.7354736328125 +1769682121,4215296,4.3452982902526855,0.011787116527557373,610.727783203125 +1769682121,54019328,4.345245838165283,0.01167452335357666,610.7220458984375 +1769682121,70310912,4.345151424407959,0.011622369289398193,610.71630859375 +1769682121,105227520,4.345003128051758,0.011708498001098633,610.7086791992188 +1769682121,152615680,4.344829559326172,0.011699974536895752,610.7029418945312 +1769682121,171852032,4.344645977020264,0.011717140674591064,610.6972045898438 +1769682121,204395008,4.344372272491455,0.011841773986816406,610.6893310546875 +1769682121,262870784,4.344089031219482,0.011819005012512207,610.6834106445312 +1769682121,271092480,4.343781471252441,0.011871516704559326,610.6774291992188 +1769682121,306442496,4.343352317810059,0.01196831464767456,610.66943359375 +1769682121,350046976,4.3429436683654785,0.011929869651794434,610.6635131835938 +1769682121,370823680,4.342526912689209,0.01188957691192627,610.6576538085938 +1769682121,403846912,4.342121601104736,0.011980593204498291,610.6500854492188 +1769682121,447983616,4.341867923736572,0.011926352977752686,610.6444702148438 +1769682121,470862080,4.341593265533447,0.011911094188690186,610.638916015625 +1769682121,504558080,4.34119176864624,0.011936724185943604,610.6317138671875 +1769682121,554311680,4.340872764587402,0.01187288761138916,610.6264038085938 +1769682121,571611904,4.340477466583252,0.01185065507888794,610.62109375 +1769682121,604787968,4.339913368225098,0.011909425258636475,610.6141967773438 +1769682121,660596480,4.339452743530273,0.011867523193359375,610.6090087890625 +1769682121,673969152,4.338815212249756,0.011875808238983154,610.6022338867188 +1769682121,706566656,4.338400363922119,0.011883914470672607,610.5972290039062 +1769682121,751509248,4.337936878204346,0.01182544231414795,610.5921630859375 +1769682121,785235200,4.337437629699707,0.011783897876739502,610.5872802734375 +1769682121,805100800,4.336733818054199,0.011831820011138916,610.5808715820312 +1769682121,852737792,4.336208343505859,0.011763334274291992,610.5761108398438 +1769682121,870982656,4.335679054260254,0.011711537837982178,610.5714111328125 +1769682121,904213504,4.334961891174316,0.011730432510375977,610.5653076171875 +1769682121,949847552,4.33439826965332,0.011676609516143799,610.5609130859375 +1769682121,972494848,4.333817958831787,0.011640727519989014,610.5565185546875 +1769682122,5788928,4.333037376403809,0.01167374849319458,610.5507202148438 +1769682122,77690368,4.332407474517822,0.01163327693939209,610.5464477539062 +1769682122,90239744,4.331406116485596,0.011658906936645508,610.540771484375 +1769682122,101874176,4.33090353012085,0.01161283254623413,610.5379028320312 +1769682122,146443264,4.329484939575195,0.011676311492919922,610.53076171875 +1769682122,170959360,4.328866004943848,0.011623919010162354,610.5279541015625 +1769682122,207994112,4.327545642852783,0.011670291423797607,610.522216796875 +1769682122,249427456,4.326395034790039,0.01163262128829956,610.51806640625 +1769682122,271881984,4.325244426727295,0.011598467826843262,610.513916015625 +1769682122,303911168,4.323679447174072,0.01162111759185791,610.508544921875 +1769682122,359882240,4.322412490844727,0.011584281921386719,610.5045776367188 +1769682122,370904064,4.32125997543335,0.011580944061279297,610.500732421875 +1769682122,405242624,4.319723129272461,0.011583805084228516,610.4956665039062 +1769682122,446494720,4.318283557891846,0.011546611785888672,610.4920043945312 +1769682122,474059008,4.31632661819458,0.01154869794845581,610.4871826171875 +1769682122,506639872,4.314882278442383,0.011536777019500732,610.4837036132812 +1769682122,553025280,4.313140869140625,0.01150500774383545,610.480224609375 +1769682122,571327232,4.311396598815918,0.011500060558319092,610.4767456054688 +1769682122,605774080,4.309023380279541,0.01154249906539917,610.4722900390625 +1769682122,671156992,4.306278228759766,0.01153630018234253,610.4677734375 +1769682122,677749760,4.3041253089904785,0.011537611484527588,610.4644775390625 +1769682122,703929600,4.301926136016846,0.011518239974975586,610.4612426757812 +1769682122,760905984,4.299536228179932,0.011479377746582031,610.4581298828125 +1769682122,768828928,4.297094345092773,0.011442840099334717,610.4551391601562 +1769682122,805088768,4.293833255767822,0.011438965797424316,610.4513549804688 +1769682122,849464064,4.2913079261779785,0.011404633522033691,610.4485473632812 +1769682122,873219584,4.288527011871338,0.011381030082702637,610.44580078125 +1769682122,904285952,4.284745216369629,0.011405110359191895,610.4423217773438 +1769682122,947616000,4.281790256500244,0.011383473873138428,610.4397583007812 +1769682122,970852096,4.279038429260254,0.01136922836303711,610.4371948242188 +1769682123,13616384,4.275331974029541,0.011385023593902588,610.4338989257812 +1769682123,47930624,4.2726216316223145,0.01136404275894165,610.431396484375 +1769682123,70481408,4.26996374130249,0.011339962482452393,610.428955078125 +1769682123,104484352,4.266411781311035,0.011336266994476318,610.4258422851562 +1769682123,163540736,4.263733863830566,0.011297464370727539,610.423583984375 +1769682123,173794560,4.261184215545654,0.011236786842346191,610.42138671875 +1769682123,203773184,4.257831573486328,0.011206567287445068,610.4187622070312 +1769682123,246880768,4.2553534507751465,0.011157333850860596,610.4169921875 +1769682123,270498304,4.25300931930542,0.011100172996520996,610.4153442382812 +1769682123,308022784,4.249950885772705,0.011065542697906494,610.4132690429688 +1769682123,357470720,4.247758388519287,0.01102137565612793,610.4119262695312 +1769682123,371836672,4.245639324188232,0.010994195938110352,610.4105834960938 +1769682123,405533184,4.2429070472717285,0.011008620262145996,610.4088134765625 +1769682123,453198592,4.240977764129639,0.010999083518981934,610.407470703125 +1769682123,471587840,4.239107608795166,0.011012077331542969,610.4060668945312 +1769682123,504479232,4.236844062805176,0.01106327772140503,610.4039306640625 +1769682123,547385600,4.235191822052002,0.011060178279876709,610.4022216796875 +1769682123,573471232,4.233489036560059,0.011045873165130615,610.4004516601562 +1769682123,606029824,4.231321811676025,0.011092901229858398,610.3978881835938 +1769682123,639092736,4.229909420013428,0.011072158813476562,610.3958129882812 +1769682123,670458368,4.228549480438232,0.011057913303375244,610.3938598632812 +1769682123,709216000,4.226912498474121,0.01106250286102295,610.39111328125 +1769682123,749115136,4.225814342498779,0.011029839515686035,610.38916015625 +1769682123,772915200,4.224817276000977,0.010983467102050781,610.3873291015625 +1769682123,805281024,4.223694324493408,0.010936737060546875,610.385009765625 +1769682123,869117696,4.222935199737549,0.010905086994171143,610.3834228515625 +1769682123,876485632,4.222139358520508,0.010867118835449219,610.3814697265625 +1769682123,906094848,4.221621990203857,0.010834336280822754,610.3802490234375 +1769682123,950862080,4.221189498901367,0.010801196098327637,610.37890625 +1769682123,978625792,4.220720291137695,0.01077502965927124,610.3773193359375 +1769682124,5158400,4.220446586608887,0.010773658752441406,610.3761596679688 +1769682124,53327872,4.220246315002441,0.010755717754364014,610.3748779296875 +1769682124,71534336,4.22021484375,0.010729432106018066,610.3736572265625 +1769682124,108271616,4.220207691192627,0.010724067687988281,610.3721923828125 +1769682124,140464896,4.220253944396973,0.010694622993469238,610.3710327148438 +1769682124,170539520,4.220267295837402,0.010699868202209473,610.3698120117188 +1769682124,206667776,4.220282077789307,0.010715723037719727,610.3681640625 +1769682124,253982976,4.2202606201171875,0.010738968849182129,610.3668823242188 +1769682124,271785728,4.220269203186035,0.010776102542877197,610.365478515625 +1769682124,304285184,4.220317840576172,0.010845541954040527,610.3634033203125 +1769682124,349226752,4.220382213592529,0.010873377323150635,610.3616943359375 +1769682124,375652352,4.22050142288208,0.010939419269561768,610.3590698242188 +1769682124,406470656,4.220622539520264,0.010985791683197021,610.3569946289062 +1769682124,449265152,4.220762252807617,0.011014819145202637,610.354736328125 +1769682124,470925056,4.220931529998779,0.011022090911865234,610.3524169921875 +1769682124,510270208,4.22092342376709,0.011068642139434814,610.3490600585938 +1769682124,551641600,4.220935821533203,0.011069953441619873,610.346435546875 +1769682124,572637952,4.220953464508057,0.011063218116760254,610.3436889648438 +1769682124,604201216,4.221010684967041,0.011094212532043457,610.340087890625 +1769682124,649627648,4.221061706542969,0.011074364185333252,610.3373413085938 +1769682124,671460864,4.2211079597473145,0.011062860488891602,610.3345947265625 +1769682124,707277824,4.22117280960083,0.011071562767028809,610.3310546875 +1769682124,749093376,4.221284866333008,0.011044085025787354,610.3285522460938 +1769682124,772028672,4.221370697021484,0.011019289493560791,610.325927734375 +1769682124,805106688,4.221495151519775,0.01103442907333374,610.3226928710938 +1769682124,847351296,4.2216596603393555,0.011020779609680176,610.3203125 +1769682124,882850048,4.221826553344727,0.011013805866241455,610.31787109375 +1769682124,905320960,4.222090244293213,0.011053979396820068,610.3145751953125 +1769682124,951690240,4.222318172454834,0.011066138744354248,610.3121337890625 +1769682124,971430400,4.2225542068481445,0.011075794696807861,610.3094482421875 +1769682125,7095296,4.222872734069824,0.01115339994430542,610.3058471679688 +1769682125,56958464,4.223273277282715,0.011195957660675049,610.3018798828125 +1769682125,70328832,4.223475456237793,0.011183857917785645,610.2999267578125 +1769682125,105515776,4.223933696746826,0.01126408576965332,610.2955932617188 +1769682125,161978368,4.224245548248291,0.011254489421844482,610.2923583984375 +1769682125,173216256,4.224353790283203,0.01123344898223877,610.2889404296875 +1769682125,206706688,4.224518775939941,0.011273503303527832,610.2843627929688 +1769682125,251961344,4.224649429321289,0.011242449283599854,610.2810668945312 +1769682125,271281920,4.224809646606445,0.011220872402191162,610.2777709960938 +1769682125,304822272,4.225025653839111,0.011275112628936768,610.2734375 +1769682125,349147648,4.225217819213867,0.011253535747528076,610.2702026367188 +1769682125,371795968,4.2253499031066895,0.011240184307098389,610.2669677734375 +1769682125,404500992,4.225532531738281,0.011299729347229004,610.2626342773438 +1769682125,451548416,4.225578308105469,0.011300325393676758,610.25927734375 +1769682125,473244160,4.225535869598389,0.011282086372375488,610.2557373046875 +1769682125,504682752,4.22549295425415,0.01135629415512085,610.2509155273438 +1769682125,564382720,4.225471496582031,0.011370718479156494,610.2471313476562 +1769682125,573727488,4.225457668304443,0.011369764804840088,610.2433471679688 +1769682125,606613760,4.2254319190979,0.011454224586486816,610.2380981445312 +1769682125,653408256,4.225435733795166,0.01143944263458252,610.2340698242188 +1769682125,670836736,4.225451469421387,0.011451423168182373,610.22998046875 +1769682125,707911936,4.225495338439941,0.011533379554748535,610.224365234375 +1769682125,760012032,4.22553825378418,0.011533200740814209,610.2201538085938 +1769682125,771866368,4.225574493408203,0.011525928974151611,610.2158203125 +1769682125,804770304,4.2256550788879395,0.011620402336120605,610.2099609375 +1769682125,867180544,4.225738525390625,0.011577308177947998,610.2056274414062 +1769682125,877931520,4.225888252258301,0.011623561382293701,610.19970703125 +1769682125,906333184,4.226001739501953,0.011631131172180176,610.1952514648438 +1769682125,947410432,4.2261176109313965,0.011585056781768799,610.1908569335938 +1769682125,977666048,4.226240634918213,0.011610567569732666,610.18505859375 +1769682126,5677824,4.2263407707214355,0.011590361595153809,610.1806640625 +1769682126,54502144,4.226515769958496,0.011540412902832031,610.1764526367188 +1769682126,70796288,4.226687431335449,0.011534273624420166,610.172119140625 +1769682126,109238784,4.226715087890625,0.011574864387512207,610.16650390625 +1769682126,148190208,4.22674560546875,0.011541903018951416,610.162353515625 +1769682126,173116160,4.226785182952881,0.011518418788909912,610.1580810546875 +1769682126,204556032,4.22690486907959,0.011606097221374512,610.1524047851562 +1769682126,254712832,4.227009296417236,0.011562764644622803,610.1480712890625 +1769682126,271484672,4.227137088775635,0.011565148830413818,610.1437377929688 +1769682126,305332480,4.227347373962402,0.01167374849319458,610.1376953125 +1769682126,347401216,4.227512836456299,0.011676132678985596,610.133056640625 +1769682126,376087808,4.227725505828857,0.01181870698928833,610.12646484375 +1769682126,406199552,4.227818012237549,0.011873841285705566,610.1212158203125 +1769682126,453025024,4.227926254272461,0.011892259120941162,610.1157836914062 +1769682126,471926784,4.228041172027588,0.011907041072845459,610.1100463867188 +1769682126,507975936,4.228198051452637,0.012027621269226074,610.1021728515625 +1769682126,554297088,4.228342533111572,0.012004375457763672,610.09619140625 +1769682126,573110784,4.228432655334473,0.011976063251495361,610.0902709960938 +1769682126,606019584,4.228550910949707,0.011988818645477295,610.0823974609375 +1769682126,659956224,4.228647708892822,0.011903584003448486,610.0767822265625 +1769682126,676916224,4.228780269622803,0.011905670166015625,610.0694580078125 +1769682126,704642816,4.2288923263549805,0.011851906776428223,610.064208984375 +1769682126,750697728,4.229011058807373,0.011761903762817383,610.05908203125 +1769682126,775919872,4.229175567626953,0.011788785457611084,610.052490234375 +1769682126,807980544,4.229294776916504,0.011764287948608398,610.0476684570312 +1769682126,847779328,4.22943115234375,0.011721193790435791,610.0427856445312 +1769682126,870855936,4.229578018188477,0.011689305305480957,610.0380249023438 +1769682126,907635200,4.229791641235352,0.011717736721038818,610.0316162109375 +1769682126,944758016,4.230018615722656,0.011693120002746582,610.025390625 +1769682126,970886400,4.230125427246094,0.011626660823822021,610.022216796875 +1769682127,4469504,4.2303643226623535,0.011662960052490234,610.0159912109375 +1769682127,52867072,4.230513572692871,0.011639595031738281,610.0114135742188 +1769682127,72418560,4.230525970458984,0.011632561683654785,610.0067749023438 +1769682127,105135616,4.23061990737915,0.011722207069396973,610.0004272460938 +1769682127,148288256,4.230690002441406,0.011733293533325195,609.9956665039062 +1769682127,178897664,4.230766296386719,0.011804640293121338,609.989013671875 +1769682127,205084928,4.230830669403076,0.011834442615509033,609.98388671875 +1769682127,253799168,4.230953216552734,0.011805355548858643,609.9786987304688 +1769682127,272168192,4.231064319610596,0.011794865131378174,609.9735717773438 +1769682127,306129920,4.23124885559082,0.011816799640655518,609.9666748046875 +1769682127,354732032,4.231368064880371,0.011730551719665527,609.9616088867188 +1769682127,371826688,4.231499671936035,0.0116768479347229,609.956787109375 +1769682127,405051392,4.231678485870361,0.01166754961013794,609.9505004882812 +1769682127,453614848,4.231867790222168,0.011578917503356934,609.946044921875 +1769682127,472482048,4.232052803039551,0.011530637741088867,609.9417114257812 +1769682127,505330432,4.2323479652404785,0.011550426483154297,609.9360961914062 +1769682127,553534208,4.232571125030518,0.011508524417877197,609.9320068359375 +1769682127,580784384,4.232913970947266,0.011536836624145508,609.9266357421875 +1769682127,606852352,4.233191013336182,0.011544883251190186,609.9224853515625 +1769682127,648690176,4.233471393585205,0.011529505252838135,609.9183349609375 +1769682127,670931968,4.2337327003479,0.01152735948562622,609.9141235351562 +1769682127,708037376,4.234079360961914,0.011593997478485107,609.9083862304688 +1769682127,747702272,4.234355926513672,0.011581659317016602,609.9039306640625 +1769682127,772716800,4.234591007232666,0.011568307876586914,609.8995361328125 +1769682127,804609024,4.234905242919922,0.01165992021560669,609.8934936523438 +1769682127,866442240,4.235220432281494,0.011686921119689941,609.887451171875 +1769682127,874318080,4.2354536056518555,0.011706829071044922,609.8828125 +1769682127,905510912,4.235682487487793,0.011712312698364258,609.8780517578125 +1769682127,947940352,4.235909461975098,0.011679649353027344,609.8733520507812 +1769682127,982511872,4.236122131347656,0.011665821075439453,609.8687133789062 +1769682128,6491136,4.236308574676514,0.011686861515045166,609.8624877929688 +1769682128,49664768,4.236451625823975,0.011642515659332275,609.8579711914062 +1769682128,71262720,4.2365946769714355,0.01159590482711792,609.8535766601562 +1769682128,104953088,4.236772537231445,0.011628985404968262,609.8478393554688 +1769682128,151968512,4.236936569213867,0.01161336898803711,609.8422241210938 +1769682128,171507712,4.2370100021362305,0.011574029922485352,609.8394165039062 +1769682128,205100032,4.237163066864014,0.011661052703857422,609.833740234375 +1769682128,266868992,4.237276077270508,0.01165693998336792,609.829345703125 +1769682128,274472192,4.237407684326172,0.011740922927856445,609.8233032226562 +1769682128,307307776,4.237504959106445,0.011779963970184326,609.8185424804688 +1769682128,351441664,4.2376203536987305,0.011764705181121826,609.8136596679688 +1769682128,373152000,4.237720012664795,0.011770188808441162,609.8087768554688 +1769682128,408732416,4.237852573394775,0.011871695518493652,609.8019409179688 +1769682128,447480320,4.23795223236084,0.01185905933380127,609.7968139648438 +1769682128,471052032,4.238042831420898,0.011843204498291016,609.7916259765625 +1769682128,506998272,4.23817253112793,0.011919498443603516,609.78466796875 +1769682128,554361344,4.238276481628418,0.011872649192810059,609.779541015625 +1769682128,572343296,4.238377571105957,0.011835753917694092,609.7743530273438 +1769682128,605334272,4.238516807556152,0.011905372142791748,609.767578125 +1769682128,649842432,4.238618850708008,0.011834859848022461,609.7625122070312 +1769682128,672693504,4.238717079162598,0.011801183223724365,609.757568359375 +1769682128,708041984,4.2388434410095215,0.011822283267974854,609.7510986328125 +1769682128,749064448,4.238945007324219,0.011768937110900879,609.7463989257812 +1769682128,771305984,4.239046573638916,0.01172250509262085,609.7417602539062 +1769682128,805082368,4.2391791343688965,0.01176828145980835,609.735595703125 +1769682128,849467136,4.239263534545898,0.011723160743713379,609.7310180664062 +1769682128,871395072,4.239333152770996,0.011711657047271729,609.7265014648438 +1769682128,905787136,4.239419937133789,0.011814355850219727,609.7203369140625 +1769682128,952774144,4.239497184753418,0.011817574501037598,609.7155151367188 +1769682128,972487424,4.239564895629883,0.011818170547485352,609.7106323242188 +1769682129,8562432,4.239646911621094,0.011912286281585693,609.703857421875 +1769682129,67949568,4.239706516265869,0.011890172958374023,609.69873046875 +1769682129,77338368,4.239774227142334,0.011947154998779297,609.691650390625 +1769682129,105584384,4.2398176193237305,0.011948049068450928,609.6864013671875 +1769682129,148425472,4.239855766296387,0.01190173625946045,609.68115234375 +1769682129,172546816,4.2398834228515625,0.01186591386795044,609.6759643554688 +1769682129,208028160,4.23993444442749,0.011907696723937988,609.6692504882812 +1769682129,247833856,4.240046977996826,0.011848986148834229,609.6627197265625 +1769682129,271485952,4.240101337432861,0.011784732341766357,609.6595458984375 +1769682129,305816576,4.240199565887451,0.011809110641479492,609.6534423828125 +1769682129,372008448,4.240257740020752,0.011742889881134033,609.6489868164062 +1769682129,378192896,4.240318298339844,0.011733949184417725,609.6431884765625 +1769682129,404317184,4.240358829498291,0.011708080768585205,609.6388549804688 +1769682129,449381632,4.240391254425049,0.01165771484375,609.6347045898438 +1769682129,475749120,4.240422248840332,0.011660158634185791,609.6292724609375 +1769682129,506717696,4.240438461303711,0.011636793613433838,609.6251831054688 +1769682129,548150272,4.240448474884033,0.011587381362915039,609.6212158203125 +1769682129,571082752,4.240450382232666,0.01156681776046753,609.6172485351562 +1769682129,607238400,4.240442276000977,0.011606693267822266,609.612060546875 +1769682129,660270592,4.240431308746338,0.011569023132324219,609.6082153320312 +1769682129,671314176,4.240406513214111,0.011561691761016846,609.6043090820312 +1769682129,705854208,4.240368843078613,0.011631906032562256,609.5990600585938 +1769682129,753705984,4.240332126617432,0.011623561382293701,609.5950927734375 +1769682129,773154816,4.240288734436035,0.011599183082580566,609.591064453125 +1769682129,805311488,4.240222930908203,0.01165914535522461,609.5856323242188 +1769682129,848734976,4.240167617797852,0.011613249778747559,609.5816040039062 +1769682129,874909952,4.240145683288574,0.011598587036132812,609.5762939453125 +1769682129,905764096,4.240164279937744,0.011569797992706299,609.5724487304688 +1769682129,951904000,4.240177631378174,0.011472880840301514,609.5687866210938 +1769682129,973337600,4.2401838302612305,0.01141500473022461,609.5642700195312 +1769682130,8077824,4.240184783935547,0.011344850063323975,609.5611572265625 +1769682130,48067840,4.240179538726807,0.011264503002166748,609.5582885742188 +1769682130,72064000,4.240164756774902,0.011198997497558594,609.5556640625 +1769682130,105276672,4.240137577056885,0.011142194271087646,609.5525512695312 +1769682130,170184192,4.2401123046875,0.01109468936920166,609.5503540039062 +1769682130,179447296,4.2401933670043945,0.011071622371673584,609.5477294921875 +1769682130,205851904,4.240281105041504,0.01106196641921997,609.5457153320312 +1769682130,248087040,4.240352630615234,0.011031687259674072,609.5438232421875 +1769682130,277530624,4.24043083190918,0.011058509349822998,609.541259765625 +1769682130,306579456,4.240477085113525,0.01106405258178711,609.5392456054688 +1769682130,348708352,4.240511417388916,0.011062324047088623,609.5372924804688 +1769682130,371459584,4.240532875061035,0.01105034351348877,609.5352783203125 +1769682130,410716160,4.240545272827148,0.011077940464019775,609.5326538085938 +1769682130,450035968,4.240530967712402,0.011064350605010986,609.5307006835938 +1769682130,471884800,4.240513801574707,0.011046290397644043,609.5287475585938 +1769682130,505921536,4.2404608726501465,0.011068284511566162,609.5262451171875 +1769682130,555849216,4.240406513214111,0.011055707931518555,609.5244140625 +1769682130,572354304,4.240345001220703,0.011025428771972656,609.5225830078125 +1769682130,605367552,4.240234375,0.01102358102798462,609.520263671875 +1769682130,650950656,4.2401227951049805,0.011021077632904053,609.5185546875 +1769682130,679339520,4.239963054656982,0.011006414890289307,609.516357421875 +1769682130,704988416,4.239833354949951,0.011001944541931152,609.5147705078125 +1769682130,748699136,4.239667892456055,0.010976016521453857,609.5133056640625 +1769682130,771520000,4.239492893218994,0.010941147804260254,609.5117797851562 +1769682130,806442496,4.23922061920166,0.01094740629196167,609.5098876953125 +1769682130,848341760,4.239151477813721,0.010892331600189209,609.5084838867188 +1769682130,872001536,4.239076614379883,0.010865449905395508,609.5072021484375 +1769682130,905111552,4.238945484161377,0.010831117630004883,609.5056762695312 +1769682130,949674240,4.238778114318848,0.010805904865264893,609.5042114257812 +1769682130,972052224,4.238678455352783,0.010782241821289062,609.5036010742188 +1769682131,5875456,4.238455295562744,0.010751962661743164,609.50244140625 +1769682131,50262272,4.238275527954102,0.010740816593170166,609.501708984375 +1769682131,72559104,4.238076686859131,0.010713338851928711,609.5010375976562 +1769682131,106676736,4.237887382507324,0.010727643966674805,609.5001220703125 +1769682131,157796096,4.2378153800964355,0.010703444480895996,609.4995727539062 +1769682131,173434880,4.23773193359375,0.010679423809051514,609.4990844726562 +1769682131,209254912,4.237607955932617,0.010662615299224854,609.49853515625 +1769682135,205608448,4.224598407745361,0.010496079921722412,609.5523071289062 +1769682135,268037120,0.0,-0.0,609.5524291992188 +1769682135,277842944,0.0,-0.0,609.552490234375 +1769682135,305382144,0.0,-0.0,609.552490234375 +1769682135,352566528,0.0,-0.0,609.552490234375 +1769682135,372752896,0.0,-0.0,609.552490234375 +1769682135,406224128,0.0,-0.0,609.552490234375 +1769682135,462984448,0.0,-0.0,609.552490234375 +1769682135,468595456,0.0,-0.0,609.552490234375 +1769682135,507687424,0.0,-0.0,609.552490234375 +1769682135,554949888,0.0,-0.0,609.552490234375 +1769682135,572461824,0.0,-0.0,609.552490234375 +1769682135,605119488,0.0,-0.0,609.552490234375 +1769682135,652199936,0.0,-0.0,609.552490234375 +1769682135,672070656,0.0,-0.0,609.5525512695312 +1769682135,705380864,0.0,-0.0,609.5525512695312 +1769682135,748313088,0.0,-0.0,609.5525512695312 +1769682135,772692736,0.0,-0.0,609.5525512695312 +1769682135,807455232,0.0,-0.0,609.5525512695312 +1769682135,870539008,0.0,-0.0,609.5525512695312 +1769682135,875869696,0.0,-0.0,609.5525512695312 +1769682135,905640448,0.0,-0.0,609.5525512695312 +1769682135,949940224,0.0,-0.0,609.5525512695312 +1769682135,977299712,0.0,-0.0,609.5525512695312 +1769682136,7739136,0.0,-0.0,609.5525512695312 +1769682136,50407424,0.0,-0.0,609.5525512695312 +1769682136,72501248,0.0,-0.0,609.5525512695312 +1769682136,105592832,0.0,-0.0,609.5525512695312 +1769682136,161005824,0.0,-0.0,609.5525512695312 +1769682136,172840960,0.0,-0.0,609.5525512695312 +1769682136,205764864,0.0,-0.0,609.5525512695312 +1769682136,254204160,0.0,-0.0,609.5525512695312 +1769682136,272860416,0.0,-0.0,609.5525512695312 +1769682136,307017216,0.0,-0.0,609.5525512695312 +1769682136,351220992,0.0,-0.0,609.5525512695312 +1769682136,379367680,0.0034029525704681873,0.0032043808605521917,609.5524291992188 +1769682136,406116096,0.021643387153744698,0.004624626599252224,609.5513305664062 +1769682136,451884032,0.03976617380976677,0.005941410548985004,609.5484619140625 +1769682136,472517376,0.05778250843286514,0.007169752381742001,609.5445556640625 +1769682136,511099904,0.081634521484375,0.008639760315418243,609.5381469726562 +1769682136,544549376,0.10540352761745453,0.009884128347039223,609.531005859375 +1769682136,571830016,0.11726581305265427,0.010409368202090263,609.52734375 +1769682136,605761536,0.14104428887367249,0.011280613020062447,609.5197143554688 +1769682136,655042048,0.15911392867565155,0.011776397004723549,609.513671875 +1769682136,673604864,0.176932692527771,0.012150730937719345,609.5076904296875 +1769682136,705716224,0.20046986639499664,0.012492287904024124,609.4993896484375 +1769682136,738513408,0.21930725872516632,0.01265111193060875,609.4929809570312 +1769682136,774960128,0.24567173421382904,0.012760970741510391,609.4839477539062 +1769682136,806621952,0.2657368779182434,0.012783583253622055,609.4768676757812 +1769682136,843195904,0.2860662639141083,0.012785762548446655,609.4693603515625 +1769682136,872035840,0.307112455368042,0.012771394103765488,609.4615478515625 +1769682136,908335360,0.336223304271698,0.01275257021188736,609.4505615234375 +1769682136,955716864,0.35883045196533203,0.012726947665214539,609.4418334960938 +1769682136,973983232,0.3823032081127167,0.012706547975540161,609.4327392578125 +1769682137,5829376,0.41358131170272827,0.01269451528787613,609.4201049804688 +1769682137,59636480,0.4461400508880615,0.012710049748420715,609.4067993164062 +1769682137,67796480,0.4628530442714691,0.012715823948383331,609.3999633789062 +1769682137,106857984,0.4973461925983429,0.012763135135173798,609.3856811523438 +1769682137,151463680,0.5237857699394226,0.012782730162143707,609.3745727539062 +1769682137,180385536,0.5597022771835327,0.012861408293247223,609.3590698242188 +1769682137,207918080,0.5870012640953064,0.01291394978761673,609.34716796875 +1769682137,252221440,0.615516185760498,0.012947112321853638,609.3347778320312 +1769682137,272827136,0.6439962387084961,0.012996673583984375,609.3222045898438 +1769682137,309521152,0.6817622184753418,0.013092294335365295,609.3048706054688 +1769682137,351538432,0.7110896706581116,0.013123676180839539,609.2916259765625 +1769682137,372863488,0.739020586013794,0.013150498270988464,609.2781982421875 +1769682137,406035200,0.7761174440383911,0.013232171535491943,609.26025390625 +1769682137,450116352,0.8041372895240784,0.013224154710769653,609.2467651367188 +1769682137,473204224,0.829494297504425,0.013218924403190613,609.2333984375 +1769682137,506790656,0.8626610636711121,0.013236626982688904,609.2158813476562 +1769682137,539421440,0.8875075578689575,0.013181954622268677,609.2030029296875 +1769682137,572568320,0.9140591621398926,0.01312410831451416,609.1903076171875 +1769682137,608411904,0.9499590992927551,0.013100102543830872,609.1734008789062 +1769682137,639517952,0.9769260883331299,0.013000324368476868,609.1608276367188 +1769682137,673328896,1.012678623199463,0.012907743453979492,609.1441040039062 +1769682137,706096384,1.0403298139572144,0.012815013527870178,609.1318969726562 +1769682137,757355008,1.0678212642669678,0.012685149908065796,609.1196899414062 +1769682137,771649280,1.0936838388442993,0.012547239661216736,609.10791015625 +1769682137,806284800,1.127964735031128,0.01240028440952301,609.0928955078125 +1769682137,850561024,1.1627728939056396,0.012195184826850891,609.0786743164062 +1769682137,872391936,1.1805819272994995,0.012050047516822815,609.07177734375 +1769682137,906775296,1.215928077697754,0.011887341737747192,609.05859375 +1769682137,968537600,1.242965579032898,0.01170426607131958,609.049072265625 +1769682137,979342592,1.2786927223205566,0.011513561010360718,609.0369873046875 +1769682138,9905408,1.3054602146148682,0.011359483003616333,609.0283203125 +1769682138,57018624,1.3321542739868164,0.011160701513290405,609.0200805664062 +1769682138,72855552,1.3590024709701538,0.010974258184432983,609.0123291015625 +1769682138,112318720,1.394913673400879,0.010759711265563965,609.0026245117188 +1769682138,148767744,1.4219253063201904,0.010539472103118896,608.9959716796875 +1769682138,173798400,1.4491287469863892,0.010341852903366089,608.9896850585938 +1769682138,208324352,1.4849796295166016,0.010121196508407593,608.9822387695312 +1769682138,273410560,1.5121104717254639,0.009913921356201172,608.9772338867188 +1769682138,280322304,1.547849416732788,0.009683221578598022,608.97119140625 +1769682138,305920512,1.5746173858642578,0.009503602981567383,608.9673461914062 +1769682138,338953216,1.6014699935913086,0.009313017129898071,608.9639282226562 +1769682138,372858368,1.6285656690597534,0.009134858846664429,608.9609985351562 +1769682138,408431872,1.6647047996520996,0.00891914963722229,608.957763671875 +1769682138,454042880,1.6917058229446411,0.00875169038772583,608.9558715820312 +1769682138,472629504,1.718482255935669,0.008590012788772583,608.954345703125 +1769682138,508374016,1.7539151906967163,0.008382529020309448,608.953125 +1769682138,556000512,1.7805426120758057,0.008233636617660522,608.9528198242188 +1769682138,574534656,1.8070487976074219,0.008084684610366821,608.952880859375 +1769682138,606874880,1.8423644304275513,0.0078812837600708,608.95361328125 +1769682138,655006464,1.8774375915527344,0.007692426443099976,608.9552001953125 +1769682138,671610112,1.894858479499817,0.007604748010635376,608.956298828125 +1769682138,706140416,1.9296181201934814,0.007422596216201782,608.9589233398438 +1769682138,754795520,1.9555423259735107,0.007312506437301636,608.9614868164062 +1769682138,780365824,1.9899135828018188,0.00714448094367981,608.9652709960938 +1769682138,807257344,2.0155348777770996,0.0070393383502960205,608.9686279296875 +1769682138,841420800,2.04103946685791,0.0069501399993896484,608.9722290039062 +1769682138,872121600,2.066527843475342,0.006853461265563965,608.9762573242188 +1769682138,908076544,2.1001956462860107,0.006696850061416626,608.9821166992188 +1769682138,943376384,2.1335294246673584,0.006575465202331543,608.9884643554688 +1769682138,972597248,2.150103807449341,0.006551116704940796,608.9918823242188 +1769682139,5847808,2.183136224746704,0.006420493125915527,608.9989624023438 +1769682139,54648320,2.2077529430389404,0.0063818395137786865,609.004638671875 +1769682139,73213184,2.2321431636810303,0.006320208311080933,609.0105590820312 +1769682139,106093568,2.264314651489258,0.006180703639984131,609.018798828125 +1769682139,139015680,2.2884578704833984,0.006141602993011475,609.0253295898438 +1769682139,174761984,2.3125057220458984,0.0061099231243133545,609.0320434570312 +1769682139,207569920,2.344264030456543,0.005971848964691162,609.0414428710938 +1769682139,250985984,2.367727518081665,0.005961716175079346,609.0486450195312 +1769682139,272483840,2.391030788421631,0.005933523178100586,609.05615234375 +1769682139,306515968,2.421964168548584,0.005834907293319702,609.0664672851562 +1769682139,355929344,2.4450273513793945,0.005840301513671875,609.0743408203125 +1769682139,374208512,2.475513219833374,0.005759775638580322,609.0850830078125 +1769682139,406024448,2.4981563091278076,0.005736023187637329,609.0932006835938 +1769682139,452599040,2.5208120346069336,0.005760848522186279,609.1015014648438 +1769682139,473085184,2.5432181358337402,0.005763649940490723,609.10986328125 +1769682139,509825792,2.5726985931396484,0.005670219659805298,609.1212768554688 +1769682139,565728768,2.59452223777771,0.005718588829040527,609.1299438476562 +1769682139,576356608,2.6234512329101562,0.0056344568729400635,609.1416625976562 +1769682139,607728384,2.644927978515625,0.005623131990432739,609.150634765625 +1769682139,653055744,2.666315793991089,0.005688399076461792,609.15966796875 +1769682139,672530176,2.68752121925354,0.005688965320587158,609.168701171875 +1769682139,708207104,2.715635061264038,0.0056154727935791016,609.180908203125 +1769682139,757874688,2.743469476699829,0.005631506443023682,609.1931762695312 +1769682139,767939840,2.757197141647339,0.005674302577972412,609.1993408203125 +1769682139,806182144,2.784374952316284,0.005658984184265137,609.2116088867188 +1769682139,855123200,2.804537057876587,0.005746662616729736,609.2208251953125 +1769682139,873567488,2.82456111907959,0.005782723426818848,609.2301025390625 +1769682139,906287360,2.85101580619812,0.005730688571929932,609.242431640625 +1769682139,939867392,2.870671510696411,0.005827069282531738,609.2516479492188 +1769682139,978634240,2.8965654373168945,0.005812346935272217,609.2638549804688 +1769682140,9336576,2.9157471656799316,0.005847036838531494,609.2728881835938 +1769682140,51547136,2.934643030166626,0.005949139595031738,609.2819213867188 +1769682140,73691136,2.9595932960510254,0.005936741828918457,609.2938842773438 +1769682140,106903552,2.9779953956604004,0.005972146987915039,609.3027954101562 +1769682140,145403648,3.0023226737976074,0.0060217976570129395,609.314697265625 +1769682140,172726528,3.014371633529663,0.006126582622528076,609.3206176757812 +1769682140,206362624,3.0383217334747314,0.0060797929763793945,609.3323364257812 +1769682140,254034432,3.055816888809204,0.006168365478515625,609.3411865234375 +1769682140,273976832,3.07319712638855,0.006232321262359619,609.3499755859375 +1769682140,307271168,3.0960657596588135,0.006186068058013916,609.3617553710938 +1769682140,348600320,3.1129751205444336,0.006280422210693359,609.370361328125 +1769682140,379301376,3.1353394985198975,0.00627666711807251,609.3819580078125 +1769682140,408822784,3.151890516281128,0.0063239336013793945,609.3905029296875 +1769682140,453628928,3.168356418609619,0.006423294544219971,609.39892578125 +1769682140,474190592,3.1898539066314697,0.006435811519622803,609.4100952148438 +1769682140,508524800,3.205829620361328,0.006498098373413086,609.4182739257812 +1769682140,543921664,3.2269704341888428,0.00657343864440918,609.4290161132812 +1769682140,572410368,3.2373454570770264,0.006686866283416748,609.4342651367188 +1769682140,607988480,3.257779598236084,0.006676733493804932,609.4447631835938 +1769682140,653869824,3.2729058265686035,0.006781458854675293,609.452392578125 +1769682140,675146240,3.2929444313049316,0.006810367107391357,609.4624633789062 +1769682140,706023424,3.3077285289764404,0.006873488426208496,609.4698486328125 +1769682140,749088512,3.3224098682403564,0.006987512111663818,609.4771728515625 +1769682140,777646336,3.341752052307129,0.007032632827758789,609.486572265625 +1769682140,807423232,3.355988025665283,0.007105112075805664,609.4934692382812 +1769682140,842975488,3.3701086044311523,0.0072457194328308105,609.5001220703125 +1769682140,872444416,3.3839492797851562,0.007318675518035889,609.506591796875 +1769682140,908187648,3.4022741317749023,0.0073313117027282715,609.51513671875 +1769682140,960838144,3.4157602787017822,0.007434666156768799,609.521240234375 +1769682140,969659136,3.42919921875,0.00747758150100708,609.52734375 +1769682141,6359808,3.4468605518341064,0.007517993450164795,609.5352172851562 +1769682141,55964672,3.4643092155456543,0.007570862770080566,609.54296875 +1769682141,72953600,3.4729788303375244,0.007653474807739258,609.5467529296875 +1769682141,107995648,3.490154266357422,0.007635056972503662,609.5542602539062 +1769682141,140836096,3.5027918815612793,0.007720649242401123,609.5598754882812 +1769682141,173850880,3.515353202819824,0.007768154144287109,609.5653686523438 +1769682141,206518784,3.5318539142608643,0.007729470729827881,609.5726928710938 +1769682141,251052544,3.5440001487731934,0.007799983024597168,609.578125 +1769682141,272739328,3.55607008934021,0.007847428321838379,609.58349609375 +1769682141,310415616,3.5718793869018555,0.00784069299697876,609.590576171875 +1769682141,350068992,3.5836291313171387,0.007927298545837402,609.5957641601562 +1769682141,373762048,3.595240592956543,0.008007168769836426,609.600830078125 +1769682141,408704512,3.610583543777466,0.008029341697692871,609.6072998046875 +1769682141,456165120,3.621917247772217,0.008135020732879639,609.6119384765625 +1769682141,473619200,3.636822462081909,0.008150160312652588,609.6178588867188 +1769682141,506507520,3.6479249000549316,0.008178472518920898,609.6222534179688 +1769682141,543582464,3.6624808311462402,0.008212566375732422,609.6278686523438 +1769682141,572686336,3.6697397232055664,0.008269786834716797,609.6307983398438 +1769682141,606503680,3.683953046798706,0.008234500885009766,609.6364135742188 +1769682141,639537152,3.694488048553467,0.008280277252197266,609.6407470703125 +1769682141,683582720,3.7049460411071777,0.008301973342895508,609.6450805664062 +1769682141,709280768,3.71869158744812,0.008261620998382568,609.65087890625 +1769682141,757133568,3.7288401126861572,0.008321046829223633,609.6551513671875 +1769682141,772334336,3.7388463020324707,0.008337914943695068,609.6595458984375 +1769682141,812141568,3.7521462440490723,0.008308827877044678,609.6651611328125 +1769682141,854874112,3.7619376182556152,0.00835484266281128,609.6694946289062 +1769682141,874403328,3.771682024002075,0.008390426635742188,609.6736450195312 +1769682141,906972928,3.7845327854156494,0.008353769779205322,609.6791381835938 +1769682141,957780480,3.794004440307617,0.00841444730758667,609.6832885742188 +1769682141,989102336,3.8064491748809814,0.008388161659240723,609.6887817382812 +1769682142,7190528,3.8156726360321045,0.008415520191192627,609.69287109375 +1769682142,45395712,3.8278496265411377,0.008446097373962402,609.6982421875 +1769682142,74744832,3.8367912769317627,0.008485496044158936,609.7022094726562 +1769682142,108137216,3.845649003982544,0.008535921573638916,609.7059936523438 +1769682142,140833536,3.8543570041656494,0.008631348609924316,609.7097778320312 +1769682142,182996736,3.862997531890869,0.008705556392669678,609.7133178710938 +1769682142,206977280,3.8742828369140625,0.008747100830078125,609.7177734375 +1769682142,251559168,3.8826212882995605,0.008838951587677002,609.7208862304688 +1769682142,273825536,3.893458604812622,0.008898735046386719,609.7247924804688 +1769682142,306618368,3.9014861583709717,0.008951902389526367,609.7274780273438 +1769682142,345005568,3.911851406097412,0.00901651382446289,609.73095703125 +1769682142,373281024,3.9169421195983887,0.009071707725524902,609.7326049804688 +1769682142,408612608,3.926950454711914,0.00908505916595459,609.7359619140625 +1769682142,465291776,3.934282064437866,0.009136736392974854,609.7383422851562 +1769682142,473327872,3.9415292739868164,0.009164214134216309,609.7407836914062 +1769682142,507019776,3.9509811401367188,0.009158313274383545,609.7440185546875 +1769682142,554741760,3.9579293727874756,0.009197652339935303,609.746337890625 +1769682142,574901504,3.9670469760894775,0.009203493595123291,609.7494506835938 +1769682142,609339904,3.9737753868103027,0.009220480918884277,609.7517700195312 +1769682142,654608384,3.980320930480957,0.009266972541809082,609.7540283203125 +1769682142,672843008,3.9866461753845215,0.009302139282226562,609.7562255859375 +1769682142,708133632,3.9949777126312256,0.009311199188232422,609.7591552734375 +1769682142,753443328,4.003068447113037,0.009357154369354248,609.7617797851562 +1769682142,773238784,4.00709867477417,0.009397387504577637,609.7630615234375 +1769682142,808228864,4.0148844718933105,0.009393572807312012,609.765625 +1769682142,872641536,4.020628452301025,0.009422063827514648,609.7674560546875 +1769682142,881604096,4.028061389923096,0.00942540168762207,609.7698974609375 +1769682142,908890112,4.033432960510254,0.009446024894714355,609.771728515625 +1769682142,942495232,4.038776874542236,0.009501993656158447,609.7735595703125 +1769682142,972634368,4.0438408851623535,0.009538352489471436,609.7753295898438 +1769682143,10845696,4.050475120544434,0.009584903717041016,609.7775268554688 +1769682143,51579904,4.05527925491333,0.009651541709899902,609.779052734375 +1769682143,73594112,4.059950828552246,0.009719550609588623,609.7803344726562 +1769682143,106358016,4.066041469573975,0.009805619716644287,609.78173828125 +1769682143,158276864,4.071951389312744,0.00990229845046997,609.7828369140625 +1769682143,168129024,4.074794769287109,0.009958744049072266,609.783203125 +1769682143,207485440,4.080249786376953,0.010034322738647461,609.7837524414062 +1769682143,256756992,4.085397243499756,0.01009601354598999,609.783935546875 +1769682143,280620800,4.089186191558838,0.010125279426574707,609.7841796875 +1769682143,307580672,4.0929036140441895,0.010145723819732666,609.7842407226562 +1769682143,344444928,4.0974860191345215,0.010152995586395264,609.7843627929688 +1769682143,372665600,4.099732398986816,0.010146141052246094,609.784423828125 +1769682143,409032704,4.10398006439209,0.010141193866729736,609.7848510742188 +1769682143,452784896,4.107086658477783,0.01013404130935669,609.7852172851562 +1769682143,473792512,4.110068321228027,0.01013094186782837,609.7857055664062 +1769682143,508807424,4.113938808441162,0.010109126567840576,609.7864990234375 +1769682143,555551744,4.1176300048828125,0.010092020034790039,609.7872924804688 +1769682143,573548032,4.120273590087891,0.010085701942443848,609.7879638671875 +1769682143,606856192,4.1228251457214355,0.010063409805297852,609.7886352539062 +1769682143,640696064,4.125181674957275,0.010058701038360596,609.7894897460938 +1769682143,676258816,4.128244400024414,0.010024011135101318,609.7906494140625 +1769682143,709265664,4.13038444519043,0.010013222694396973,609.7915649414062 +1769682143,742781696,4.132474899291992,0.010012626647949219,609.7926025390625 +1769682143,772895488,4.134450435638428,0.010010898113250732,609.793701171875 +1769682143,807197696,4.1369218826293945,0.010009229183197021,609.7951049804688 +1769682143,851460352,4.138669967651367,0.010023355484008789,609.796142578125 +1769682143,874819584,4.140958309173584,0.01002037525177002,609.797607421875 +1769682143,907351808,4.142546653747559,0.010012030601501465,609.7987670898438 +1769682143,951162112,4.144467353820801,0.009984314441680908,609.80029296875 +1769682143,973148416,4.145360469818115,0.009983181953430176,609.8012084960938 +1769682144,6945792,4.147043704986572,0.009928107261657715,609.8030395507812 +1769682144,67931904,4.148219108581543,0.009910821914672852,609.8046875 +1769682144,76698880,4.149636745452881,0.00986635684967041,609.8069458007812 +1769682144,108196096,4.150630950927734,0.00985783338546753,609.8087768554688 +1769682144,151806464,4.1515793800354,0.009869813919067383,609.8107299804688 +1769682144,174125568,4.15275764465332,0.009871482849121094,609.8133544921875 +1769682144,208753408,4.153599262237549,0.00989687442779541,609.815185546875 +1769682144,249830144,4.15447998046875,0.009929895401000977,609.8175659179688 +1769682144,275116800,4.155132293701172,0.009944558143615723,609.8192749023438 +1769682144,306441216,4.155640125274658,0.009960830211639404,609.82080078125 +1769682144,354049792,4.156154155731201,0.009971678256988525,609.822998046875 +1769682144,374406144,4.156439781188965,0.009964823722839355,609.8246459960938 +1769682144,407035904,4.1567158699035645,0.009961724281311035,609.8263549804688 +1769682144,440686848,4.156917095184326,0.009982466697692871,609.828125 +1769682144,474667776,4.1570844650268555,0.00997835397720337,609.8305053710938 +1769682144,506985728,4.157147407531738,0.009990870952606201,609.832275390625 +1769682144,551859968,4.157127380371094,0.010019958019256592,609.8340454101562 +1769682144,573354752,4.157094955444336,0.010025262832641602,609.8363037109375 +1769682144,606985472,4.156975746154785,0.010038256645202637,609.8380126953125 +1769682144,641091072,4.156843185424805,0.010055840015411377,609.839599609375 +1769682144,673088256,4.1566996574401855,0.010055303573608398,609.8411865234375 +1769682144,708526080,4.156436443328857,0.009990811347961426,609.8434448242188 +1769682144,753797888,4.15609884262085,0.009934306144714355,609.845947265625 +1769682144,773134080,4.155930995941162,0.009936988353729248,609.8472900390625 +1769682144,806860032,4.155579090118408,0.009859442710876465,609.8501586914062 +1769682144,855654144,4.155283451080322,0.009852170944213867,609.8524780273438 +1769682144,874435584,4.15491247177124,0.009808957576751709,609.8558349609375 +1769682144,907858688,4.154616355895996,0.009811222553253174,609.8582153320312 +1769682144,941720576,4.154323101043701,0.009846031665802002,609.8606567382812 +1769682144,974113536,4.153931140899658,0.009838998317718506,609.8638305664062 +1769682145,8961792,4.153632164001465,0.0098494291305542,609.8660278320312 +1769682145,40992000,4.153331279754639,0.009878993034362793,609.8682861328125 +1769682145,73220608,4.153036594390869,0.00987309217453003,609.8704833984375 +1769682145,109328896,4.152667045593262,0.009816288948059082,609.87353515625 +1769682145,139544832,4.152386665344238,0.009819746017456055,609.8758544921875 +1769682145,173478656,4.152044296264648,0.00976252555847168,609.879150390625 +1769682145,209758976,4.1518096923828125,0.00974196195602417,609.8816528320312 +1769682145,253410816,4.151578903198242,0.009750723838806152,609.88427734375 +1769682145,273331712,4.151251792907715,0.00969916582107544,609.887939453125 +1769682145,308050176,4.1510114669799805,0.009673655033111572,609.8908081054688 +1769682145,350400256,4.150789737701416,0.009686589241027832,609.8935546875 +1769682145,373579008,4.150555610656738,0.009623169898986816,609.8974609375 +1769682145,406616832,4.150392055511475,0.009588122367858887,609.9005126953125 +1769682145,439656960,4.150249481201172,0.009582221508026123,609.9036254882812 +1769682145,474694400,4.150095462799072,0.00950765609741211,609.9078979492188 +1769682145,508039168,4.150002956390381,0.009469687938690186,609.9113159179688 +1769682145,565124608,4.1499223709106445,0.009440124034881592,609.9158935546875 +1769682145,573602560,4.149881362915039,0.009466767311096191,609.9182739257812 +1769682145,607548672,4.149810314178467,0.009387314319610596,609.9230346679688 +1769682145,653584128,4.149769306182861,0.009410381317138672,609.9266357421875 +1769682145,675378432,4.149747848510742,0.009375452995300293,609.9314575195312 +1769682145,707129600,4.149759292602539,0.009381473064422607,609.9351806640625 +1769682145,740119808,4.149783611297607,0.009432077407836914,609.938720703125 +1769682145,774256384,4.1498332023620605,0.009441673755645752,609.943359375 +1769682145,808157696,4.1498847007751465,0.009486734867095947,609.9465942382812 +1769682145,842903040,4.149947643280029,0.009561598300933838,609.9498291015625 +1769682145,873743360,4.150042533874512,0.009578883647918701,609.953857421875 +1769682145,906784256,4.150120735168457,0.009609043598175049,609.9567260742188 +1769682145,941640960,4.150206565856934,0.009679615497589111,609.9594116210938 +1769682145,975340800,4.150323390960693,0.009688615798950195,609.9628295898438 +1769682146,8243712,4.150424957275391,0.009704828262329102,609.9653930664062 +1769682146,57854720,4.1505866050720215,0.009727537631988525,609.9685668945312 +1769682146,80745984,4.150737762451172,0.009736061096191406,609.9710083007812 +1769682146,106891776,4.150897979736328,0.009738683700561523,609.973388671875 +1769682146,145352704,4.151126384735107,0.009734272956848145,609.9766235351562 +1769682146,174226944,4.151331424713135,0.009724676609039307,609.97900390625 +1769682146,210392832,4.151538848876953,0.009718596935272217,609.9815063476562 +1769682146,247170816,4.151774883270264,0.009709954261779785,609.98486328125 +1769682146,273200128,4.151985168457031,0.009708404541015625,609.9873046875 +1769682146,306667008,4.152197360992432,0.00973653793334961,609.98974609375 +1769682146,352943104,4.152472972869873,0.009776771068572998,609.9929809570312 +1769682146,374003968,4.152666091918945,0.009818673133850098,609.9951782226562 +1769682146,406799872,4.152895927429199,0.009855866432189941,609.9972534179688 +1769682146,440391424,4.153141498565674,0.009913921356201172,609.9990844726562 +1769682146,474859520,4.15346622467041,0.009942352771759033,610.0013427734375 +1769682146,508851712,4.153750896453857,0.009963810443878174,610.0029907226562 +1769682146,541490432,4.154036045074463,0.009993970394134521,610.0045166015625 +1769682146,573412096,4.154427528381348,0.009973347187042236,610.00634765625 +1769682146,613021696,4.154770851135254,0.0099639892578125,610.0076904296875 +1769682146,642670848,4.155120372772217,0.009964287281036377,610.0089111328125 +1769682146,674643200,4.155584335327148,0.009930551052093506,610.0106201171875 +1769682146,707312896,4.15595817565918,0.009919345378875732,610.0119018554688 +1769682146,752555520,4.156486988067627,0.009892284870147705,610.0136108398438 +1769682146,775310080,4.156923294067383,0.009868144989013672,610.0149536132812 +1769682146,807140864,4.157366752624512,0.00983208417892456,610.0162963867188 +1769682146,840674048,4.157815933227539,0.009822726249694824,610.0177001953125 +1769682146,875823104,4.158438205718994,0.009775996208190918,610.0197143554688 +1769682146,908013312,4.158916473388672,0.009741544723510742,610.0213623046875 +1769682146,945517056,4.159552097320557,0.00970315933227539,610.0235595703125 +1769682146,973541376,4.160033226013184,0.00968480110168457,610.0254516601562 +1769682147,9246464,4.160517692565918,0.009682118892669678,610.0274047851562 +1769682147,46342656,4.161155700683594,0.009688377380371094,610.0301513671875 +1769682147,73549056,4.161632061004639,0.009699523448944092,610.0322265625 +1769682147,107021056,4.162113666534424,0.009725332260131836,610.0343627929688 +1769682147,153174016,4.162749767303467,0.009776949882507324,610.037109375 +1769682147,175243520,4.163193225860596,0.009824275970458984,610.0390625 +1769682147,207521792,4.163609027862549,0.009878695011138916,610.0408325195312 +1769682147,240209408,4.164030075073242,0.009925663471221924,610.04248046875 +1769682147,273823488,4.164597988128662,0.009950578212738037,610.0443115234375 +1769682147,307452416,4.165034294128418,0.009966075420379639,610.0455322265625 +1769682147,341031168,4.165461540222168,0.009988903999328613,610.0466918945312 +1769682147,373821184,4.16602087020874,0.009971141815185547,610.0480346679688 +1769682147,407954432,4.16644287109375,0.009960711002349854,610.049072265625 +1769682147,442617088,4.166858196258545,0.009953975677490234,610.0501098632812 +1769682147,475709440,4.167370796203613,0.009914875030517578,610.0516357421875 +1769682147,510286848,4.167761325836182,0.009852766990661621,610.0527954101562 +1769682147,542663424,4.1681365966796875,0.009779632091522217,610.0540161132812 +1769682147,573591808,4.1686110496521,0.009648621082305908,610.0557250976562 +1769682147,606907904,4.169000625610352,0.009563982486724854,610.0570068359375 +1769682147,644036608,4.169506072998047,0.009468495845794678,610.058837890625 +1769682147,675842560,4.169894695281982,0.009417712688446045,610.0601806640625 +1769682147,708522752,4.170287132263184,0.009377896785736084,610.0616455078125 +1769682147,741169920,4.170673847198486,0.009372889995574951,610.0631713867188 +1769682147,774535680,4.171182632446289,0.0093308687210083,610.0652465820312 +1769682147,808943616,4.171590805053711,0.009325683116912842,610.06689453125 +1769682147,853164800,4.172131538391113,0.009346306324005127,610.0689086914062 +1769682147,873748224,4.172533988952637,0.009379804134368896,610.0704345703125 +1769682147,907412480,4.172974586486816,0.00941312313079834,610.07177734375 +1769682147,958771712,4.17356538772583,0.009532690048217773,610.0735473632812 +1769682147,973082112,4.17400598526001,0.009641945362091064,610.0747680664062 +1769682148,7552512,4.174458026885986,0.009745001792907715,610.0759887695312 +1769682148,53312768,4.174914360046387,0.009853899478912354,610.0770874023438 +1769682148,73720576,4.175532341003418,0.009939908981323242,610.07861328125 +1769682148,108430592,4.175997734069824,0.00999671220779419,610.07958984375 +1769682148,142911488,4.176455497741699,0.010054171085357666,610.08056640625 +1769682148,173828352,4.177006721496582,0.010041654109954834,610.0819091796875 +1769682148,207656704,4.1774187088012695,0.00999230146408081,610.082763671875 +1769682148,240737792,4.177818298339844,0.009933888912200928,610.083740234375 +1769682148,273802240,4.1783318519592285,0.00984114408493042,610.0848999023438 +1769682148,309398528,4.178715705871582,0.00977170467376709,610.0857543945312 +1769682148,342603776,4.179093837738037,0.009711742401123047,610.086669921875 +1769682148,374887680,4.179563999176025,0.009620428085327148,610.0880126953125 +1769682148,407001856,4.179905891418457,0.009582340717315674,610.0890502929688 +1769682148,456875776,4.180308818817139,0.009506702423095703,610.0905151367188 +1769682148,476112640,4.180544376373291,0.009443163871765137,610.091552734375 +1769682148,507290624,4.180795192718506,0.009387373924255371,610.0925903320312 +1769682148,544156160,4.181121349334717,0.009370625019073486,610.09375 +1769682148,579898624,4.181352138519287,0.009366095066070557,610.0944213867188 +1769682148,609075968,4.181670665740967,0.009430348873138428,610.0949096679688 +1769682148,645202432,4.1820902824401855,0.009543240070343018,610.0950927734375 +1769682148,673667328,4.182392597198486,0.009619832038879395,610.0950927734375 +1769682148,708734720,4.182790756225586,0.009697973728179932,610.094970703125 +1769682148,746132736,4.183297634124756,0.009770095348358154,610.0946044921875 +1769682148,775241728,4.183737277984619,0.009806156158447266,610.0942993164062 +1769682148,808843264,4.184213638305664,0.009831428527832031,610.0939331054688 +1769682148,853282304,4.1848464012146,0.009864509105682373,610.0936889648438 +1769682148,874208000,4.185423851013184,0.009879231452941895,610.0933837890625 +1769682148,907043328,4.1860175132751465,0.009925127029418945,610.0933227539062 +1769682148,940161792,4.18661642074585,0.009978055953979492,610.09326171875 +1769682148,977589248,4.1874237060546875,0.010031282901763916,610.0932006835938 +1769682149,8341248,4.188103199005127,0.010053455829620361,610.09326171875 +1769682149,41005056,4.1888108253479,0.010071635246276855,610.0933837890625 +1769682149,73474048,4.189774036407471,0.010066390037536621,610.0936279296875 +1769682149,112133632,4.190545558929443,0.010028243064880371,610.0938720703125 +1769682149,144408576,4.191474437713623,0.009935319423675537,610.0942993164062 +1769682149,174872320,4.192193508148193,0.009863555431365967,610.0946044921875 +1769682149,206777088,4.192910194396973,0.009791433811187744,610.0950927734375 +1769682149,256440832,4.1938886642456055,0.009693324565887451,610.0956420898438 +1769682149,274349568,4.1946306228637695,0.009624123573303223,610.09619140625 +1769682149,307384320,4.195400714874268,0.009558439254760742,610.0968017578125 +1769682149,342465536,4.196182727813721,0.009503483772277832,610.0974731445312 +1769682149,375970560,4.197201251983643,0.009419143199920654,610.0985107421875 +1769682149,409616384,4.197969913482666,0.009366750717163086,610.0994873046875 +1769682149,441814272,4.1985650062561035,0.009311437606811523,610.1004028320312 +1769682149,473738752,4.19931697845459,0.009301900863647461,610.1018676757812 +1769682149,514326528,4.199843406677246,0.009320199489593506,610.1030883789062 +1769682149,548616704,4.20050048828125,0.009349703788757324,610.1047973632812 +1769682149,574917376,4.200978755950928,0.00939708948135376,610.1060791015625 +1769682149,607627520,4.201403617858887,0.009470582008361816,610.1075439453125 +1769682149,655545600,4.20193338394165,0.00953829288482666,610.1094970703125 +1769682149,673620480,4.2023024559021,0.009591519832611084,610.1109619140625 +1769682149,706967040,4.2026214599609375,0.009640634059906006,610.112548828125 +1769682149,740054784,4.202915191650391,0.009701728820800781,610.1141357421875 +1769682149,777042944,4.203294277191162,0.009744644165039062,610.1160888671875 +1769682149,807501568,4.203513145446777,0.009772717952728271,610.1176147460938 +1769682149,840704512,4.203671455383301,0.009818494319915771,610.1190185546875 +1769682149,875326464,4.203855514526367,0.009820818901062012,610.1209716796875 +1769682149,910196992,4.203971862792969,0.009797155857086182,610.1222534179688 +1769682149,942760960,4.203965187072754,0.009780585765838623,610.12353515625 +1769682149,974128896,4.2038774490356445,0.009725034236907959,610.125244140625 +1769682150,7343104,4.203752517700195,0.009695291519165039,610.12646484375 +1769682150,59496448,4.203420639038086,0.009654045104980469,610.1281127929688 +1769682150,66871040,4.203225135803223,0.009634613990783691,610.1289672851562 +1769682150,107593728,4.202552795410156,0.00955742597579956,610.1305541992188 +1769682150,142697984,4.201889991760254,0.009587585926055908,610.1317749023438 +1769682150,173655808,4.200879096984863,0.009612500667572021,610.1336059570312 +1769682150,208642816,4.200048446655273,0.009643375873565674,610.135009765625 +1769682150,242889472,4.199080467224121,0.009701073169708252,610.1362915039062 +1769682150,273683712,4.197723865509033,0.009756743907928467,610.1380615234375 +1769682150,307159296,4.196598052978516,0.009798645973205566,610.1392822265625 +1769682150,346964224,4.194958209991455,0.009875178337097168,610.1408081054688 +1769682150,375438848,4.193645477294922,0.009909868240356445,610.1417846679688 +1769682150,407685632,4.1922783851623535,0.009937644004821777,610.1427612304688 +1769682150,455304704,4.190806865692139,0.009975910186767578,610.1437377929688 +1769682150,474208256,4.188641548156738,0.01006382703781128,610.1449584960938 +1769682150,509699584,4.186916351318359,0.010151863098144531,610.1458740234375 +1769682150,540657920,4.18510627746582,0.010243654251098633,610.1469116210938 +1769682150,573822720,4.182648181915283,0.010293364524841309,610.148193359375 +1769682150,607581184,4.180716514587402,0.010307610034942627,610.1492919921875 +1769682150,645752320,4.178023815155029,0.010316967964172363,610.1508178710938 +1769682150,675795456,4.175927639007568,0.010313153266906738,610.1519775390625 +1769682150,709674240,4.173763751983643,0.010301530361175537,610.1531982421875 +1769682150,758918656,4.17063045501709,0.01027977466583252,610.1549682617188 +1769682150,773394688,4.168251037597656,0.010268807411193848,610.1563720703125 +1769682150,807253504,4.1658172607421875,0.010251104831695557,610.1578979492188 +1769682150,850046976,4.163252353668213,0.010259091854095459,610.159423828125 +1769682150,874656768,4.1597466468811035,0.010250985622406006,610.1614379882812 +1769682150,909593344,4.157052516937256,0.010206282138824463,610.1629028320312 +1769682150,940388352,4.154293060302734,0.010167181491851807,610.1642456054688 +1769682150,980020736,4.150495529174805,0.010069727897644043,610.1658935546875 +1769682151,25555712,4.147502899169922,0.010003447532653809,610.1671142578125 +1769682151,48842752,4.143340110778809,0.00991743803024292,610.1687622070312 +1769682151,73741824,4.1400885581970215,0.009847819805145264,610.1701049804688 +1769682151,110963200,4.1367316246032715,0.009771585464477539,610.1715087890625 +1769682151,143568896,4.133193016052246,0.00979381799697876,610.1731567382812 +1769682151,173761792,4.128373622894287,0.009799480438232422,610.17578125 +1769682151,207614208,4.124713897705078,0.009829521179199219,610.1778564453125 +1769682151,256293888,4.119583606719971,0.009879767894744873,610.1808471679688 +1769682151,273953792,4.1156005859375,0.009930789470672607,610.1832885742188 +1769682151,307443456,4.1115031242370605,0.009974479675292969,610.1856689453125 +1769682151,340240128,4.10732889175415,0.01003962755203247,610.18798828125 +1769682151,377947136,4.10156774520874,0.01008683443069458,610.1911010742188 +1769682151,408153856,4.097204685211182,0.010140299797058105,610.1932983398438 +1769682151,448256768,4.091022491455078,0.010226905345916748,610.1961669921875 +1769682151,474999040,4.086280822753906,0.010304629802703857,610.1981201171875 +1769682151,510131712,4.081300258636475,0.010409653186798096,610.1998901367188 +1769682151,541193472,4.07622766494751,0.01052933931350708,610.2015380859375 +1769682151,575589376,4.069199085235596,0.010637104511260986,610.2035522460938 +1769682151,607296256,4.063769817352295,0.010659992694854736,610.2049560546875 +1769682151,655239680,4.056307315826416,0.010676145553588867,610.2067260742188 +1769682151,674028544,4.050633907318115,0.010684967041015625,610.2080688476562 +1769682151,709595904,4.044864177703857,0.010692298412322998,610.2092895507812 +1769682151,741744640,4.038815975189209,0.010711252689361572,610.2105102539062 +1769682151,780445184,4.030640602111816,0.010720551013946533,610.2120971679688 +1769682151,807753728,4.024347305297852,0.01073378324508667,610.2132568359375 +1769682151,843483904,4.017888069152832,0.010766983032226562,610.2142944335938 +1769682151,875047424,4.009038925170898,0.010773539543151855,610.2156372070312 +1769682151,914775040,4.002269744873047,0.010784924030303955,610.2166748046875 +1769682151,944506368,3.9930381774902344,0.01079171895980835,610.2178344726562 +1769682151,974579968,3.9860215187072754,0.0107574462890625,610.2186889648438 +1769682152,10848000,3.9788451194763184,0.010717809200286865,610.2195434570312 +1769682152,55534592,3.968940496444702,0.010665059089660645,610.220703125 +1769682152,74032640,3.9613571166992188,0.010632812976837158,610.2215576171875 +1769682152,107223808,3.953627824783325,0.010607302188873291,610.2225341796875 +1769682152,140238080,3.9457502365112305,0.010595440864562988,610.2235107421875 +1769682152,175441920,3.9350497722625732,0.01061701774597168,610.224853515625 +1769682152,208424448,3.926842212677002,0.010687053203582764,610.2258911132812 +1769682152,244481536,3.9184508323669434,0.01078331470489502,610.2267456054688 +1769682152,274681344,3.9069395065307617,0.010920226573944092,610.2278442382812 +1769682152,308867072,3.8981809616088867,0.011027932167053223,610.2283325195312 +1769682152,341105152,3.8892035484313965,0.011143326759338379,610.228759765625 +1769682152,374084864,3.877136707305908,0.011290431022644043,610.2288818359375 +1769682152,407562496,3.867902994155884,0.011392056941986084,610.228759765625 +1769682152,444598528,3.855412006378174,0.011503040790557861,610.2282104492188 +1769682152,475884800,3.845940113067627,0.011572003364562988,610.2276611328125 +1769682152,508096768,3.8362839221954346,0.011636734008789062,610.22705078125 +1769682152,554583808,3.826418876647949,0.011690974235534668,610.2262573242188 +1769682152,574641920,3.812833786010742,0.011763811111450195,610.22509765625 +1769682152,608130304,3.802499771118164,0.011794447898864746,610.2239990234375 +1769682152,640872192,3.7919318675994873,0.011819899082183838,610.2227783203125 +1769682152,674258176,3.777663230895996,0.011859238147735596,610.220947265625 +1769682152,707463424,3.7668750286102295,0.01187354326248169,610.2192993164062 +1769682152,744723200,3.752279043197632,0.011889815330505371,610.2167358398438 +1769682152,774429440,3.74112606048584,0.01191413402557373,610.2145385742188 +1769682152,808457728,3.7297897338867188,0.011943697929382324,610.2122192382812 +1769682152,846420992,3.714541435241699,0.011997580528259277,610.2088012695312 +1769682152,874407168,3.702876329421997,0.01205211877822876,610.2060546875 +1769682152,907208192,3.6911532878875732,0.01212233304977417,610.203125 +1769682152,960151040,3.675363063812256,0.012241661548614502,610.1987915039062 +1769682152,968324352,3.6673672199249268,0.012288153171539307,610.1964111328125 +1769682153,8313344,3.6511523723602295,0.012452363967895508,610.1914672851562 +1769682153,41080576,3.6388487815856934,0.012518465518951416,610.187255859375 +1769682153,75300096,3.6222219467163086,0.012719333171844482,610.181396484375 +1769682153,111290880,3.6095967292785645,0.012852787971496582,610.1767578125 +1769682153,143523328,3.596879482269287,0.01291656494140625,610.1719970703125 +1769682153,174223104,3.5796549320220947,0.013097941875457764,610.1654663085938 +1769682153,207468544,3.56675386428833,0.01317131519317627,610.160400390625 +1769682153,259376640,3.5493357181549072,0.013243496417999268,610.1537475585938 +1769682153,274945024,3.5360107421875,0.013287007808685303,610.148681640625 +1769682153,307624448,3.5225017070770264,0.013336002826690674,610.143798828125 +1769682153,355857920,3.5042710304260254,0.013364136219024658,610.1371459960938 +1769682153,374384640,3.490471839904785,0.01337122917175293,610.1321411132812 +1769682153,408009216,3.476619243621826,0.013372659683227539,610.1270751953125 +1769682153,442157824,3.462653636932373,0.013320982456207275,610.1218872070312 +1769682153,478417664,3.443861722946167,0.013373374938964844,610.1149291992188 +1769682153,509928192,3.429675340652466,0.013371527194976807,610.109619140625 +1769682153,545704192,3.410494089126587,0.013365983963012695,610.1024780273438 +1769682153,574413824,3.3960494995117188,0.013366758823394775,610.0971069335938 +1769682153,612193792,3.381523847579956,0.01336759328842163,610.0916748046875 +1769682153,643447040,3.366849422454834,0.013324320316314697,610.0863647460938 +1769682153,675359232,3.3471243381500244,0.013403892517089844,610.0791625976562 +1769682153,707579904,3.3322315216064453,0.013432621955871582,610.0736694335938 +1769682153,758601984,3.3123881816864014,0.013464033603668213,610.06640625 +1769682153,768521216,3.3022701740264893,0.013423621654510498,610.0626831054688 +1769682153,824288512,3.281766653060913,0.01333630084991455,610.054931640625 +1769682153,843009280,3.2662739753723145,0.01316988468170166,610.0488891601562 +1769682153,875226624,3.2454111576080322,0.01313704252243042,610.04052734375 +1769682153,907272448,3.2297141551971436,0.013104557991027832,610.033935546875 +1769682153,943097600,3.213921308517456,0.013027429580688477,610.0272216796875 +1769682153,974233600,3.192803382873535,0.013100504875183105,610.0178833007812 +1769682154,25802496,3.1768457889556885,0.013103306293487549,610.0106811523438 +1769682154,56696832,3.155573606491089,0.013113081455230713,610.0010986328125 +1769682154,70071552,3.14485764503479,0.013056695461273193,609.9961547851562 +1769682154,108575488,3.1231300830841064,0.013110458850860596,609.986572265625 +1769682154,140881920,3.106722831726074,0.013048291206359863,609.9794921875 +1769682154,179867648,3.084681272506714,0.013086438179016113,609.97021484375 +1769682154,207636224,3.0681209564208984,0.013070106506347656,609.96337890625 +1769682154,242939136,3.0515472888946533,0.013000071048736572,609.9567260742188 +1769682154,275214592,3.029376983642578,0.013045132160186768,609.9480590820312 +1769682154,313399296,3.0125880241394043,0.013039588928222656,609.941650390625 +1769682154,343321088,2.9958014488220215,0.012946724891662598,609.935302734375 +1769682154,375003648,2.9732558727264404,0.013058960437774658,609.9273071289062 +1769682154,407636224,2.956357955932617,0.01317906379699707,609.9217529296875 +1769682154,448773632,2.933652639389038,0.013369441032409668,609.91455078125 +1769682154,474629632,2.916639804840088,0.013521909713745117,609.9093017578125 +1769682154,507816448,2.899543046951294,0.013669788837432861,609.9039916992188 +1769682154,540397312,2.882406711578369,0.013780653476715088,609.8985595703125 +1769682154,580105984,2.8594398498535156,0.01400679349899292,609.8910522460938 +1769682154,609966080,2.842013120651245,0.014123201370239258,609.88525390625 +1769682154,642695936,2.824591636657715,0.01415950059890747,609.8792724609375 +1769682154,675347456,2.8010873794555664,0.014275670051574707,609.87109375 +1769682154,709556992,2.783341646194458,0.014215052127838135,609.8646850585938 +1769682154,741280256,2.765533924102783,0.014069616794586182,609.8582153320312 +1769682154,774105856,2.741701126098633,0.013968557119369507,609.8494873046875 +1769682154,808598784,2.723646879196167,0.013868540525436401,609.8428344726562 +1769682154,856766720,2.699434280395508,0.013764351606369019,609.8341064453125 +1769682154,874046208,2.6811912059783936,0.013718247413635254,609.8274536132812 +1769682154,907505408,2.6628706455230713,0.013693422079086304,609.8206787109375 +1769682154,942071040,2.6445584297180176,0.013630986213684082,609.8139038085938 +1769682157,982116096,0.0,-0.0,609.8541259765625 +1769682158,7977216,0.0,-0.0,609.8541259765625 +1769682158,45611264,0.0,-0.0,609.8541259765625 +1769682158,74780928,0.0,-0.0,609.8541259765625 +1769682158,110979840,0.0,-0.0,609.8541259765625 +1769682158,150271488,0.0,-0.0,609.8541259765625 +1769682158,176170752,0.0,-0.0,609.8541259765625 +1769682158,207754752,0.0,-0.0,609.8541259765625 +1769682158,259920128,0.0,-0.0,609.8541259765625 +1769682158,269520640,0.0,-0.0,609.8541259765625 +1769682158,308075264,0.0,-0.0,609.8541259765625 +1769682158,341237760,0.0,-0.0,609.8541259765625 +1769682158,376476416,0.0,-0.0,609.8541259765625 +1769682158,411150080,0.0,-0.0,609.8541259765625 +1769682158,444909312,0.0,-0.0,609.8541259765625 +1769682158,474940416,0.0,-0.0,609.8541259765625 +1769682158,511097344,0.0,-0.0,609.8541259765625 +1769682158,545890048,0.0,-0.0,609.8541259765625 +1769682158,575280640,0.0,-0.0,609.8541259765625 +1769682158,608097024,0.0,-0.0,609.8541259765625 +1769682158,660713728,0.0,-0.0,609.8541259765625 +1769682158,668152320,0.0,-0.0,609.8541259765625 +1769682158,709788928,0.0,-0.0,609.8541259765625 +1769682158,753166080,0.0,-0.0,609.8541259765625 +1769682158,775462144,0.0,-0.0,609.8541259765625 +1769682158,801373952,0.0,-0.0,609.8541259765625 +1769682158,845110272,0.0,-0.0,609.8541259765625 +1769682158,874618880,0.0,-0.0,609.8541259765625 +1769682158,909497344,0.0,-0.0,609.8541259765625 +1769682158,956896256,0.0,-0.0,609.8541259765625 +1769682158,974360832,0.0,-0.0,609.8541259765625 +1769682159,8856320,0.0,-0.0,609.8541259765625 +1769682159,54490624,0.0,-0.0,609.8541259765625 +1769682159,75139072,0.0,-0.0,609.8541259765625 +1769682159,108480768,0.0,-0.0,609.8541259765625 +1769682159,146513152,0.0,-0.0,609.8541259765625 +1769682159,175200000,0.0,-0.0,609.8541259765625 +1769682159,209602560,0.0,-0.0,609.8541259765625 +1769682159,246182400,0.0,-0.0,609.8541259765625 +1769682159,274810880,0.0,-0.0,609.8541259765625 +1769682159,307977472,0.01646745391190052,0.002282199449837208,609.8528442382812 +1769682159,341676032,0.03290480747818947,0.003522201906889677,609.8486328125 +1769682159,375904512,0.054711904376745224,0.004959048703312874,609.8405151367188 +1769682159,409948160,0.07100990414619446,0.005990112200379372,609.8338623046875 +1769682159,455758336,0.08719686418771744,0.006970844231545925,609.8272094726562 +1769682159,475392000,0.10890986025333405,0.00814834050834179,609.8192749023438 +1769682159,508088576,0.12524712085723877,0.008904190734028816,609.8139038085938 +1769682159,549371904,0.147283673286438,0.009732630103826523,609.8073120117188 +1769682159,574764544,0.16369718313217163,0.010202677920460701,609.8029174804688 +1769682159,608636672,0.1799885779619217,0.010559998452663422,609.7985229492188 +1769682159,647462656,0.20200471580028534,0.010872066020965576,609.7929077148438 +1769682159,674899200,0.21894554793834686,0.011007867753505707,609.7885131835938 +1769682159,709126400,0.236598938703537,0.011078529059886932,609.7838134765625 +1769682159,744195584,0.25536221265792847,0.011098340153694153,609.77880859375 +1769682159,776418048,0.28082194924354553,0.011094525456428528,609.7715454101562 +1769682159,808638208,0.29986998438835144,0.011066999286413193,609.7656860351562 +1769682159,844850176,0.3273927569389343,0.011023081839084625,609.7572021484375 +1769682159,874690304,0.34844765067100525,0.01099368929862976,609.75048828125 +1769682159,908705792,0.370537668466568,0.010978929698467255,609.743408203125 +1769682159,942390784,0.3931029736995697,0.010969884693622589,609.7359619140625 +1769682159,975007232,0.4242825508117676,0.010989420115947723,609.7254028320312 +1769682160,10759936,0.44760531187057495,0.011018015444278717,609.7171630859375 +1769682160,43973632,0.48024895787239075,0.01107625663280487,609.70556640625 +1769682160,74629888,0.5048568844795227,0.011134237051010132,609.696533203125 +1769682160,107990016,0.530433177947998,0.0112062469124794,609.6871337890625 +1769682160,142672640,0.5565781593322754,0.011269040405750275,609.6773071289062 +1769682160,176081408,0.591789960861206,0.01140543818473816,609.66357421875 +1769682160,208673280,0.6183471083641052,0.01150195300579071,609.6527709960938 +1769682160,255010816,0.6451399922370911,0.011579707264900208,609.6416625976562 +1769682160,275375104,0.6812154054641724,0.011712424457073212,609.6261596679688 +1769682160,311536896,0.7084360122680664,0.011777892708778381,609.6140747070312 +1769682160,342540544,0.7362242937088013,0.011827915906906128,609.6014404296875 +1769682160,374998784,0.7709525227546692,0.011938661336898804,609.5840454101562 +1769682160,408814592,0.7949067950248718,0.011979565024375916,609.5707397460938 +1769682160,445470976,0.827975869178772,0.01203659176826477,609.5529174804688 +1769682160,475069440,0.8540663719177246,0.012073129415512085,609.5391235351562 +1769682160,508422144,0.880544126033783,0.01211501657962799,609.5250244140625 +1769682160,560755200,0.916264533996582,0.01216837763786316,609.5055541992188 +1769682160,569861376,0.9342669248580933,0.012174814939498901,609.49560546875 +1769682160,609225216,0.9705340266227722,0.012247473001480103,609.4754638671875 +1769682160,657721600,0.9979514479637146,0.012238562107086182,609.4598999023438 +1769682160,674695168,1.0340549945831299,0.012331604957580566,609.4389038085938 +1769682160,709295872,1.059652328491211,0.012363553047180176,609.423095703125 +1769682160,741261312,1.0858134031295776,0.012344449758529663,609.4072265625 +1769682160,775015168,1.1216702461242676,0.012425631284713745,609.3858032226562 +1769682160,808281856,1.1486177444458008,0.012446701526641846,609.36962890625 +1769682160,842105856,1.1757131814956665,0.01240547001361847,609.3533325195312 +1769682160,874878720,1.2120839357376099,0.012464761734008789,609.3314819335938 +1769682160,910625280,1.239471197128296,0.012469083070755005,609.3148803710938 +1769682160,959722240,1.2762112617492676,0.012463688850402832,609.292724609375 +1769682160,974626560,1.303755283355713,0.012461289763450623,609.2760009765625 +1769682161,8751872,1.3311381340026855,0.012460440397262573,609.25927734375 +1769682161,55447296,1.3581188917160034,0.01241368055343628,609.2424926757812 +1769682161,76645632,1.3921279907226562,0.012538939714431763,609.2200317382812 +1769682161,108696064,1.4175803661346436,0.012601912021636963,609.203125 +1769682161,145705728,1.450742483139038,0.012693285942077637,609.1802978515625 +1769682161,175143936,1.4762427806854248,0.012761682271957397,609.1629638671875 +1769682161,211955712,1.5022491216659546,0.012817680835723877,609.1453857421875 +1769682161,247956480,1.5370653867721558,0.012861132621765137,609.12158203125 +1769682161,274866432,1.5630992650985718,0.012862145900726318,609.1036376953125 +1769682161,308525056,1.5889863967895508,0.012852966785430908,609.0856323242188 +1769682161,346327808,1.6237523555755615,0.01282164454460144,609.061767578125 +1769682161,376724480,1.649837613105774,0.012782573699951172,609.0438842773438 +1769682161,408233728,1.6760351657867432,0.01273927092552185,609.0261840820312 +1769682161,455304448,1.7022013664245605,0.012616991996765137,609.0084838867188 +1769682161,476551680,1.736817479133606,0.012648016214370728,608.9850463867188 +1769682161,510056960,1.7626832723617554,0.012602001428604126,608.9675903320312 +1769682161,542497024,1.7886300086975098,0.012419551610946655,608.9501953125 +1769682161,575408640,1.8229920864105225,0.012394577264785767,608.927001953125 +1769682161,609777152,1.8488481044769287,0.012311547994613647,608.90966796875 +1769682161,643502592,1.874475359916687,0.012140631675720215,608.892333984375 +1769682161,675189248,1.9085307121276855,0.012136220932006836,608.8693237304688 +1769682161,713743872,1.9340606927871704,0.012086570262908936,608.8521118164062 +1769682161,747100416,1.96803617477417,0.012460947036743164,608.8284912109375 +1769682161,775427328,1.9934505224227905,0.012623369693756104,608.8095092773438 +1769682161,810949120,2.018716812133789,0.012852996587753296,608.789306640625 +1769682161,855930112,2.0523219108581543,0.013163000345230103,608.7610473632812 +1769682161,877524736,2.0774264335632324,0.013383686542510986,608.7389526367188 +1769682161,909005568,2.1023244857788086,0.013567745685577393,608.7164916992188 +1769682161,941321728,2.1273367404937744,0.013577520847320557,608.693603515625 +1769682161,978339072,2.160439968109131,0.013830244541168213,608.6629028320312 +1769682162,9884928,2.1850132942199707,0.01387721300125122,608.6398315429688 +1769682162,53231104,2.217526912689209,0.013905256986618042,608.609130859375 +1769682162,75261952,2.2417376041412354,0.01390048861503601,608.5863037109375 +1769682162,111545088,2.2658398151397705,0.013882935047149658,608.5635986328125 +1769682162,149219840,2.297828197479248,0.013843894004821777,608.5333862304688 +1769682162,176237824,2.3217642307281494,0.013829171657562256,608.5108032226562 +1769682162,208897536,2.345494270324707,0.01382705569267273,608.4882202148438 +1769682162,257341440,2.3767762184143066,0.01386365294456482,608.4579467773438 +1769682162,274774272,2.399993896484375,0.013914406299591064,608.4349975585938 +1769682162,308610816,2.4230360984802246,0.013965129852294922,608.411865234375 +1769682162,342314496,2.445993185043335,0.013848066329956055,608.388427734375 +1769682162,376720640,2.4763052463531494,0.014042645692825317,608.3568725585938 +1769682162,408786176,2.4989757537841797,0.01403820514678955,608.3331298828125 +1769682162,441836032,2.521449327468872,0.013844996690750122,608.3093872070312 +1769682162,475535616,2.551119089126587,0.014005392789840698,608.2782592773438 +1769682162,509939456,2.573093891143799,0.01400226354598999,608.2553100585938 +1769682162,546019328,2.602012872695923,0.013974249362945557,608.2251586914062 +1769682162,575945728,2.6234090328216553,0.014230966567993164,608.2030029296875 +1769682162,611579648,2.6446731090545654,0.014332413673400879,608.1815795898438 +1769682162,655239680,2.672837257385254,0.014872431755065918,608.1549072265625 +1769682162,675508224,2.693711280822754,0.015173733234405518,608.1364135742188 +1769682162,710067200,2.7143514156341553,0.015458464622497559,608.1187133789062 +1769682162,754880768,2.7348527908325195,0.015597999095916748,608.1016845703125 +1769682162,776077312,2.7620017528533936,0.01591724157333374,608.07958984375 +1769682162,810889472,2.782087802886963,0.016011297702789307,608.063232421875 +1769682162,844334848,2.8084208965301514,0.016093790531158447,608.0415649414062 +1769682162,874977536,2.828080415725708,0.01613539457321167,608.025390625 +1769682162,910836224,2.8475472927093506,0.016157984733581543,608.0091552734375 +1769682162,946242304,2.8730454444885254,0.016182422637939453,607.987548828125 +1769682162,975181568,2.8920109272003174,0.016217529773712158,607.97119140625 +1769682163,8354304,2.9107143878936768,0.016258060932159424,607.9546508789062 +1769682163,43105280,2.929169178009033,0.01614069938659668,607.9379272460938 +1769682163,76742400,2.953425168991089,0.016383588314056396,607.9152221679688 +1769682163,110369280,2.9715118408203125,0.016444146633148193,607.8978881835938 +1769682163,153450240,2.9892659187316895,0.016354024410247803,607.8802490234375 +1769682163,175597312,3.0128273963928223,0.016579627990722656,607.8563232421875 +1769682163,209175040,3.0301272869110107,0.016660749912261963,607.8381958007812 +1769682163,242917888,3.0473222732543945,0.016544103622436523,607.8198852539062 +1769682163,275949056,3.07014799118042,0.016532599925994873,607.7953491210938 +1769682163,308663040,3.0871262550354004,0.016357243061065674,607.7769165039062 +1769682163,341902336,3.103726387023926,0.016025424003601074,607.7583618164062 +1769682163,375122176,3.125554323196411,0.0160028338432312,607.7337036132812 +1769682163,410674688,3.1418497562408447,0.015874624252319336,607.7150268554688 +1769682163,447184896,3.1632580757141113,0.015797972679138184,607.6900024414062 +1769682163,476054784,3.1792707443237305,0.015816152095794678,607.6710815429688 +1769682163,510028800,3.195176839828491,0.0158500075340271,607.6519165039062 +1769682163,554732032,3.2109549045562744,0.015700101852416992,607.6326293945312 +1769682163,577157120,3.231785774230957,0.01594299077987671,607.6066284179688 +1769682163,610450176,3.2470571994781494,0.015986323356628418,607.587158203125 +1769682163,643133952,3.262247323989868,0.015829622745513916,607.5675659179688 +1769682163,675111936,3.2822277545928955,0.016084790229797363,607.5414428710938 +1769682163,711432704,3.297149419784546,0.016127347946166992,607.5218505859375 +1769682163,752929280,3.3166940212249756,0.01619243621826172,607.49560546875 +1769682163,775144448,3.3312554359436035,0.0162506103515625,607.4757690429688 +1769682163,808502528,3.3457438945770264,0.016315102577209473,607.4557495117188 +1769682163,855909376,3.3649446964263916,0.01636403799057007,607.428955078125 +1769682163,876311296,3.3791770935058594,0.016524910926818848,607.408935546875 +1769682163,910883072,3.3932409286499023,0.016732215881347656,607.388916015625 +1769682163,942364416,3.4071474075317383,0.01673710346221924,607.3689575195312 +1769682163,979011328,3.425553798675537,0.017170369625091553,607.3424072265625 +1769682164,8772608,3.4391748905181885,0.017312586307525635,607.322509765625 +1769682164,42528512,3.452681064605713,0.017225682735443115,607.3025512695312 +1769682164,76221696,3.4702377319335938,0.017589271068572998,607.2764282226562 +1769682164,110121728,3.483264446258545,0.017532944679260254,607.2567749023438 +1769682164,154144768,3.5004780292510986,0.01728212833404541,607.2302856445312 +1769682164,175317760,3.5132572650909424,0.017062067985534668,607.210205078125 +1769682164,211817984,3.525886297225952,0.016844332218170166,607.1898803710938 +1769682164,262412288,3.5424458980560303,0.016557395458221436,607.16259765625 +1769682164,269716224,3.5506670475006104,0.01629239320755005,607.14892578125 +1769682164,308942336,3.566924571990967,0.016193270683288574,607.12158203125 +1769682164,355304704,3.5790538787841797,0.015842020511627197,607.1008911132812 +1769682164,376931840,3.5950329303741455,0.015932857990264893,607.0734252929688 +1769682164,409449984,3.606674909591675,0.015972435474395752,607.0527954101562 +1769682164,442369792,3.6178481578826904,0.016072750091552734,607.0320434570312 +1769682164,475657728,3.632627010345459,0.01642298698425293,607.0037841796875 +1769682164,511329792,3.6437196731567383,0.01611393690109253,606.9818725585938 +1769682164,543739136,3.654733657836914,0.015419483184814453,606.959716796875 +1769682164,575518720,3.6691198348999023,0.015093743801116943,606.9293823242188 +1769682164,609801216,3.6798341274261475,0.014673113822937012,606.90625 +1769682164,653457152,3.6940035820007324,0.014105081558227539,606.8751220703125 +1769682164,676336128,3.704512119293213,0.01384824514389038,606.8517456054688 +1769682164,708782336,3.7148847579956055,0.01367419958114624,606.8284912109375 +1769682164,758854656,3.7285518646240234,0.013523995876312256,606.7977294921875 +1769682164,775134720,3.738670825958252,0.013479650020599365,606.7749633789062 +1769682164,809029632,3.7486586570739746,0.013517439365386963,606.7523193359375 +1769682164,841892608,3.7585277557373047,0.013386428356170654,606.7296142578125 +1769682164,877624320,3.7715110778808594,0.01389080286026001,606.69873046875 +1769682164,910970368,3.781156063079834,0.014071226119995117,606.6749877929688 +1769682164,943282944,3.7905871868133545,0.013885974884033203,606.6508178710938 +1769682164,976139776,3.8030667304992676,0.014117419719696045,606.618408203125 +1769682165,8775936,3.8123199939727783,0.013984918594360352,606.5945434570312 +1769682165,43683328,3.821629762649536,0.013856828212738037,606.5717163085938 +1769682165,75913472,3.8339316844940186,0.014841139316558838,606.5426025390625 +1769682165,110402304,3.842961311340332,0.015552222728729248,606.5209350585938 +1769682165,161769984,3.854459762573242,0.01662057638168335,606.4910888671875 +1769682165,169584896,3.859811782836914,0.017272114753723145,606.4756469726562 +1769682165,209779456,3.870436906814575,0.018529832363128662,606.443115234375 +1769682165,255425536,3.87848162651062,0.018391847610473633,606.417236328125 +1769682165,275850752,3.889073610305786,0.01820695400238037,606.3804931640625 +1769682165,309037056,3.896923542022705,0.017592549324035645,606.3522338867188 +1769682165,341874176,3.9047048091888428,0.01656949520111084,606.3240356445312 +1769682165,378570240,3.914886474609375,0.01588970422744751,606.2872314453125 +1769682165,409351424,3.922304391860962,0.015193521976470947,606.2604370117188 +1769682165,442383616,3.9296960830688477,0.014281749725341797,606.234375 +1769682165,475247616,3.9391672611236572,0.014080047607421875,606.2006225585938 +1769682165,508638208,3.9459543228149414,0.01391756534576416,606.1759033203125 +1769682165,546741248,3.954793691635132,0.013604342937469482,606.1428833007812 +1769682165,576824064,3.9614431858062744,0.013301491737365723,606.1182250976562 +1769682165,610749184,3.9681649208068848,0.012712299823760986,606.0936279296875 +1769682165,657160448,3.9769973754882812,0.011574089527130127,606.0613403320312 +1769682165,676114944,3.983494997024536,0.010719001293182373,606.0375366210938 +1769682165,711693568,3.9898715019226074,0.009911835193634033,606.0142211914062 +1769682165,742373120,3.9963440895080566,0.00879216194152832,605.9915771484375 +1769682165,777067520,4.004955768585205,0.008532822132110596,605.9623413085938 +1769682165,809374976,4.011302947998047,0.008350253105163574,605.9413452148438 +1769682165,842765056,4.017592430114746,0.008020997047424316,605.9212036132812 +1769682165,875763200,4.025821685791016,0.008205175399780273,605.8953857421875 +1769682165,911261440,4.031863212585449,0.008227705955505371,605.876953125 +1769682165,951361280,4.039773941040039,0.008290410041809082,605.8530883789062 +1769682165,975710720,4.0455522537231445,0.008346140384674072,605.8355712890625 +1769682166,11572224,4.05123233795166,0.008401691913604736,605.8184814453125 +1769682166,56633344,4.058640480041504,0.008457183837890625,605.7960815429688 +1769682166,76251392,4.064072132110596,0.00848078727722168,605.7794799804688 +1769682166,108980224,4.069640159606934,0.008458733558654785,605.7634887695312 +1769682166,142361600,4.075040340423584,0.008735120296478271,605.748779296875 +1769682166,177635584,4.0816144943237305,0.009840726852416992,605.73095703125 +1769682166,209591808,4.086211204528809,0.01051020622253418,605.71875 +1769682166,243649280,4.090724468231201,0.010831773281097412,605.7072143554688 +1769682166,275504384,4.0966410636901855,0.011296272277832031,605.6926879882812 +1769682166,315288832,4.101154327392578,0.010915040969848633,605.6815795898438 +1769682166,350299392,4.106945514678955,0.01003497838973999,605.6659545898438 +1769682166,375956224,4.111240386962891,0.009320616722106934,605.6537475585938 +1769682166,409647616,4.115447521209717,0.008620381355285645,605.641357421875 +1769682166,464290816,4.1207380294799805,0.007775425910949707,605.6246948242188 +1769682166,473918464,4.12328577041626,0.007240235805511475,605.6162109375 +1769682166,511500288,4.128195285797119,0.006797671318054199,605.5993041992188 +1769682166,542010624,4.131783962249756,0.0062334537506103516,605.5867309570312 +1769682166,575883520,4.136383533477783,0.0059326887130737305,605.5699462890625 +1769682166,609088512,4.139754772186279,0.005659699440002441,605.5576782226562 +1769682166,656256256,4.144172668457031,0.005130350589752197,605.5416870117188 +1769682166,675736832,4.147459506988525,0.004452943801879883,605.5302124023438 +1769682166,708915968,4.150649547576904,0.0037741661071777344,605.51904296875 +1769682166,757613568,4.154653549194336,0.002956867218017578,605.5046997070312 +1769682166,778890496,4.157773494720459,0.0022693872451782227,605.4942016601562 +1769682166,809025792,4.160900115966797,0.002098977565765381,605.48388671875 +1769682166,854143488,4.163904666900635,0.0020659565925598145,605.4739379882812 +1769682166,876664064,4.167781352996826,0.0024036765098571777,605.4612426757812 +1769682166,911178496,4.170591354370117,0.002604663372039795,605.4520263671875 +1769682166,943397888,4.173277378082275,0.0027047395706176758,605.4432373046875 +1769682166,975448832,4.176661968231201,0.003102123737335205,605.4318237304688 +1769682167,10996992,4.17912483215332,0.0032912492752075195,605.4234619140625 +1769682167,46495232,4.182202339172363,0.0034893155097961426,605.41259765625 +1769682167,76765184,4.184439182281494,0.0035952329635620117,605.404541015625 +1769682167,108891648,4.1866044998168945,0.003665030002593994,605.3966064453125 +1769682167,216501504,4.189613342285156,0.0037837624549865723,605.38671875 +1769682167,219961856,4.191899299621582,0.004238307476043701,605.3803100585938 +1769682167,226019584,4.193922519683838,0.004730403423309326,605.374755859375 +1769682167,253851904,4.1963791847229,0.0052964091300964355,605.3682250976562 +1769682167,272318720,4.197574615478516,0.005477786064147949,605.365234375 +1769682167,309945856,4.2000651359558105,0.005747973918914795,605.3597412109375 +1769682167,359183616,4.202544212341309,0.005275428295135498,605.3536987304688 +1769682167,376461056,4.204288482666016,0.004765927791595459,605.3486328125 +1769682167,409652480,4.205924987792969,0.00424426794052124,605.3433227539062 +1769682167,466672128,4.2080817222595215,0.0034992098808288574,605.3357543945312 +1769682167,476687872,4.209626197814941,0.003019869327545166,605.329833984375 +1769682167,508968192,4.211029052734375,0.0026396512985229492,605.3236694335938 +1769682167,546926080,4.212737560272217,0.0022333264350891113,605.3153076171875 +1769682167,576115200,4.213977813720703,0.0019965171813964844,605.3088989257812 +1769682167,609975296,4.21515417098999,0.001811981201171875,605.302490234375 +1769682167,647975936,4.216501712799072,0.0015993118286132812,605.2939453125 +1769682167,675715584,4.217456340789795,0.0013436079025268555,605.2876586914062 +1769682167,710079744,4.218306064605713,0.000998079776763916,605.2816162109375 +1769682167,768191744,4.219366073608398,0.0005605816841125488,605.273681640625 +1769682167,777322752,4.220128059387207,0.00027239322662353516,605.2680053710938 +1769682167,810837248,4.2209978103637695,-5.328655242919922e-05,605.2622680664062 +1769682167,855515904,4.2217817306518555,3.933906555175781e-06,605.2567138671875 +1769682167,876781312,4.22272253036499,0.00039827823638916016,605.2495727539062 +1769682167,910271232,4.223363876342773,0.0006633400917053223,605.244384765625 +1769682167,942560256,4.223821640014648,0.0008545517921447754,605.2393798828125 +1769682167,976292096,4.2243218421936035,0.0012028813362121582,605.2329711914062 +1769682168,10395904,4.224603652954102,0.001387953758239746,605.2284545898438 +1769682168,55503104,4.22480583190918,0.0015845894813537598,605.2225952148438 +1769682168,76695808,4.224925994873047,0.0016949772834777832,605.21826171875 +1769682168,109339136,4.225022792816162,0.001690506935119629,605.214111328125 +1769682168,156478208,4.225149154663086,0.0016532540321350098,605.20849609375 +1769682168,178605056,4.225240707397461,0.0018288493156433105,605.2048950195312 +1769682168,209070080,4.225282192230225,0.0020862817764282227,605.2015991210938 +1769682168,256652800,4.225193977355957,0.002307713031768799,605.1985473632812 +1769682168,292739840,4.2250237464904785,0.0026502609252929688,605.1950073242188 +1769682168,302810368,4.224889755249023,0.002747952938079834,605.1932983398438 +1769682168,345812224,4.224626541137695,0.0027331113815307617,605.1890258789062 +1769682168,375990784,4.224610805511475,0.0024598240852355957,605.18603515625 +1769682168,409364480,4.224783420562744,0.0018555521965026855,605.1826171875 +1769682168,442707456,4.224981307983398,0.0014551281929016113,605.178955078125 +1769682168,476308736,4.225281715393066,0.001201629638671875,605.1739501953125 +1769682168,510298624,4.225478649139404,0.0010368824005126953,605.1702270507812 +1769682168,545837824,4.225631237030029,0.0008813142776489258,605.1651000976562 +1769682168,576949504,4.225712776184082,0.0007950067520141602,605.1612548828125 +1769682168,609033728,4.225707530975342,0.000736534595489502,605.1574096679688 +1769682168,655070976,4.225661277770996,0.0006511807441711426,605.1536254882812 +1769682168,676261376,4.2255048751831055,0.0007179975509643555,605.148681640625 +1769682168,709504000,4.225235462188721,0.0008380413055419922,605.1450805664062 +1769682168,742473984,4.224941730499268,0.0009337663650512695,605.1414184570312 +1769682168,776783616,4.224538326263428,0.0011508464813232422,605.1369018554688 +1769682168,809430784,4.224174499511719,0.0011872649192810059,605.133544921875 +1769682168,842266624,4.223843574523926,0.0013611316680908203,605.13037109375 +1769682168,876441344,4.223463535308838,0.0017818808555603027,605.126220703125 +1769682168,909451264,4.222967147827148,0.0020515918731689453,605.123291015625 +1769682168,958291456,4.222324848175049,0.0023670196533203125,605.1194458007812 +1769682168,975666432,4.221876621246338,0.0025766491889953613,605.1166381835938 +1769682169,9710080,4.221271514892578,0.002750873565673828,605.1138305664062 +1769682169,44014592,4.220566272735596,0.002782762050628662,605.1097412109375 +1769682169,76231680,4.220324516296387,0.0025765299797058105,605.1062622070312 +1769682169,109955072,4.219885349273682,0.0025963187217712402,605.1027221679688 +1769682169,154535168,4.219212532043457,0.002710700035095215,605.0977172851562 +1769682169,176121344,4.218597888946533,0.0027534961700439453,605.0938720703125 +1769682169,209342976,4.217944145202637,0.002710998058319092,605.0895385742188 +1769682169,247121664,4.216921329498291,0.002601146697998047,605.0836791992188 +1769682169,276094720,4.216048240661621,0.002504587173461914,605.0792846679688 +1769682169,309453824,4.215079307556152,0.002391993999481201,605.0748291015625 +1769682169,360999680,4.214270114898682,0.0017154812812805176,605.0690307617188 +1769682169,370523648,4.213925838470459,0.0014687776565551758,605.0662841796875 +1769682169,409186304,4.213191032409668,0.0015097260475158691,605.0615234375 +1769682169,456848896,4.212314128875732,0.001699686050415039,605.0575561523438 +1769682169,475683328,4.211681842803955,0.0018960833549499512,605.0550537109375 +1769682169,510119424,4.210983753204346,0.002110898494720459,605.0526733398438 +1769682169,542387456,4.210296154022217,0.002304255962371826,605.0503540039062 +1769682169,577922816,4.209407329559326,0.002608060836791992,605.0473022460938 +1769682169,609856512,4.208688735961914,0.0027875304222106934,605.0448608398438 +1769682169,657690368,4.207954406738281,0.0028975605964660645,605.0422973632812 +1769682169,671089920,4.20728874206543,0.0030108094215393066,605.039794921875 +1769682169,712525824,4.206165790557861,0.003569483757019043,605.0361938476562 +1769682169,749297152,4.204980850219727,0.004239916801452637,605.032470703125 +1769682169,779048704,4.204057693481445,0.004682004451751709,605.0298461914062 +1769682169,810379264,4.203120231628418,0.005056917667388916,605.0274047851562 +1769682169,861442560,4.20176362991333,0.005417883396148682,605.0244750976562 +1769682169,869378048,4.201076030731201,0.005479753017425537,605.0231323242188 +1769682169,909176832,4.199666500091553,0.005564749240875244,605.0208740234375 +1769682169,942587904,4.198604106903076,0.00555497407913208,605.0194702148438 +1769682169,976310784,4.197345733642578,0.005535483360290527,605.017822265625 +1769682170,9572096,4.196860313415527,0.004955291748046875,605.0162963867188 +1769682170,47110912,4.196561813354492,0.004457533359527588,605.0138549804688 +1769682170,76017408,4.1963791847229,0.004368484020233154,605.0122680664062 +1769682170,109499392,4.19611120223999,0.004342257976531982,605.0106201171875 +1769682170,145673728,4.195794582366943,0.004320919513702393,605.0086059570312 +1769682170,176767232,4.195420742034912,0.004360795021057129,605.0072631835938 +1769682170,210073856,4.194973468780518,0.004019618034362793,605.0054931640625 +1769682170,256498432,4.194491863250732,0.003545820713043213,605.003662109375 +1769682170,276402176,4.194159507751465,0.002803325653076172,605.0013427734375 +1769682170,312155136,4.194515705108643,0.001540541648864746,604.9994506835938 +1769682170,343028736,4.194782733917236,0.0009941458702087402,604.998046875 +1769682170,375945216,4.194957733154297,0.0011309981346130371,604.9977416992188 +1769682170,409362432,4.195094585418701,0.0015230774879455566,604.9986572265625 +1769682170,445015296,4.195223331451416,0.0021788477897644043,605.0009155273438 +1769682170,476913408,4.1952385902404785,0.0026941299438476562,605.0032348632812 +1769682170,510909440,4.1952128410339355,0.0031937360763549805,605.0056762695312 +1769682170,558502400,4.1950836181640625,0.003795623779296875,605.0093383789062 +1769682170,578579200,4.194924831390381,0.004169106483459473,605.0120239257812 +1769682170,609623552,4.194722652435303,0.0044754743576049805,605.0148315429688 +1769682170,646128640,4.194478988647461,0.004723668098449707,605.0186767578125 +1769682170,677475072,4.194291591644287,0.004792451858520508,605.0218505859375 +1769682170,710125824,4.193841457366943,0.005122363567352295,605.0253295898438 +1769682170,744403712,4.193215847015381,0.005889177322387695,605.0303955078125 +1769682170,776105216,4.192746639251709,0.0064544677734375,605.0347290039062 +1769682170,809392128,4.192262649536133,0.00695425271987915,605.0396728515625 +1769682170,849814272,4.19143009185791,0.007564961910247803,605.046875 +1769682170,876555264,4.190777778625488,0.0076146721839904785,605.0526733398438 +1769682170,909741312,4.190115928649902,0.007535338401794434,605.0588989257812 +1769682170,949810688,4.18975830078125,0.007103383541107178,605.0670776367188 +1769682170,976647424,4.190204620361328,0.006159365177154541,605.0725708007812 +1769682171,10811648,4.190664291381836,0.0058095455169677734,605.0780639648438 +1769682171,55583744,4.191123962402344,0.005743622779846191,605.08349609375 +1769682171,76695808,4.191732883453369,0.005620360374450684,605.0906982421875 +1769682171,110183424,4.1922125816345215,0.005575120449066162,605.0960083007812 +1769682171,142605056,4.192691802978516,0.005570054054260254,605.1015625 +1769682171,176645632,4.1932454109191895,0.005389153957366943,605.1097412109375 +1769682171,209741056,4.193506240844727,0.0050550103187561035,605.1161499023438 +1769682171,243605760,4.193948268890381,0.00435715913772583,605.1223754882812 +1769682171,276139776,4.194774150848389,0.0029366612434387207,605.1309204101562 +1769682171,310978048,4.1954240798950195,0.0022066831588745117,605.1378784179688 +1769682171,357625600,4.196270942687988,0.0014250874519348145,605.1481323242188 +1769682171,376086272,4.196633338928223,0.0014133453369140625,605.1565551757812 +1769682171,409731072,4.197011947631836,0.0017868280410766602,605.1663818359375 +1769682171,459066880,4.197391986846924,0.0024431943893432617,605.1771240234375 +1769682171,476255744,4.197926998138428,0.003038167953491211,605.1923828125 +1769682171,511262976,4.1983208656311035,0.003571629524230957,605.204345703125 +1769682171,550855680,4.198841094970703,0.0041887760162353516,605.220947265625 +1769682171,576390656,4.1992316246032715,0.0045607686042785645,605.2337036132812 +1769682171,609967616,4.199616432189941,0.00484853982925415,605.2467651367188 +1769682171,647189248,4.200138568878174,0.00506669282913208,605.264892578125 +1769682171,676244736,4.200520038604736,0.005090117454528809,605.2791137695312 +1769682171,709719552,4.200843811035156,0.0051056742668151855,605.2939453125 +1769682171,743129600,4.201050281524658,0.005643486976623535,605.3095703125 +1769682171,776311552,4.20133113861084,0.00600588321685791,605.331298828125 +1769682171,810522368,4.201540946960449,0.006408393383026123,605.3485107421875 +1769682171,856782080,4.201646327972412,0.007116436958312988,605.3660888671875 +1769682171,876131840,4.201488971710205,0.007109940052032471,605.3902587890625 +1769682171,909635328,4.2016472816467285,0.006739437580108643,605.4085693359375 +1769682171,946632448,4.2020463943481445,0.006134450435638428,605.4326782226562 +1769682171,977008128,4.202333450317383,0.005833268165588379,605.4506225585938 +1769682172,1249024,4.20252799987793,0.005860269069671631,605.4625244140625 +1769682172,42846464,4.202915668487549,0.005543947219848633,605.486328125 +1769682172,76678400,4.203284740447998,0.004993081092834473,605.5103149414062 +1769682172,109752576,4.203553199768066,0.004746615886688232,605.5286254882812 +1769682172,154147328,4.203906059265137,0.0044078826904296875,605.5536499023438 +1769682172,176628480,4.204085350036621,0.004148125648498535,605.5731811523438 +1769682172,209740544,4.203761577606201,0.0042269229888916016,605.5933227539062 +1769682172,244307968,4.203226089477539,0.0035543441772460938,605.6201782226562 +1769682172,276072448,4.202831268310547,0.0028968453407287598,605.6403198242188 +1769682172,312555008,4.202444076538086,0.0022676587104797363,605.6605224609375 +1769682172,347821056,4.201928615570068,0.0015376806259155273,605.687744140625 +1769682172,376439808,4.2013936042785645,0.0012648701667785645,605.708251953125 +1769682172,409697536,4.200786113739014,0.0014243125915527344,605.7295532226562 +1769682172,445448704,4.200007438659668,0.0020357370376586914,605.7588500976562 +1769682172,477302272,4.19943380355835,0.0026708245277404785,605.78076171875 +1769682172,510051840,4.198883056640625,0.003204047679901123,605.8021850585938 +1769682172,545888512,4.198160171508789,0.0037874579429626465,605.8307495117188 +1769682172,579296512,4.19761848449707,0.004122138023376465,605.852294921875 +1769682172,610674176,4.197103500366211,0.0043572187423706055,605.874267578125 +1769682172,646012160,4.196437358856201,0.004532217979431152,605.9044189453125 +1769682172,676626688,4.195955276489258,0.00457531213760376,605.9278564453125 +1769682172,711267072,4.195490837097168,0.004575252532958984,605.9519653320312 +1769682172,744817408,4.1948652267456055,0.0046073198318481445,605.9852905273438 +1769682172,776653824,4.194415092468262,0.004634559154510498,606.0110473632812 +1769682172,809842432,4.193978786468506,0.004652798175811768,606.0372314453125 +1769682172,846806528,4.193197727203369,0.004790663719177246,606.0728759765625 +1769682172,879525376,4.1920695304870605,0.005034267902374268,606.1002197265625 +1769682172,910912000,4.1909637451171875,0.0047591328620910645,606.1279296875 +1769682172,955177728,4.189539909362793,0.004170596599578857,606.1651000976562 +1769682172,976898304,4.188499450683594,0.003631293773651123,606.1931762695312 +1769682173,9910272,4.187480449676514,0.003080606460571289,606.2216796875 +1769682173,55416576,4.186480522155762,0.0029114484786987305,606.2508544921875 +1769682173,76962560,4.185153961181641,0.0017297863960266113,606.2909545898438 +1769682173,111340288,4.184185028076172,0.0011767148971557617,606.322265625 +1769682173,147098112,4.183036804199219,0.001477658748626709,606.3663940429688 +1769682173,176600832,4.181934833526611,0.0017324090003967285,606.4013061523438 +1769682173,209703680,4.180844306945801,0.0016500353813171387,606.437255859375 +1769682173,244343808,4.179785251617432,0.001990795135498047,606.4741821289062 +1769682173,276423680,4.178404808044434,0.0012607574462890625,606.5248413085938 +1769682173,309473280,4.177392482757568,0.0010908842086791992,606.5636596679688 +1769682173,343972864,4.176416873931885,0.0014830231666564941,606.603271484375 +1769682173,376344320,4.175121784210205,0.0007944107055664062,606.656982421875 +1769682173,410858240,4.17415714263916,0.0007854104042053223,606.697998046875 +1769682173,457293568,4.173208713531494,0.0013499855995178223,606.7393798828125 +1769682173,478695424,4.171974182128906,0.0008241534233093262,606.7953491210938 +1769682173,511089920,4.171082973480225,0.0008003115653991699,606.8377685546875 +1769682173,542925312,4.170224666595459,0.0013102889060974121,606.880859375 +1769682173,577230080,4.169102668762207,0.0006340146064758301,606.93896484375 +1769682173,609632512,4.168271541595459,0.0005499720573425293,606.9833374023438 +1769682173,646193152,4.167211055755615,0.00041985511779785156,607.0432739257812 +1769682173,676575744,4.166425704956055,0.0003160238265991211,607.0888671875 +1769682173,710830336,4.165666103363037,0.00022876262664794922,607.1348266601562 +1769682173,757204224,4.164690017700195,0.00015842914581298828,607.1966552734375 +1769682173,776704256,4.163981914520264,0.00012999773025512695,607.2432250976562 +1769682173,809576960,4.1634674072265625,0.000459134578704834,607.2902221679688 +1769682173,853161984,4.162270545959473,0.0010411739349365234,607.3539428710938 +1769682173,877135360,4.161383628845215,0.0011022686958312988,607.4019165039062 +1769682173,910290432,4.160515785217285,0.0010826587677001953,607.4498901367188 +1769682173,942746880,4.159675598144531,0.0016461014747619629,607.4979858398438 +1769682173,980207360,4.158583641052246,0.0008639097213745117,607.5621337890625 +1769682174,10987776,4.157785415649414,0.0007273554801940918,607.6104125976562 +1769682174,44133120,4.157160758972168,0.0014110207557678223,607.658935546875 +1769682174,76846080,4.156529903411865,0.0013123154640197754,607.7238159179688 +1769682175,12279296,4.150117874145508,0.008500933647155762,609.1473999023438 +1769682175,81367552,4.144186496734619,0.008262932300567627,609.2015380859375 +1769682175,84209152,4.13884973526001,0.007888734340667725,609.2415161132812 +1769682175,127165440,4.131182670593262,0.007477164268493652,609.2811889648438 +1769682175,158300928,4.119405746459961,0.006925821304321289,609.3338012695312 +1769682175,168249600,4.112438201904297,0.006880819797515869,609.3599853515625 +1769682175,210708224,4.096336364746094,0.006213843822479248,609.412109375 +1769682175,242914048,4.083091735839844,0.006422281265258789,609.4511108398438 +1769682175,278121216,4.063271999359131,0.005633831024169922,609.5029907226562 +1769682175,310792960,4.047703266143799,0.005473136901855469,609.5418701171875 +1769682175,346537216,4.023349761962891,0.005588054656982422,609.5938110351562 +1769682175,376629504,4.003457069396973,0.005876421928405762,609.6331176757812 +1769682175,410163712,3.982625961303711,0.006206870079040527,609.6726684570312 +1769682175,453100288,3.952674150466919,0.0066727399826049805,609.7257080078125 +1769682175,478168576,3.9282593727111816,0.007009267807006836,609.7654418945312 +1769682175,511344384,3.9022843837738037,0.007327854633331299,609.8053588867188 +1769682175,547804416,3.866111993789673,0.0077100396156311035,609.8583374023438 +1769682175,577872128,3.8371798992156982,0.008115410804748535,609.89794921875 +1769682175,609825792,3.8068695068359375,0.008897960186004639,609.9373168945312 +1769682175,654842368,3.775696039199829,0.010726094245910645,609.97705078125 +1769682175,677592320,3.731565237045288,0.012241125106811523,610.031005859375 +1769682175,712079360,3.6969528198242188,0.013324379920959473,610.07177734375 +1769682175,749825024,3.649249792098999,0.01378720998764038,610.125244140625 +1769682175,778205952,3.611497640609741,0.013888776302337646,610.164794921875 +1769682175,803533056,3.5858988761901855,0.014225006103515625,610.1908569335938 +1769682175,849121536,3.5188941955566406,0.014036118984222412,610.2553100585938 +1769682175,877832704,3.477097272872925,0.014640212059020996,610.29345703125 +1769682175,910181888,3.4338839054107666,0.01535940170288086,610.3311767578125 +1769682175,945871872,3.374770402908325,0.016158580780029297,610.3810424804688 +1769682175,977900544,3.32853364944458,0.015867888927459717,610.417236328125 +1769682176,10656000,3.2812039852142334,0.015286087989807129,610.4523315429688 +1769682176,60681472,3.2159125804901123,0.014447152614593506,610.49755859375 +1769682176,71197184,3.182331085205078,0.014294743537902832,610.5195922851562 +1769682176,110075648,3.1142468452453613,0.013330817222595215,610.5628051757812 +1769682176,144161280,3.062640905380249,0.013183534145355225,610.5944213867188 +1769682176,177172736,2.999695062637329,0.012559890747070312,610.6351928710938 +1769682176,210233088,2.9594624042510986,0.012432456016540527,610.6638793945312 +1769682176,244720896,2.9239416122436523,0.01259392499923706,610.690673828125 +1769682176,277966336,2.8827874660491943,0.012273132801055908,610.7236328125 +1769682176,310959104,2.856577157974243,0.012246936559677124,610.7467041015625 +1769682176,347937280,2.830965757369995,0.012234002351760864,610.7754516601562 +1769682176,377376256,2.816272497177124,0.01224285364151001,610.7957763671875 +1769682176,409433088,2.8041467666625977,0.012350916862487793,610.8152465820312 +1769682176,445486592,2.7951903343200684,0.01282733678817749,610.8410034179688 +1769682176,476876288,2.7940661907196045,0.013337403535842896,610.8601684570312 +1769682176,512184576,2.7976632118225098,0.01385045051574707,610.8788452148438 +1769682176,553696768,2.8054544925689697,0.014501571655273438,610.8971557617188 +1769682176,578471680,2.822873115539551,0.014898926019668579,610.92041015625 +1769682176,610660864,2.840867519378662,0.015242993831634521,610.9370727539062 +1769682176,643301376,2.865060806274414,0.015654951333999634,610.9531860351562 +1769682176,676832512,2.901536703109741,0.01572898030281067,610.9734497070312 +1769682176,711816192,2.9325263500213623,0.015829533338546753,610.9880981445312 +1769682176,743990528,2.9633803367614746,0.01619786024093628,611.0025634765625 +1769682176,776538368,3.0049173831939697,0.017368733882904053,611.0220336914062 +1769682176,809728256,3.0362212657928467,0.01883113384246826,611.0379028320312 +1769682176,843272448,3.0675594806671143,0.020499110221862793,611.0545043945312 +1769682176,878418176,3.109412908554077,0.02214372158050537,611.0771484375 +1769682176,910505216,3.1408398151397705,0.02258545160293579,611.0933837890625 +1769682176,958749440,3.1828107833862305,0.022529900074005127,611.113525390625 +1769682176,976531712,3.2142951488494873,0.022313177585601807,611.1278076171875 +1769682177,10173696,3.245791435241699,0.022025644779205322,611.1414184570312 +1769682177,43648000,3.277405261993408,0.02195340394973755,611.1546630859375 +1769682177,78296320,3.31986141204834,0.022292912006378174,611.1715087890625 +1769682177,110978048,3.3517699241638184,0.02292788028717041,611.18359375 +1769682177,162542080,3.3943207263946533,0.02383667230606079,611.1990966796875 +1769682177,169180160,3.415557622909546,0.023881733417510986,611.2061767578125 +1769682177,211280128,3.458036184310913,0.022941648960113525,611.2185668945312 +1769682177,246852864,3.500624179840088,0.021868526935577393,611.2288208007812 +1769682177,277394688,3.5325582027435303,0.021102964878082275,611.2353515625 +1769682177,310234112,3.564497709274292,0.020393967628479004,611.2411499023438 +1769682177,347332608,3.607131004333496,0.019568979740142822,611.248046875 +1769682177,378246912,3.6391496658325195,0.01904118061065674,611.2528076171875 +1769682177,410247680,3.671178102493286,0.01859837770462036,611.2573852539062 +1769682177,456225024,3.713691234588623,0.018139302730560303,611.2635498046875 +1769682177,477329408,3.7449631690979004,0.017896056175231934,611.2682495117188 +1769682177,512730368,3.7752766609191895,0.017731785774230957,611.2731323242188 +1769682177,543698944,3.80450177192688,0.017713844776153564,611.2782592773438 +1769682177,578838016,3.8419294357299805,0.018064677715301514,611.2857055664062 +1769682177,609855488,3.8692967891693115,0.018833518028259277,611.2924194335938 +1769682177,643561728,3.895942449569702,0.019781768321990967,611.2999877929688 +1769682177,676986624,3.9302446842193604,0.020796597003936768,611.3109130859375 +1769682177,712059392,3.955090045928955,0.021550416946411133,611.3195190429688 +1769682177,747270144,3.9873504638671875,0.022431612014770508,611.331298828125 +1769682177,777029120,4.010400295257568,0.02299976348876953,611.3401489257812 +1769682177,811353856,4.032818794250488,0.02412492036819458,611.3491821289062 +1769682177,855032320,4.061432838439941,0.026906311511993408,611.3627319335938 +1769682177,877604096,4.082024097442627,0.02908426523208618,611.3737182617188 +1769682177,910677504,4.101731300354004,0.0306473970413208,611.3848876953125 +1769682177,943282944,4.120947360992432,0.03111046552658081,611.395263671875 +1769682177,980350720,4.145469665527344,0.03082174062728882,611.40771484375 +1769682178,11076352,4.163078308105469,0.030513882637023926,611.416259765625 +1769682178,46967808,4.185752868652344,0.030605316162109375,611.426513671875 +1769682178,77448960,4.2019734382629395,0.03111112117767334,611.4337158203125 +1769682178,112242176,4.217417240142822,0.03168696165084839,611.4404296875 +1769682178,143779840,4.231861114501953,0.031607747077941895,611.4462280273438 +1769682178,176903168,4.250139236450195,0.030254662036895752,611.4520874023438 +1769682178,209735168,4.263357162475586,0.029161810874938965,611.455078125 +1769682178,260928512,4.28007173538208,0.027771830558776855,611.4579467773438 +1769682178,277286656,4.291936874389648,0.026836812496185303,611.4595336914062 +1769682178,312414464,4.303236484527588,0.026028156280517578,611.4607543945312 +1769682178,343795968,4.314167022705078,0.025357544422149658,611.4617919921875 +1769682178,378517760,4.32757568359375,0.02464824914932251,611.4630737304688 +1769682178,410189824,4.337150573730469,0.024274230003356934,611.4640502929688 +1769682178,444423424,4.346046447753906,0.024027466773986816,611.4651489257812 +1769682178,480366592,4.356900215148926,0.024222910404205322,611.4669799804688 +1769682178,511978240,4.3645734786987305,0.024922192096710205,611.4693603515625 +1769682178,544934400,4.374136924743652,0.026027917861938477,611.4735717773438 +1769682178,576963584,4.38083028793335,0.0268593430519104,611.4773559570312 +1769682178,612050688,4.387246131896973,0.027632832527160645,611.4813232421875 +1769682178,645556480,4.39467191696167,0.028534650802612305,611.4869384765625 +1769682178,678205184,4.400272369384766,0.029452621936798096,611.491455078125 +1769682178,709939456,4.4055657386779785,0.031156957149505615,611.496826171875 +1769682178,744435712,4.411924839019775,0.03377252817153931,611.5051879882812 +1769682178,769462016,4.414775848388672,0.0348626971244812,611.5095825195312 +1769682178,811689472,4.419869422912598,0.03523200750350952,611.517578125 +1769682178,845891584,4.424562931060791,0.03494584560394287,611.5242309570312 +1769682178,878072576,4.427758693695068,0.034571051597595215,611.5285034179688 +1769682178,909748224,4.4309210777282715,0.034301578998565674,611.5322875976562 +1769682178,945573376,4.434525966644287,0.03445303440093994,611.5365600585938 +1769682178,977115648,4.436930179595947,0.03467559814453125,611.539306640625 +1769682179,10235648,4.438603401184082,0.03436309099197388,611.5410766601562 +1769682179,44634112,4.440418720245361,0.0333094596862793,611.5415649414062 +1769682179,77639168,4.4416961669921875,0.03246551752090454,611.5407104492188 +1769682179,112209920,4.44266414642334,0.03166365623474121,611.539306640625 +1769682179,155105792,4.4435200691223145,0.03091871738433838,611.5374145507812 +1769682179,176907520,4.444416046142578,0.030127286911010742,611.5344848632812 +1769682179,211513856,4.4448723793029785,0.029647469520568848,611.5321655273438 +1769682179,247032576,4.44520902633667,0.029163479804992676,611.5289916992188 +1769682179,278735360,4.445399284362793,0.028917133808135986,611.526611328125 +1769682179,311442944,4.445413589477539,0.02881026268005371,611.5242919921875 +1769682179,346707712,4.445043087005615,0.029170453548431396,611.5219116210938 +1769682179,377683712,4.444713115692139,0.029701292514801025,611.520751953125 +1769682179,409765632,4.4442620277404785,0.030278444290161133,611.5199584960938 +1769682179,457828864,4.443484783172607,0.031033694744110107,611.5191650390625 +1769682179,479077888,4.442821025848389,0.0315590500831604,611.5187377929688 +1769682179,510932736,4.442066192626953,0.032022833824157715,611.5181884765625 +1769682179,557245440,4.4414963722229,0.032771408557891846,611.517822265625 +1769682179,577293312,4.440584182739258,0.0342409610748291,611.5181884765625 +1769682179,612434688,4.439638137817383,0.035389721393585205,611.518798828125 +1769682179,646283008,4.438021183013916,0.035795748233795166,611.5191650390625 +1769682179,677227008,4.435808181762695,0.03561776876449585,611.5193481445312 +1769682179,710485248,4.434115886688232,0.03531229496002197,611.5192260742188 +1769682179,743892992,4.431796073913574,0.034792184829711914,611.5189208984375 +1769682179,777074688,4.430103778839111,0.03450089693069458,611.5185546875 +1769682179,846403584,4.428448677062988,0.034451186656951904,611.51806640625 +1769682179,864382976,4.426007270812988,0.03448301553726196,611.517333984375 +1769682179,889019392,4.423096179962158,0.03404510021209717,611.5160522460938 +1769682179,902533632,4.4211602210998535,0.03373980522155762,611.5146484375 +1769682179,943956992,4.417289733886719,0.0332108736038208,611.5104370117188 +1769682179,977399552,4.413439750671387,0.03278893232345581,611.5050659179688 +1769682180,12508672,4.4105706214904785,0.03249704837799072,611.5003051757812 +1769682180,48216576,4.406771659851074,0.03218024969100952,611.4935302734375 +1769682180,77576192,4.403947353363037,0.03199291229248047,611.4882202148438 +1769682180,110272256,4.401137828826904,0.03184962272644043,611.4828491210938 +1769682180,153639680,4.397457599639893,0.031712472438812256,611.4757080078125 +1769682180,177896960,4.394744396209717,0.03166508674621582,611.4705810546875 +1769682180,212805632,4.392017364501953,0.03175950050354004,611.4656372070312 +1769682180,244723200,4.388487815856934,0.03200078010559082,611.4598999023438 +1769682180,277480960,4.385905742645264,0.03220534324645996,611.4558715820312 +1769682180,310205184,4.383354663848877,0.032418668270111084,611.4520874023438 +1769682180,347127552,4.380041122436523,0.032693564891815186,611.4473876953125 +1769682180,377271808,4.377625942230225,0.03289002180099487,611.44384765625 +1769682180,412584192,4.375406742095947,0.03327751159667969,611.4404296875 +1769682180,448258816,4.37264347076416,0.03393012285232544,611.4361572265625 +1769682180,477314048,4.37036657333374,0.034355103969573975,611.43310546875 +1769682180,511039232,4.3671040534973145,0.034272074699401855,611.4296264648438 +1769682180,561446144,4.362926006317139,0.0339779257774353,611.4251098632812 +1769682180,568212224,4.360866546630859,0.033777594566345215,611.4228515625 +1769682180,610220288,4.3568220138549805,0.03340691328048706,611.4185180664062 +1769682180,643610880,4.353397369384766,0.03303879499435425,611.415283203125 +1769682180,679247616,4.346673011779785,0.03287613391876221,611.4111938476562 +1769682180,711444224,4.340286731719971,0.032859623432159424,611.408447265625 +1769682180,745335040,4.333289623260498,0.032842814922332764,611.4051513671875 +1769682180,777412096,4.3303351402282715,0.03280472755432129,611.4019165039062 +1769682180,810600960,4.3274712562561035,0.032826900482177734,611.3980102539062 +1769682180,843822336,4.323890209197998,0.03287672996520996,611.391845703125 +1769682180,877354496,4.321338653564453,0.03292691707611084,611.3865966796875 +1769682180,910386176,4.318861961364746,0.03299134969711304,611.381103515625 +1769682180,958744832,4.3157548904418945,0.03309190273284912,611.3734130859375 +1769682180,977091072,4.3135552406311035,0.033171117305755615,611.3675537109375 +1769682181,11126528,4.311464309692383,0.03324002027511597,611.3614501953125 +1769682181,47319040,4.30888032913208,0.033303141593933105,611.353271484375 +1769682181,80097536,4.307007789611816,0.03327876329421997,611.3470458984375 +1769682181,112806656,4.305230140686035,0.033145248889923096,611.3407592773438 +1769682181,151779072,4.3030314445495605,0.0329052209854126,611.3323364257812 +1769682181,177470976,4.3014116287231445,0.03271204233169556,611.3260498046875 +1769682181,214547712,4.299875259399414,0.03253746032714844,611.3198852539062 +1769682181,247796224,4.297944068908691,0.0323522686958313,611.3117065429688 +1769682181,277676032,4.296576976776123,0.032292306423187256,611.3056640625 +1769682181,310637568,4.295374393463135,0.032403647899627686,611.299560546875 +1769682181,356940800,4.294039726257324,0.03247976303100586,611.2913818359375 +1769682181,377490688,4.292973041534424,0.03237336874008179,611.2852172851562 +1769682181,412789760,4.291510105133057,0.03212416172027588,611.2786865234375 +1769682181,445072128,4.2896623611450195,0.03184664249420166,611.2697143554688 +1769682181,479632128,4.288330078125,0.03165125846862793,611.2630004882812 +1769682181,510144256,4.287022590637207,0.03143388032913208,611.2562255859375 +1769682181,544837632,4.285337924957275,0.031110107898712158,611.2474975585938 +1769682181,577854208,4.284099578857422,0.030831456184387207,611.2413940429688 +1769682181,612557312,4.28289794921875,0.03053128719329834,611.2356567382812 +1769682181,644868352,4.281418323516846,0.030214905738830566,611.228759765625 +1769682181,677581056,4.280519485473633,0.030353665351867676,611.2240600585938 +1769682181,711078656,4.279655456542969,0.03076314926147461,611.2196655273438 +1769682181,762926592,4.278571128845215,0.03145092725753784,611.2138671875 +1769682181,772587008,4.278041839599609,0.03178125619888306,611.2108154296875 +1769682181,810402816,4.277028560638428,0.032605767250061035,611.2037353515625 +1769682181,845419520,4.27606725692749,0.033353447914123535,611.1953735351562 +1769682181,880008704,4.275376796722412,0.03384119272232056,611.1880493164062 +1769682181,912243456,4.274701118469238,0.034240663051605225,611.179931640625 +1769682181,950059008,4.273849964141846,0.03459054231643677,611.1683349609375 +1769682181,977655808,4.2732930183410645,0.034676194190979004,611.1593017578125 +1769682182,15127808,4.272878170013428,0.034380555152893066,611.14990234375 +1769682182,49399296,4.272355079650879,0.03367668390274048,611.1368408203125 +1769682182,77476864,4.271980285644531,0.03310871124267578,611.127197265625 +1769682182,110479872,4.271615505218506,0.032579898834228516,611.1175537109375 +1769682182,162954496,4.271152496337891,0.03201329708099365,611.1049194335938 +1769682182,170285312,4.270932674407959,0.031706809997558594,611.0986938476562 +1769682182,212176896,4.2704949378967285,0.03148961067199707,611.085693359375 +1769682182,244246272,4.270188808441162,0.03108680248260498,611.072021484375 +1769682182,282780672,4.270076274871826,0.03035980463027954,611.0613403320312 +1769682182,310664704,4.270143032073975,0.029609978199005127,611.0501098632812 +1769682182,346260480,4.270346641540527,0.029182851314544678,611.0347900390625 +1769682182,377594368,4.270495414733887,0.029073774814605713,611.0230102539062 +1769682182,412088832,4.2706403732299805,0.029041647911071777,611.0109252929688 +1769682182,447241728,4.270819187164307,0.029043614864349365,610.9946899414062 +1769682182,477348096,4.2709527015686035,0.02905505895614624,610.9825439453125 +1769682182,511130112,4.270852088928223,0.028719842433929443,610.9705810546875 +1769682182,562102784,4.270683288574219,0.02790534496307373,610.9551391601562 +1769682182,570235904,4.270763397216797,0.027369022369384766,610.9478149414062 +1769682182,610622976,4.271233558654785,0.02773338556289673,610.9346923828125 +1769682182,648237312,4.271636486053467,0.028680026531219482,610.9240112304688 +1769682182,679579136,4.271938800811768,0.029498398303985596,610.9169311523438 +1769682182,710596096,4.272216796875,0.030337512493133545,610.9103393554688 +1769682182,744744192,4.2725300788879395,0.03144526481628418,610.9014282226562 +1769682182,777639680,4.272755146026611,0.03221338987350464,610.894287109375 +1769682182,812717824,4.27295446395874,0.03289937973022461,610.886474609375 +1769682182,848575232,4.273138046264648,0.033651113510131836,610.8750610351562 +1769682182,877181696,4.273258686065674,0.03403580188751221,610.8656616210938 +1769682182,910309376,4.273547649383545,0.03402191400527954,610.8557739257812 +1769682182,957784064,4.2739644050598145,0.03314763307571411,610.8411254882812 +1769682182,977422336,4.274230003356934,0.03227418661117554,610.8296508789062 +1769682183,10485760,4.274470329284668,0.031394124031066895,610.8182373046875 +1769682183,44089600,4.274733066558838,0.030354678630828857,610.8034057617188 +1769682183,80443904,4.274885177612305,0.02972966432571411,610.79248046875 +1769682183,110898432,4.275014400482178,0.029253721237182617,610.781494140625 +1769682183,145719296,4.274870872497559,0.028599917888641357,610.7662963867188 +1769682183,177505792,4.274845600128174,0.027673959732055664,610.7535400390625 +1769682183,210890496,4.2748026847839355,0.026561379432678223,610.739501953125 +1769682183,251559168,4.275432586669922,0.02576303482055664,610.7195434570312 +1769682183,278537216,4.275877475738525,0.026004552841186523,610.7041015625 +1769682183,310556928,4.276303768157959,0.02641737461090088,610.6885375976562 +1769682183,357066496,4.276841163635254,0.02701181173324585,610.6676635742188 +1769682183,377198848,4.277220726013184,0.027408897876739502,610.6522216796875 +1769682183,410676480,4.277470588684082,0.02764195203781128,610.6373291015625 +1769682183,446464000,4.277431964874268,0.026948094367980957,610.61865234375 +1769682183,479050752,4.2773847579956055,0.026192843914031982,610.6057739257812 +1769682183,511500032,4.278114318847656,0.025866329669952393,610.5941772460938 +1769682183,546669568,4.278989791870117,0.026474475860595703,610.5818481445312 +1769682183,577714432,4.27962589263916,0.02714639902114868,610.5741577148438 +1769682183,614556672,4.280238628387451,0.027868688106536865,610.5674438476562 +1769682183,649265152,4.281018257141113,0.028836488723754883,610.558837890625 +1769682183,677344000,4.281598091125488,0.029526352882385254,610.5523071289062 +1769682183,711641856,4.282153606414795,0.03016519546508789,610.5452880859375 +1769682183,755469312,4.282764434814453,0.03090798854827881,610.5349731445312 +1769682183,777689344,4.28321647644043,0.031353116035461426,610.5264892578125 +1769682183,810634240,4.2836408615112305,0.03161966800689697,610.517333984375 +1769682183,843974144,4.2842912673950195,0.03142577409744263,610.5039672851562 +1769682183,881626624,4.284737586975098,0.0309598445892334,610.4931030273438 +1769682183,910997504,4.285146236419678,0.030393123626708984,610.482177734375 +1769682183,945519616,4.285592079162598,0.02957296371459961,610.4678955078125 +1769682183,978143232,4.285878658294678,0.028956174850463867,610.457763671875 +1769682184,13944576,4.286092758178711,0.028387069702148438,610.4483032226562 +1769682184,50072320,4.286186695098877,0.027634918689727783,610.4368286132812 +1769682184,78308352,4.285919666290283,0.026700198650360107,610.4281005859375 +1769682184,110790912,4.285529613494873,0.025690674781799316,610.4188232421875 +1769682184,158888704,4.285491943359375,0.024705588817596436,610.4058837890625 +1769682184,167187200,4.285785675048828,0.02477473020553589,610.3994750976562 +1769682184,212269568,4.286334037780762,0.025631189346313477,610.38671875 +1769682184,244488448,4.286851406097412,0.02663964033126831,610.3739624023438 +1769682184,285886976,4.2872185707092285,0.0273551344871521,610.3643798828125 +1769682184,327170560,4.287557125091553,0.0279884934425354,610.3551635742188 +1769682184,349373440,4.287537097930908,0.0279274582862854,610.3433837890625 +1769682184,377636096,4.287505149841309,0.027367055416107178,610.33544921875 +1769682184,413116928,4.2876410484313965,0.026703953742980957,610.328369140625 +1769682184,453497600,4.288259983062744,0.02638918161392212,610.3208618164062 +1769682184,478348032,4.288668632507324,0.02631467580795288,610.3167114257812 +1769682184,511472896,4.289044380187988,0.026304244995117188,610.3134155273438 +1769682184,554400768,4.289534568786621,0.0263901948928833,610.3098754882812 +1769682184,577934848,4.28989315032959,0.026494860649108887,610.3074951171875 +1769682184,610582272,4.290152549743652,0.02663475275039673,610.304931640625 +1769682184,646468608,4.290441036224365,0.02684009075164795,610.3012084960938 +1769682184,679800832,4.2906389236450195,0.026989996433258057,610.2979125976562 +1769682184,710604800,4.290731906890869,0.02710247039794922,610.2942504882812 +1769682184,750124288,4.290670871734619,0.027332663536071777,610.2891235351562 +1769682184,777976064,4.290561199188232,0.027622699737548828,610.28564453125 +1769682184,810530816,4.290397644042969,0.027908265590667725,610.28271484375 +1769682184,844453120,4.2900471687316895,0.02820640802383423,610.2798461914062 +1769682184,878313216,4.289751052856445,0.02837812900543213,610.2784423828125 +1769682184,911119616,4.289405345916748,0.02850550413131714,610.277587890625 +1769682184,949556736,4.2888264656066895,0.028639793395996094,610.27734375 +1769682184,979436032,4.288090705871582,0.02838212251663208,610.2774658203125 +1769682185,10352640,4.287092685699463,0.027656376361846924,610.27685546875 +1769682185,63753728,4.285538673400879,0.027001142501831055,610.274658203125 +1769682185,71214080,4.285170555114746,0.0268058180809021,610.2731323242188 +1769682185,114519296,4.284365177154541,0.026980698108673096,610.2697143554688 +1769682185,144337664,4.283510208129883,0.02725088596343994,610.26611328125 +1769682185,177643008,4.2828369140625,0.027446448802947998,610.263427734375 +1769682185,211020288,4.282138347625732,0.027622997760772705,610.2609252929688 +1769682185,248676352,4.280882835388184,0.02742224931716919,610.2581176757812 +1769682185,278536704,4.279872894287109,0.026843547821044922,610.2565307617188 +1769682185,310617856,4.278852462768555,0.026179969310760498,610.2553100585938 +1769682185,349926912,4.277565956115723,0.025338172912597656,610.254638671875 +1769682185,379200768,4.27658748626709,0.024773836135864258,610.2550659179688 +1769682185,410690560,4.275599956512451,0.024235785007476807,610.2564697265625 +1769682185,454837504,4.274283409118652,0.02359539270401001,610.260009765625 +1769682185,478054656,4.273303508758545,0.02320873737335205,610.263916015625 +1769682185,511015424,4.272333145141602,0.022940218448638916,610.2686767578125 +1769682185,546020096,4.271029472351074,0.022770404815673828,610.2757568359375 +1769682185,581750272,4.270045757293701,0.022751271724700928,610.28125 +1769682185,611161344,4.269073486328125,0.022770166397094727,610.2864990234375 +1769682185,645609472,4.267780303955078,0.02282947301864624,610.2930297851562 +1769682185,677696256,4.266611099243164,0.02318274974822998,610.2979125976562 +1769682185,711175424,4.265435695648193,0.023756742477416992,610.3035888671875 +1769682185,750275840,4.2638983726501465,0.024509906768798828,610.3121337890625 +1769682185,779410176,4.2627716064453125,0.025003492832183838,610.3191528320312 +1769682185,810863616,4.26162052154541,0.02541893720626831,610.3269653320312 +1769682185,854932480,4.260138511657715,0.025851905345916748,610.33837890625 +1769682185,878347008,4.258938789367676,0.026015937328338623,610.347412109375 +1769682185,912083968,4.257504463195801,0.025562584400177002,610.3564453125 +1769682185,945361408,4.255553245544434,0.02476370334625244,610.3677978515625 +1769682185,982236672,4.254169464111328,0.02427119016647339,610.3759155273438 +1769682186,11039744,4.252831935882568,0.023918330669403076,610.3839111328125 +1769682186,50645504,4.251030445098877,0.023594796657562256,610.3944091796875 +1769682186,77261568,4.249699592590332,0.023414194583892822,610.4020385742188 +1769682186,114322688,4.248364448547363,0.02326357364654541,610.4096069335938 +1769682186,148159232,4.246523380279541,0.022997617721557617,610.4195556640625 +1769682186,177875456,4.245092868804932,0.022584080696105957,610.427001953125 +1769682186,210615296,4.243680000305176,0.02212148904800415,610.4345703125 +1769682186,262284288,4.2418646812438965,0.021531343460083008,610.44482421875 +1769682186,272974336,4.241003513336182,0.021407127380371094,610.4503173828125 +1769682186,311673600,4.239286422729492,0.020943820476531982,610.4620361328125 +1769682186,345679360,4.237590789794922,0.020662426948547363,610.4747314453125 +1769682186,378978304,4.236353397369385,0.020515501499176025,610.4849243164062 +1769682186,410937600,4.2351274490356445,0.020393192768096924,610.4954833984375 +1769682186,446707968,4.233555316925049,0.020298898220062256,610.5100708007812 +1769682186,478000384,4.232399940490723,0.020259857177734375,610.5213623046875 +1769682186,511354368,4.231266498565674,0.02023845911026001,610.53271484375 +1769682186,549790976,4.22981071472168,0.020236074924468994,610.5482177734375 +1769682186,594567168,4.22875452041626,0.020258009433746338,610.5598754882812 +1769682186,599894016,4.227994441986084,0.0204736590385437,610.5676879882812 +1769682186,648705792,4.226181983947754,0.020821034908294678,610.5878295898438 +1769682186,679911168,4.225161552429199,0.021101951599121094,610.6001586914062 +1769682186,710602240,4.224184513092041,0.02134495973587036,610.6126098632812 +1769682186,745870336,4.222936630249023,0.02158266305923462,610.6295166015625 +1769682186,777803776,4.222012996673584,0.02170741558074951,610.6424560546875 +1769682186,813585408,4.220996379852295,0.02159827947616577,610.6554565429688 +1769682186,845857024,4.219682216644287,0.021194517612457275,610.672607421875 +1769682186,877716992,4.2187018394470215,0.020914137363433838,610.6852416992188 +1769682186,910895872,4.217832565307617,0.020693600177764893,610.6976318359375 +1769682186,949323776,4.21682071685791,0.020564138889312744,610.7139282226562 +1769682186,978582272,4.2160868644714355,0.020491182804107666,610.7260131835938 +1769682187,10957056,4.215392112731934,0.020445644855499268,610.7379760742188 +1769682187,45458688,4.214527606964111,0.02040499448776245,610.7537231445312 +1769682187,78257920,4.2138285636901855,0.020247995853424072,610.7654418945312 +1769682187,110791680,4.213217735290527,0.019968032836914062,610.7769165039062 +1769682187,144951296,4.2124505043029785,0.019595801830291748,610.7921752929688 +1769682187,178674432,4.212189197540283,0.019498586654663086,610.8035278320312 +1769682187,211309568,4.211992263793945,0.019462287425994873,610.8152465820312 +1769682187,246796544,4.211786270141602,0.01940011978149414,610.8312377929688 +1769682187,277691136,4.211692810058594,0.01935100555419922,610.8436889648438 +1769682187,310739968,4.211629867553711,0.01932501792907715,610.8564453125 +1769682187,347495424,4.211602687835693,0.019334077835083008,610.8738403320312 +1769682187,377752064,4.2116007804870605,0.019384562969207764,610.8871459960938 +1769682187,412197120,4.2116379737854,0.01945209503173828,610.9003295898438 +1769682187,457153280,4.211753845214844,0.019558846950531006,610.9177856445312 +1769682187,478307840,4.211879253387451,0.01964426040649414,610.9306030273438 +1769682187,511307776,4.212038516998291,0.019723176956176758,610.9432373046875 +1769682187,544755200,4.212193965911865,0.019909679889678955,610.9597778320312 +1769682187,578473216,4.212294578552246,0.020076990127563477,610.9721069335938 +1769682187,611555328,4.212425708770752,0.020186007022857666,610.9843139648438 +1769682187,648925952,4.212560653686523,0.02024787664413452,611.0008544921875 +1769682187,677900544,4.212621212005615,0.020228862762451172,611.0134887695312 +1769682187,711205888,4.212619781494141,0.02016007900238037,611.026611328125 +1769682187,747622656,4.212486743927002,0.019800245761871338,611.0442504882812 +1769682187,777796864,4.212347030639648,0.019443809986114502,611.0574951171875 +1769682187,811378432,4.212158203125,0.019196391105651855,611.0707397460938 +1769682187,848378368,4.212236404418945,0.0192030668258667,611.0883178710938 +1769682187,878247680,4.212298393249512,0.019304871559143066,611.1013793945312 +1769682187,910900736,4.212380886077881,0.019421815872192383,611.1141967773438 +1769682187,945560832,4.212372303009033,0.019616365432739258,611.130859375 +1769682187,969173248,4.212327480316162,0.01978069543838501,611.1389770507812 +1769682188,12193536,4.211928367614746,0.019467413425445557,611.15478515625 +1769682188,44864768,4.2114362716674805,0.01894080638885498,611.1702270507812 +1769682188,77870848,4.211006164550781,0.018536806106567383,611.1815795898438 +1769682188,112140544,4.210713863372803,0.01842176914215088,611.1930541992188 +1769682188,144895744,4.210278034210205,0.018389999866485596,611.2086181640625 +1769682188,178308608,4.209835529327393,0.018370628356933594,611.2208862304688 +1769682188,212887040,4.209423065185547,0.01834702491760254,611.2337036132812 +1769682188,261106176,4.208703517913818,0.018340766429901123,611.2517700195312 +1769682188,269857280,4.208293914794922,0.018443942070007324,611.26123046875 +1769682188,311165184,4.207493305206299,0.018406689167022705,611.280517578125 +1769682188,351464704,4.206485271453857,0.01847761869430542,611.3002319335938 +1769682188,373339136,4.20594596862793,0.018719077110290527,611.3101806640625 +1769682188,412106752,4.20477294921875,0.018640637397766113,611.329833984375 +1769682188,446322176,4.203464508056641,0.018790245056152344,611.349365234375 +1769682188,477933056,4.2023797035217285,0.018979191780090332,611.3639526367188 +1769682188,510839552,4.201175689697266,0.01919025182723999,611.3783569335938 +1769682188,550729728,4.199406147003174,0.01944708824157715,611.3974609375 +1769682188,579098624,4.198014736175537,0.019611656665802002,611.4116821289062 +1769682188,614300672,4.196561336517334,0.0197446346282959,611.42578125 +1769682188,650039040,4.1942243576049805,0.01963907480239868,611.4445190429688 +1769682188,678294528,4.192229270935059,0.019110798835754395,611.4581909179688 +1769682188,711909120,4.190046787261963,0.01850980520248413,611.4716186523438 +1769682188,757387008,4.187103271484375,0.017849445343017578,611.4893188476562 +1769682188,777699584,4.184871196746826,0.017762601375579834,611.502685546875 +1769682188,810901504,4.182436943054199,0.01784956455230713,611.5159912109375 +1769682188,845649408,4.178889274597168,0.0180814266204834,611.5331420898438 +1769682188,881310464,4.176137447357178,0.0183255672454834,611.5455322265625 +1769682188,911215360,4.173222541809082,0.018480539321899414,611.5572509765625 +1769682188,946181376,4.168764591217041,0.018112480640411377,611.5722045898438 +1769682188,978366976,4.165257453918457,0.017611384391784668,611.5830688476562 +1769682189,14799104,4.161773681640625,0.017142891883850098,611.5936279296875 +1769682189,47432448,4.156866073608398,0.016978323459625244,611.6080322265625 +1769682189,78318592,4.15295934677124,0.01706939935684204,611.6193237304688 +1769682189,127918848,4.1490159034729,0.017196059226989746,611.6310424804688 +1769682189,163581696,4.143418788909912,0.017328858375549316,611.647705078125 +1769682189,172244736,4.140496253967285,0.01752495765686035,611.656494140625 +1769682189,211350784,4.13449239730835,0.01745814085006714,611.6751098632812 +1769682189,248200704,4.128101348876953,0.017586708068847656,611.6947631835938 +1769682189,278316032,4.123222351074219,0.01774519681930542,611.7098999023438 +1769682189,313197824,4.118166923522949,0.017926037311553955,611.7250366210938 +1769682189,350830592,4.111263275146484,0.018238186836242676,611.7448120117188 +1769682189,378398464,4.105859279632568,0.01853400468826294,611.7589111328125 +1769682189,414266624,4.100297927856445,0.018867552280426025,611.7722778320312 +1769682189,449393664,4.092618465423584,0.019305169582366943,611.7889404296875 +1769682189,478400512,4.086734294891357,0.019589126110076904,611.800537109375 +1769682189,511951872,4.08071231842041,0.019816458225250244,611.8115844726562 +1769682189,557485824,4.072358131408691,0.019965946674346924,611.82568359375 +1769682189,578031616,4.065931797027588,0.019852936267852783,611.8363037109375 +1769682189,611119104,4.059250354766846,0.019296467304229736,611.8465576171875 +1769682189,645328128,4.050117015838623,0.01814216375350952,611.8599243164062 +1769682189,684987648,4.043202877044678,0.017265737056732178,611.869873046875 +1769682189,711589632,4.036083698272705,0.01676309108734131,611.8800048828125 +1769682189,745492480,4.026436805725098,0.016641855239868164,611.8934936523438 +1769682189,779738624,4.01883602142334,0.016780197620391846,611.9033203125 +1769682189,811391232,4.011115550994873,0.01703011989593506,611.9126586914062 +1769682189,851086080,4.000649929046631,0.017451763153076172,611.9240112304688 +1769682189,879336960,3.992361307144165,0.017550945281982422,611.9318237304688 +1769682189,911078912,3.9838387966156006,0.017226457595825195,611.9390869140625 +1769682189,963850752,3.972266912460327,0.016587376594543457,611.9480590820312 +1769682189,971667712,3.9664106369018555,0.016442835330963135,611.9525146484375 +1769682190,11310080,3.9542994499206543,0.016275763511657715,611.9619140625 +1769682190,48423424,3.94181752204895,0.01648324728012085,611.9725341796875 +1769682190,80668160,3.9323503971099854,0.016635537147521973,611.981689453125 +1769682190,111703808,3.9226837158203125,0.01680278778076172,611.9920043945312 +1769682190,154446848,3.9094595909118652,0.017065703868865967,612.007080078125 +1769682190,177868800,3.8994619846343994,0.01731276512145996,612.01904296875 +1769682190,214630400,3.8893814086914062,0.01761019229888916,612.0311889648438 +1769682190,249230080,3.8756611347198486,0.018068671226501465,612.0469360351562 +1769682190,279364864,3.865109920501709,0.01844543218612671,612.05810546875 +1769682190,311173376,3.8544819355010986,0.01881784200668335,612.068359375 +1769682190,361590272,3.8400936126708984,0.01922285556793213,612.0804443359375 +1769682190,368573184,3.8327999114990234,0.01942199468612671,612.0858154296875 +1769682190,412025344,3.817923069000244,0.01963222026824951,612.0952758789062 +1769682190,446019072,3.8027515411376953,0.019786596298217773,612.103515625 +1769682190,478991104,3.7912380695343018,0.019841432571411133,612.1091918945312 +1769682190,511263488,3.779649257659912,0.019846796989440918,612.1146240234375 +1769682190,547129856,3.7639923095703125,0.01975959539413452,612.1218872070312 +1769682190,580439808,3.751976251602173,0.01953434944152832,612.1276245117188 +1769682190,611637248,3.7395973205566406,0.01882028579711914,612.133056640625 +1769682190,648282880,3.722916603088379,0.01739645004272461,612.1397094726562 +1769682190,678580480,3.7104830741882324,0.016426026821136475,612.1443481445312 +1769682190,711078656,3.6978707313537598,0.015780985355377197,612.1487426757812 +1769682190,759201536,3.680860757827759,0.015612006187438965,612.1546020507812 +1769682190,780298240,3.6679494380950928,0.015771567821502686,612.1585693359375 +1769682190,812375296,3.6549510955810547,0.016048789024353027,612.1621704101562 +1769682190,846173440,3.637425184249878,0.016507506370544434,612.1661376953125 +1769682190,879106304,3.6241455078125,0.016881346702575684,612.16845703125 +1769682190,911912448,3.6105902194976807,0.017129957675933838,612.1702880859375 +1769682190,947784448,3.5920698642730713,0.01676309108734131,612.1723022460938 +1769682190,983902720,3.5782101154327393,0.016435325145721436,612.1737060546875 +1769682191,12239104,3.564122200012207,0.016221821308135986,612.175048828125 +1769682191,46539776,3.5450475215911865,0.016499459743499756,612.1773071289062 +1769682191,78524416,3.530614137649536,0.016965150833129883,612.1793823242188 +1769682191,114397952,3.5161049365997314,0.017450928688049316,612.181640625 +1769682191,147915776,3.496577739715576,0.018031656742095947,612.1849975585938 +1769682191,178872576,3.4817843437194824,0.01840674877166748,612.187744140625 +1769682191,211222272,3.4669189453125,0.018735170364379883,612.1906127929688 +1769682191,258576896,3.446927309036255,0.019131720066070557,612.1946411132812 +1769682191,278043392,3.4318203926086426,0.01939946413040161,612.1976318359375 +1769682191,311115264,3.416550874710083,0.01964545249938965,612.2005004882812 +1769682191,361474304,3.396160840988159,0.019972145557403564,612.2037353515625 +1769682191,387097344,3.380758047103882,0.020134925842285156,612.2056884765625 +1769682191,402560512,3.3704724311828613,0.02016127109527588,612.2064208984375 +1769682191,445762048,3.344576120376587,0.020069658756256104,612.2071533203125 +1769682191,479343360,3.3289144039154053,0.019992530345916748,612.2068481445312 +1769682191,513586176,3.3131802082061768,0.01990187168121338,612.2059936523438 +1769682191,550530560,3.2920045852661133,0.01982271671295166,612.2044067382812 +1769682191,578583296,3.276095151901245,0.01980423927307129,612.2028198242188 +1769682191,611145472,3.260080337524414,0.01979905366897583,612.2008056640625 +1769682191,658940416,3.2385709285736084,0.01981407403945923,612.1976318359375 +1769682191,668630784,3.2277469635009766,0.019794046878814697,612.1958618164062 +1769682191,712045824,3.206033706665039,0.019516170024871826,612.1919555664062 +1769682191,744971520,3.1836962699890137,0.0184745192527771,612.1869506835938 +1769682191,782593280,3.166848659515381,0.017541825771331787,612.1820678710938 +1769682191,812206592,3.1501359939575195,0.016743004322052002,612.1764526367188 +1769682191,847649024,3.127429246902466,0.015988200902938843,612.16845703125 +1769682191,878227712,3.110229969024658,0.01593276858329773,612.1622314453125 +1769682191,911566336,3.0928292274475098,0.01610502600669861,612.1561889648438 +1769682191,947389440,3.0695064067840576,0.01645791530609131,612.1480102539062 +1769682191,978819328,3.051826238632202,0.016785413026809692,612.141845703125 +1769682192,12990720,3.0340802669525146,0.01710456609725952,612.1355590820312 +1769682192,66423296,3.0103328227996826,0.017513632774353027,612.1270751953125 +1769682192,74366464,2.9984219074249268,0.017628073692321777,612.122802734375 +1769682192,111195392,2.974213123321533,0.01782447099685669,612.1143188476562 +1769682192,157027328,2.9497992992401123,0.017513751983642578,612.1061401367188 +1769682192,181515264,2.931384801864624,0.017287135124206543,612.1002197265625 +1769682192,211609600,2.912628173828125,0.017068475484848022,612.0941772460938 +1769682192,245615872,2.8874285221099854,0.017444610595703125,612.0869140625 +1769682192,279628288,2.868364095687866,0.017908483743667603,612.0817260742188 +1769682192,312313344,2.8492484092712402,0.01837986707687378,612.07666015625 +1769682192,348450304,2.8236987590789795,0.01894882321357727,612.0701293945312 +1769682192,378470144,2.8044543266296387,0.019329309463500977,612.0653076171875 +1769682192,414422272,2.785327911376953,0.019650429487228394,612.0603637695312 +1769682192,449999872,2.759801149368286,0.01999548077583313,612.0538940429688 +1769682192,478663424,2.7406182289123535,0.020197242498397827,612.0490112304688 +1769682192,511549696,2.721261501312256,0.020357072353363037,612.0440673828125 +1769682192,560102912,2.6954495906829834,0.020497441291809082,612.0375366210938 +1769682192,578192896,2.675997018814087,0.020592331886291504,612.0325317382812 +1769682192,612699904,2.656500816345215,0.020617634057998657,612.0275268554688 +1769682192,645751552,2.630617141723633,0.020441055297851562,612.0201416015625 +1769682192,678667008,2.6112184524536133,0.020230978727340698,612.0137939453125 +1769682192,712712192,2.591815710067749,0.020024597644805908,612.0070190429688 +1769682192,749669888,2.5659306049346924,0.01976799964904785,611.9970092773438 +1769682192,779077376,2.5463814735412598,0.01962047815322876,611.9890747070312 +1769682192,812577280,2.5267157554626465,0.019483894109725952,611.9807739257812 +1769682192,846703360,2.5005249977111816,0.019372165203094482,611.9692993164062 +1769682192,878900480,2.480865716934204,0.01934531331062317,611.96044921875 +1769682192,911492608,2.4612598419189453,0.01936623454093933,611.9512329101562 +1769682192,949529856,2.4353232383728027,0.019430339336395264,611.9384765625 +1769682192,980226816,2.4158735275268555,0.01953071355819702,611.9285278320312 +1769682193,11240192,2.3964459896087646,0.019626140594482422,611.9181518554688 +1769682193,46710272,2.37097430229187,0.0195370614528656,611.9037475585938 +1769682193,78844672,2.351571798324585,0.01940995454788208,611.8923950195312 +1769682193,114721536,2.332108736038208,0.0193139910697937,611.88037109375 +1769682193,147259392,2.305921792984009,0.01904234290122986,611.8633422851562 +1769682193,178759424,2.286003351211548,0.018596112728118896,611.8491821289062 +1769682193,213827840,2.2662975788116455,0.01811203360557556,611.833740234375 +1769682193,247267328,2.2398948669433594,0.01749354600906372,611.8121948242188 +1769682193,278801920,2.2200028896331787,0.01705235242843628,611.7957763671875 +1769682193,311523584,2.199683427810669,0.0168607234954834,611.7796020507812 +1769682193,359555584,2.1726388931274414,0.017041683197021484,611.7589111328125 +1769682193,379446016,2.152287244796753,0.017268091440200806,611.7440185546875 +1769682193,411816960,2.1318633556365967,0.017518937587738037,611.7294311523438 +1769682193,445488384,2.1046457290649414,0.01785862445831299,611.7105102539062 +1769682193,478278912,2.084150791168213,0.01810246706008911,611.6964721679688 +1769682193,511449344,2.0637595653533936,0.018320798873901367,611.6824951171875 +1769682193,546133760,2.0365774631500244,0.01853272318840027,611.6640625 +1769682193,578718464,2.0160601139068604,0.018627285957336426,611.6505126953125 +1769682193,611687680,1.9954081773757935,0.018650531768798828,611.6371459960938 +1769682193,646206208,1.9680638313293457,0.0185890793800354,611.6199951171875 +1769682193,679086336,1.9473052024841309,0.018513023853302002,611.6077270507812 +1769682193,712763904,1.9263949394226074,0.01842626929283142,611.5960083007812 +1769682193,746932224,1.8983181715011597,0.017878234386444092,611.5813598632812 +1769682193,779480576,1.8772274255752563,0.01758265495300293,611.5709228515625 +1769682193,811924736,1.8561729192733765,0.01739346981048584,611.5606079101562 +1769682193,850168576,1.8282965421676636,0.017250865697860718,611.5463256835938 +1769682193,880329728,1.8071783781051636,0.01760721206665039,611.5353393554688 +1769682193,913402368,1.7860618829727173,0.01819533109664917,611.5241088867188 +1769682193,958332416,1.7579014301300049,0.01911899447441101,611.5079956054688 +1769682193,978757376,1.7366875410079956,0.019919127225875854,611.494873046875 +1769682194,11490048,1.715356707572937,0.020718634128570557,611.48046875 +1769682194,46050048,1.6870864629745483,0.02170446515083313,611.4594116210938 +1769682194,79378432,1.66574227809906,0.02230018377304077,611.4422607421875 +1769682194,111647488,1.6443183422088623,0.022760838270187378,611.424560546875 +1769682194,147953920,1.6157522201538086,0.023149967193603516,611.4005126953125 +1769682194,179054336,1.594377040863037,0.023289114236831665,611.3825073242188 +1769682194,213975552,1.5729994773864746,0.023320257663726807,611.3648071289062 +1769682194,247396864,1.5446606874465942,0.023214608430862427,611.342041015625 +1769682194,278899712,1.5233439207077026,0.023586124181747437,611.3255004882812 +1769682194,328106496,1.502416729927063,0.02384456992149353,611.3076171875 +1769682194,359278336,1.4746215343475342,0.02416934072971344,611.2817993164062 +1769682194,369326848,1.4606510400772095,0.024282485246658325,611.26806640625 +1769682194,411667456,1.4326316118240356,0.024754926562309265,611.2392578125 +1769682194,447260160,1.404662847518921,0.025169074535369873,611.2085571289062 +1769682194,479800320,1.3835598230361938,0.02544616162776947,611.1844482421875 +1769682194,506852864,1.3628665208816528,0.025491729378700256,611.159423828125 +1769682194,546940416,1.335777759552002,0.025345101952552795,611.1243896484375 +1769682194,578677760,1.315462350845337,0.025116726756095886,611.0972900390625 +1769682194,613070848,1.2950336933135986,0.024561792612075806,611.0703125 +1769682194,655183360,1.2682331800460815,0.023586049675941467,611.03662109375 +1769682194,679677440,1.2480218410491943,0.022997930645942688,611.0136108398438 +1769682194,712930304,1.2278318405151367,0.02242499589920044,610.9920654296875 +1769682194,748692224,1.2010810375213623,0.021662637591362,610.96533203125 +1769682194,779363840,1.1810410022735596,0.02108989655971527,610.9466552734375 +1769682194,812738816,1.1610195636749268,0.020522847771644592,610.9290771484375 +1769682194,848842240,1.134880781173706,0.019788265228271484,610.9072875976562 +1769682194,878763008,1.1153063774108887,0.019286498427391052,610.8922729492188 +1769682194,911963392,1.0955941677093506,0.018848657608032227,610.878173828125 +1769682194,945184000,1.0696755647659302,0.018390357494354248,610.8607788085938 +1769682194,979032320,1.0504316091537476,0.018181830644607544,610.848388671875 +1769682195,15344896,1.0312912464141846,0.0180647075176239,610.836181640625 +1769682195,62748672,1.0058852434158325,0.01801358163356781,610.8200073242188 +1769682195,67971328,0.9932780265808105,0.018037810921669006,610.8118286132812 +1769682195,111808512,0.9676822423934937,0.018172502517700195,610.795166015625 +1769682197,547941120,0.0,-0.0,610.519287109375 +1769682197,578963712,0.0,-0.0,610.519287109375 +1769682197,612030976,0.0,-0.0,610.519287109375 +1769682197,651033344,0.0,-0.0,610.519287109375 +1769682197,680354816,0.0,-0.0,610.519287109375 +1769682197,711882240,0.0,-0.0,610.519287109375 +1769682197,751959040,0.0,-0.0,610.519287109375 +1769682197,779987456,0.0,-0.0,610.519287109375 +1769682197,812767488,0.0,-0.0,610.519287109375 +1769682197,847019008,0.0,-0.0,610.519287109375 +1769682197,879002368,0.0,-0.0,610.519287109375 +1769682197,915835136,0.0,-0.0,610.519287109375 +1769682197,946582784,0.0,-0.0,610.519287109375 +1769682197,979719936,0.0,-0.0,610.519287109375 +1769682198,12879872,0.0,-0.0,610.519287109375 +1769682198,51246336,0.0,-0.0,610.519287109375 +1769682198,79638016,0.0,-0.0,610.519287109375 +1769682198,113188608,0.0,-0.0,610.519287109375 +1769682198,159996672,0.0,-0.0,610.519287109375 +1769682198,179217664,0.0,-0.0,610.519287109375 +1769682198,212375808,0.0,-0.0,610.5193481445312 +1769682198,245857536,0.0,-0.0,610.5193481445312 +1769682198,278932224,0.0,-0.0,610.5193481445312 +1769682198,312406272,0.0,-0.0,610.5193481445312 +1769682198,347892736,0.0,-0.0,610.5193481445312 +1769682198,379276288,0.0,-0.0,610.5193481445312 +1769682198,412165632,0.0,-0.0,610.5193481445312 +1769682198,445723392,0.0,-0.0,610.5193481445312 +1769682198,479228160,0.0,-0.0,610.5193481445312 +1769682198,512685824,0.0,-0.0,610.5193481445312 +1769682198,561560320,0.0,-0.0,610.5194702148438 +1769682198,570423552,0.0,-0.0,610.5194702148438 +1769682198,611966464,0.0,-0.0,610.5194702148438 +1769682198,646645760,0.0,-0.0,610.5194702148438 +1769682198,679396352,0.0,-0.0,610.5194702148438 +1769682198,712074496,0.0,-0.0,610.5194702148438 +1769682198,746901504,0.0,-0.0,610.5194702148438 +1769682198,782393600,0.0,-0.0,610.5194702148438 +1769682198,812574720,0.0,-0.0,610.5194702148438 +1769682198,849497856,0.0,-0.0,610.5194702148438 +1769682198,878909952,0.0,-0.0,610.5194702148438 +1769682198,914416896,0.0,-0.0,610.5194702148438 +1769682198,949228544,0.0,-0.0,610.51953125 +1769682198,979188224,0.0,-0.0,610.51953125 +1769682199,12215296,0.0,-0.0,610.51953125 +1769682199,58538752,0.0,-0.0,610.51953125 +1769682199,79518208,0.0,-0.0,610.51953125 +1769682199,112444160,0.0,-0.0,610.51953125 +1769682199,145972736,0.0,-0.0,610.51953125 +1769682199,181851136,0.0,-0.0,610.51953125 +1769682199,212603136,0.0,-0.0,610.51953125 +1769682199,248636160,0.0,-0.0,610.51953125 +1769682199,278988288,0.0,-0.0,610.51953125 +1769682199,313848064,0.0,-0.0,610.51953125 +1769682199,347606784,0.0,-0.0,610.51953125 +1769682199,379577600,0.0,-0.0,610.51953125 +1769682199,412837376,0.0,-0.0,610.51953125 +1769682199,458770432,0.0,-0.0,610.51953125 +1769682199,478819328,0.0,-0.0,610.51953125 +1769682199,514035968,0.0,-0.0,610.51953125 +1769682199,546544384,0.0,-0.0,610.51953125 +1769682199,579883264,0.0,-0.0,610.51953125 +1769682199,613348864,0.0,-0.0,610.51953125 +1769682199,652515840,0.0,-0.0,610.5195922851562 +1769682199,679008000,0.0,-0.0,610.5195922851562 +1769682199,713022208,0.0,-0.0,610.5195922851562 +1769682199,748818688,0.0,-0.0,610.5195922851562 +1769682199,779364352,0.0,-0.0,610.5195922851562 +1769682199,812263168,0.0,-0.0,610.5195922851562 +1769682199,863299072,0.0,-0.0,610.5195922851562 +1769682199,873274880,0.0,-0.0,610.5195922851562 +1769682199,913103616,0.0,-0.0,610.5195922851562 +1769682199,948838144,0.0,-0.0,610.5195922851562 +1769682199,979949312,0.0,-0.0,610.5196533203125 +1769682200,12189696,0.0,-0.0,610.5196533203125 +1769682200,50053376,0.0,-0.0,610.5196533203125 +1769682200,79229440,0.0,-0.0,610.5196533203125 +1769682200,112338432,0.0,-0.0,610.5196533203125 +1769682200,155083776,0.0,-0.0,610.5196533203125 +1769682200,178770176,0.0,-0.0,610.5196533203125 +1769682200,213524736,0.0,-0.0,610.5196533203125 +1769682200,260227072,0.0,-0.0,610.5196533203125 +1769682200,279980800,0.0,-0.0,610.5196533203125 +1769682200,314597888,0.0,-0.0,610.5196533203125 +1769682200,346783488,0.0,-0.0,610.5197143554688 +1769682200,380743424,0.0,-0.0,610.5197143554688 +1769682200,412494080,0.0,-0.0,610.5197143554688 +1769682200,447928064,0.0,-0.0,610.5197143554688 +1769682200,479210240,0.0,-0.0,610.5197143554688 +1769682200,513697536,0.0,-0.0,610.5197143554688 +1769682200,550388992,0.0,-0.0,610.5197143554688 +1769682200,579538176,0.0,-0.0,610.5197143554688 +1769682200,612252672,0.0,-0.0,610.5197143554688 +1769682200,658046464,0.0,-0.0,610.519775390625 +1769682200,679281152,0.0,-0.0,610.519775390625 +1769682200,714242304,0.0,-0.0,610.519775390625 +1769682200,747077888,0.0,-0.0,610.519775390625 +1769682200,779892736,0.0,-0.0,610.519775390625 +1769682200,812372992,0.0,-0.0,610.519775390625 +1769682200,846664704,0.0,-0.0,610.519775390625 +1769682200,879779840,0.0,-0.0,610.519775390625 +1769682200,914250496,0.0,-0.0,610.519775390625 +1769682200,949181184,0.0,-0.0,610.519775390625 +1769682200,983358976,0.0,-0.0,610.519775390625 +1769682201,13711104,0.0,-0.0,610.519775390625 +1769682201,50961664,0.0,-0.0,610.5198364257812 +1769682201,80183808,0.0,-0.0,610.5198364257812 +1769682201,112204800,0.0,-0.0,610.5198364257812 +1769682201,145797120,0.0,-0.0,610.5198364257812 +1769682201,180031488,0.0,-0.0,610.5198364257812 +1769682201,214189568,0.0,-0.0,610.5198974609375 +1769682201,247407872,0.0,-0.0,610.5198974609375 +1769682201,280477184,0.0,-0.0,610.5198974609375 +1769682201,312261888,0.0,-0.0,610.5198974609375 +1769682201,347196416,0.0,-0.0,610.5198974609375 +1769682201,379401984,0.0,-0.0,610.5199584960938 +1769682201,413069312,0.0,-0.0,610.5199584960938 +1769682201,459246848,0.0,-0.0,610.5199584960938 +1769682201,479057152,0.0,-0.0,610.5199584960938 +1769682201,513163264,0.0,-0.0,610.5199584960938 +1769682201,560775680,0.0,-0.0,610.5200805664062 +1769682201,579896320,0.0,-0.0,610.5200805664062 +1769682201,612254464,0.0,-0.0,610.5200805664062 +1769682201,647044608,0.0,-0.0,610.5200805664062 +1769682201,681948416,0.0,-0.0,610.5200805664062 +1769682201,713340160,0.0,-0.0,610.5200805664062 +1769682201,747004160,0.0,-0.0,610.5200805664062 +1769682201,779751168,0.0,-0.0,610.5200805664062 +1769682201,815056128,0.0,-0.0,610.5200805664062 +1769682201,847517440,0.0,-0.0,610.5200805664062 +1769682201,879911168,0.0,-0.0,610.5200805664062 +1769682201,912207616,0.0,-0.0,610.5201416015625 +1769682201,958910720,0.0,-0.0,610.5201416015625 +1769682201,980755712,0.0,-0.0,610.5201416015625 +1769682202,12660736,0.0,-0.0,610.5201416015625 +1769682202,47124736,0.0,-0.0,610.5201416015625 +1769682202,84957184,0.0,-0.0,610.5202026367188 +1769682202,113704704,0.0,-0.0,610.5202026367188 +1769682202,147710208,0.0,-0.0,610.5202026367188 +1769682202,178944768,0.0,-0.0,610.5202026367188 +1769682202,217677312,0.0,-0.0,610.520263671875 +1769682202,251035904,0.0,-0.0,610.520263671875 +1769682202,280160256,0.0,-0.0,610.520263671875 +1769682202,312545024,0.0,-0.0,610.520263671875 +1769682202,357021696,0.0,-0.0,610.520263671875 +1769682202,379308800,0.0,-0.0,610.520263671875 +1769682202,412445440,0.0,-0.0,610.520263671875 +1769682202,463823872,0.0,-0.0,610.5203247070312 +1769682202,482069760,0.0,-0.0,610.5203247070312 +1769682202,503348224,0.0,-0.0,610.5203247070312 +1769682202,547123456,0.0,-0.0,610.5203857421875 +1769682202,579943424,0.0,-0.0,610.5203857421875 +1769682202,613009664,0.0,-0.0,610.5203857421875 +1769682202,654123008,0.0,-0.0,610.5203857421875 +1769682202,681254144,0.0,-0.0,610.5204467773438 +1769682202,713339136,0.0,-0.0,610.5204467773438 +1769682202,759206912,0.0,-0.0,610.5204467773438 +1769682202,779421440,0.0,-0.0,610.5205078125 +1769682202,812734720,0.0,-0.0,610.5205078125 +1769682202,847097600,0.0,-0.0,610.5205078125 +1769682202,886426112,0.0,-0.0,610.5205078125 +1769682202,912331008,0.0,-0.0,610.5205078125 +1769682202,949532416,0.0,-0.0,610.5205078125 +1769682202,980490240,0.0,-0.0,610.5205078125 +1769682203,15202304,0.0,-0.0,610.5205078125 +1769682203,48718336,0.0,-0.0,610.5205688476562 +1769682203,79863040,0.0,-0.0,610.5205688476562 +1769682203,112389120,0.0,-0.0,610.5205688476562 +1769682203,163217408,0.0,-0.0,610.5206909179688 +1769682203,168869632,0.0,-0.0,610.5206909179688 +1769682203,212481280,0.0,-0.0,610.5206909179688 +1769682203,246100480,0.0,-0.0,610.5206909179688 +1769682203,281476864,0.0,-0.0,610.520751953125 +1769682203,313844736,0.0,-0.0,610.520751953125 +1769682203,347720448,0.0,-0.0,610.520751953125 +1769682203,379842304,0.0,-0.0,610.520751953125 +1769682203,413231872,0.0,-0.0,610.520751953125 +1769682203,450597632,0.0,-0.0,610.520751953125 +1769682203,479440640,0.0,-0.0,610.520751953125 +1769682203,512481536,0.0,-0.0,610.5208129882812 +1769682203,559383552,0.0,-0.0,610.5208129882812 +1769682203,580184320,0.0,-0.0,610.5208129882812 +1769682203,613138688,0.0,-0.0,610.5208129882812 +1769682203,647651584,0.0,-0.0,610.5208740234375 +1769682203,683921664,0.0,-0.0,610.5208740234375 +1769682203,713466368,0.0,-0.0,610.5208740234375 +1769682203,750812416,0.0,-0.0,610.5209350585938 +1769682203,779480320,0.0,-0.0,610.5209350585938 +1769682203,814372352,0.0,-0.0,610.5209350585938 +1769682203,850275072,0.0,-0.0,610.52099609375 +1769682203,879459584,0.0,-0.0,610.52099609375 +1769682203,912735488,0.0,-0.0,610.52099609375 +1769682203,965593344,0.0,-0.0,610.52099609375 +1769682203,971025664,0.0,-0.0,610.52099609375 +1769682204,12472064,0.0,-0.0,610.52099609375 +1769682204,47509248,0.0,-0.0,610.52099609375 +1769682204,79958272,0.0,-0.0,610.52099609375 +1769682204,112469248,0.0,-0.0,610.5210571289062 +1769682204,146753536,0.0,-0.0,610.5210571289062 +1769682204,179516416,0.0,-0.0,610.5210571289062 +1769682204,212925952,0.0,-0.0,610.5211181640625 +1769682204,249913856,0.0,-0.0,610.5211181640625 +1769682204,283777024,0.0,-0.0,610.5211181640625 +1769682204,312459008,0.0,-0.0,610.5211181640625 +1769682204,346625024,0.0,-0.0,610.521240234375 +1769682204,379767552,0.0,-0.0,610.521240234375 +1769682204,413758464,0.0,-0.0,610.521240234375 +1769682204,449177600,0.0,-0.0,610.521240234375 +1769682204,480097792,0.0,-0.0,610.521240234375 +1769682204,512474112,0.0,-0.0,610.521240234375 +1769682204,549072384,0.0,-0.0,610.521240234375 +1769682204,580157440,0.0,-0.0,610.521240234375 +1769682204,617533440,0.0,-0.0,610.521240234375 +1769682204,649853440,0.0,-0.0,610.521240234375 +1769682204,680472064,0.0,-0.0,610.5213012695312 +1769682204,713019136,0.0,-0.0,610.5213012695312 +1769682204,760906496,0.0,-0.0,610.5213012695312 +1769682204,779703040,0.0,-0.0,610.5213012695312 +1769682204,812841728,0.0,-0.0,610.5213012695312 +1769682204,847204608,0.0,-0.0,610.5213623046875 +1769682204,880687360,0.0,-0.0,610.5213623046875 +1769682204,913062912,0.0,-0.0,610.5213623046875 +1769682204,948263424,0.0,-0.0,610.5213623046875 +1769682204,980289024,0.0,-0.0,610.5213623046875 +1769682205,13211392,0.0,-0.0,610.5213623046875 +1769682205,48832000,0.0,-0.0,610.5214233398438 +1769682205,80444928,0.0,-0.0,610.5214233398438 +1769682205,114045952,0.0,-0.0,610.5214233398438 +1769682205,161984256,0.0,-0.0,610.5214233398438 +1769682205,181650688,0.0,-0.0,610.5214233398438 +1769682205,212833024,0.0,-0.0,610.521484375 +1769682205,265981696,0.0,-0.0,610.521484375 +1769682205,276981248,0.0,-0.0,610.521484375 +1769682205,330940672,0.0,-0.0,610.521484375 +1769682205,347456256,0.0,-0.0,610.521484375 +1769682205,384185856,0.0,-0.0,610.521484375 +1769682205,412777984,0.0,-0.0,610.521484375 +1769682205,496438784,0.0,-0.0,610.521484375 +1769682205,515661056,0.0,-0.0,610.521484375 +1769682205,547452672,0.0,-0.0,610.521484375 +1769682205,579428864,0.0,-0.0,610.5215454101562 +1769682205,613837312,0.0,-0.0,610.5215454101562 +1769682205,659735808,0.0,-0.0,610.5215454101562 +1769682205,667964928,0.0,-0.0,610.5215454101562 +1769682205,712635904,0.0,-0.0,610.5215454101562 +1769682205,747085312,0.0,-0.0,610.5216064453125 +1769682205,781574144,0.0,-0.0,610.5216064453125 +1769682205,813678848,0.0,-0.0,610.5216064453125 +1769682205,848017664,0.0,-0.0,610.5216064453125 +1769682205,880130048,0.0,-0.0,610.5216064453125 +1769682205,914196992,0.0,-0.0,610.5216064453125 +1769682205,947583232,0.0,-0.0,610.5216674804688 +1769682205,979836928,0.0,-0.0,610.5216674804688 +1769682206,13129472,0.0,-0.0,610.5216674804688 +1769682206,58359552,0.0,-0.0,610.5216674804688 +1769682206,413651200,0.0,-0.0,610.521728515625 +1769682206,449827328,0.0,-0.0,610.521728515625 +1769682206,480384768,0.0,-0.0,610.5218505859375 +1769682206,513718016,0.0,-0.0,610.5218505859375 +1769682206,546755840,0.0,-0.0,610.5218505859375 +1769682206,569829888,0.0,-0.0,610.5218505859375 +1769682206,612945152,0.0,-0.0,610.5218505859375 +1769682206,650286080,0.0,-0.0,610.5219116210938 +1769682206,680046848,0.0,-0.0,610.5219116210938 +1769682206,714145536,0.0,-0.0,610.5219116210938 +1769682206,752692992,0.0,-0.0,610.5219116210938 +1769682206,780060928,0.0,-0.0,610.5219116210938 +1769682206,812741632,0.0,-0.0,610.5219116210938 +1769682206,857533440,0.0,-0.0,610.52197265625 +1769682206,880605696,0.0,-0.0,610.52197265625 +1769682206,913282304,0.0,-0.0,610.52197265625 +1769682206,957183744,0.0,-0.0,610.52197265625 +1769682206,979593472,0.0,-0.0,610.52197265625 +1769682207,446772992,0.0,-0.0,610.5220947265625 +1769682207,480016640,0.0,-0.0,610.5220947265625 +1769682207,513811456,0.0,-0.0,610.5220947265625 +1769682207,548257280,0.0,-0.0,610.5221557617188 +1769682207,580140288,0.0,-0.0,610.5221557617188 +1769682207,615123200,0.0,-0.0,610.5221557617188 +1769682207,647401984,0.0,-0.0,610.5221557617188 +1769682207,680175104,0.0,-0.0,610.5221557617188 +1769682207,713165312,0.0,-0.0,610.522216796875 +1769682207,751116544,0.0,-0.0,610.522216796875 +1769682207,781094912,0.0,-0.0,610.522216796875 +1769682207,813607680,0.0,-0.0,610.522216796875 +1769682207,848231168,0.0,-0.0,610.522216796875 +1769682207,879717120,0.0,-0.0,610.522216796875 +1769682207,913111808,0.0,-0.0,610.522216796875 +1769682207,946620928,0.0,-0.0,610.522216796875 +1769682207,980966400,0.0,-0.0,610.522216796875 +1769682208,13793280,0.0,-0.0,610.522216796875 +1769682208,479720192,0.0,-0.0,610.5223999023438 +1769682208,514244352,0.0,-0.0,610.5223999023438 +1769682208,550054400,0.0,-0.0,610.5223999023438 +1769682208,580701696,0.0,-0.0,610.5223999023438 +1769682208,613005568,0.0,-0.0,610.5223999023438 +1769682208,646714368,0.0,-0.0,610.5223999023438 +1769682208,681321216,0.0,-0.0,610.5223999023438 +1769682208,714007552,0.0,-0.0,610.5223999023438 +1769682208,748898304,0.0,-0.0,610.5223999023438 +1769682208,780890112,0.0,-0.0,610.5223999023438 +1769682208,813432832,0.0,-0.0,610.5223999023438 +1769682208,847763200,0.0,-0.0,610.5223999023438 +1769682208,880700672,0.0,-0.0,610.5223999023438 +1769682208,914050816,0.0,-0.0,610.5223999023438 +1769682208,948689152,0.0,-0.0,610.5223999023438 +1769682208,980248064,0.0,-0.0,610.5223999023438 +1769682209,13663232,0.0,-0.0,610.5223999023438 +1769682209,48967680,0.0,-0.0,610.5223999023438 +1769682209,550690560,0.0,-0.0,610.5223999023438 +1769682209,581540864,0.0,-0.0,610.5223999023438 +1769682209,613680640,0.0,-0.0,610.5223999023438 +1769682209,648251648,0.0,-0.0,610.5223999023438 +1769682209,681176064,0.0,-0.0,610.5223999023438 +1769682209,713235968,0.0,-0.0,610.5223999023438 +1769682209,748465920,0.0,-0.0,610.5223999023438 +1769682209,783519744,0.0,-0.0,610.5223999023438 +1769682209,814968064,0.0,-0.0,610.5223999023438 +1769682209,848047104,0.0,-0.0,610.5223999023438 +1769682209,879817728,0.0,-0.0,610.5223999023438 +1769682209,914148352,0.0,-0.0,610.5223999023438 +1769682209,951064064,0.0,-0.0,610.5223999023438 +1769682209,982614528,0.0,-0.0,610.5223999023438 +1769682210,13415936,0.0,-0.0,610.5223999023438 +1769682210,62181376,0.0,-0.0,610.5223999023438 +1769682210,69845760,0.0,-0.0,610.5223999023438 +1769682210,613713152,0.0,-0.0,610.5223999023438 +1769682210,647152896,0.0,-0.0,610.5223999023438 +1769682210,680732160,0.0,-0.0,610.5223999023438 +1769682210,714959360,0.0,-0.0,610.5223999023438 +1769682210,751610880,0.0,-0.0,610.5223999023438 +1769682210,780151296,0.0,-0.0,610.5223999023438 +1769682210,813879040,0.0,-0.0,610.5223999023438 +1769682210,850827008,0.0,-0.0,610.5223999023438 +1769682210,880617984,0.0,-0.0,610.5223999023438 +1769682210,913469440,0.0,-0.0,610.5223999023438 +1769682210,960053248,0.0,-0.0,610.5223999023438 +1769682210,979924736,0.0,-0.0,610.5223999023438 +1769682211,13974528,0.0,-0.0,610.5223999023438 +1769682211,48370432,0.0,-0.0,610.5223999023438 +1769682211,81715968,0.0,-0.0,610.5223999023438 +1769682211,113379840,0.0,-0.0,610.5223999023438 +1769682211,147083776,0.0,-0.0,610.5223999023438 +1769682211,183228416,0.0,-0.0,610.5223999023438 +1769682211,213723392,0.0,-0.0,610.5223999023438 +1769682211,682214400,0.0,-0.0,610.5223999023438 +1769682211,714928640,0.0,-0.0,610.5223999023438 +1769682211,765383424,0.0,-0.0,610.5223999023438 +1769682211,772264960,0.0,-0.0,610.5223999023438 +1769682211,813314816,0.0,-0.0,610.5223999023438 +1769682211,862832384,0.0,-0.0,610.5223999023438 +1769682211,870007808,0.0,-0.0,610.5223999023438 +1769682211,913292800,0.0,-0.0,610.5223999023438 +1769682211,947898624,0.0,-0.0,610.5223999023438 +1769682211,980865792,0.0,-0.0,610.5223999023438 +1769682212,14882304,0.0,-0.0,610.5223999023438 +1769682212,48634624,0.0,-0.0,610.5223999023438 +1769682212,80637184,0.0,-0.0,610.5223999023438 +1769682212,114171904,0.0,-0.0,610.5223999023438 +1769682212,149696512,0.0,-0.0,610.5223999023438 +1769682212,181921536,0.0,-0.0,610.5223999023438 +1769682212,213685760,0.0,-0.0,610.5223999023438 +1769682212,260640000,0.0,-0.0,610.5223999023438 +1769682212,280925696,0.0,-0.0,610.5223999023438 +1769682212,762665472,0.0,-0.0,610.5223999023438 +1769682212,768870400,0.0,-0.0,610.5223999023438 +1769682212,814328832,0.0,-0.0,610.5223999023438 +1769682212,847870464,0.0,-0.0,610.5223999023438 +1769682212,881034496,0.0,-0.0,610.5223999023438 +1769682212,913886464,0.0,-0.0,610.5223999023438 +1769682212,948845568,0.0,-0.0,610.5223999023438 +1769682212,980126464,0.0,-0.0,610.5223999023438 +1769682213,15469824,0.0,-0.0,610.5223999023438 +1769682213,59959040,0.0,-0.0,610.5223999023438 +1769682213,80347904,0.0,-0.0,610.5223999023438 +1769682213,114457600,0.0,-0.0,610.5223999023438 +1769682213,159570944,0.0,-0.0,610.5223999023438 +1769682213,180527360,0.0,-0.0,610.5223999023438 +1769682213,213548032,0.0,-0.0,610.5223999023438 +1769682213,250955008,0.0,-0.0,610.5223999023438 +1769682213,283951616,0.0,-0.0,610.5223999023438 +1769682213,851806976,0.06103570759296417,0.010404916480183601,610.494873046875 +1769682213,881264640,0.07321997731924057,0.01142288837581873,610.487548828125 +1769682213,913535232,0.08536332100629807,0.012067525647580624,610.4796142578125 +1769682213,960177664,0.10195944458246231,0.012808654457330704,610.4674682617188 +1769682213,969041408,0.11040974408388138,0.013099785894155502,610.4608764648438 +1769682214,14630912,0.127756267786026,0.013542931526899338,610.4466552734375 +1769682214,49905664,0.14547181129455566,0.013832507655024529,610.4309692382812 +1769682214,81401088,0.15883423388004303,0.013978192582726479,610.4183349609375 +1769682214,114237440,0.17218510806560516,0.014079300686717033,610.4049682617188 +1769682214,150128640,0.19035829603672028,0.01418958231806755,610.3860473632812 +1769682214,180818944,0.20410384237766266,0.014251109212636948,610.3710327148438 +1769682214,214877696,0.2182924896478653,0.014323979616165161,610.355224609375 +1769682214,252725760,0.23831325769424438,0.0144476518034935,610.3328857421875 +1769682214,280498432,0.25382062792778015,0.01455911248922348,610.315185546875 +1769682214,313824256,0.2699202001094818,0.014686893671751022,610.296630859375 +1769682214,361282304,0.28999051451683044,0.014829099178314209,610.2703247070312 +1769682214,369785856,0.29878631234169006,0.014865610748529434,610.2567138671875 +1769682214,414332160,0.31466060876846313,0.014967937022447586,610.2290649414062 +1769682214,447556096,0.3281581699848175,0.015035275369882584,610.2013549804688 +1769682214,949974784,0.551561713218689,0.01836484670639038,609.791748046875 +1769682214,987657472,0.5723786950111389,0.018817901611328125,609.7582397460938 +1769682215,14424576,0.5933755040168762,0.01926606148481369,609.7238159179688 +1769682215,49449728,0.6217347979545593,0.01983276754617691,609.6763916015625 +1769682215,80876288,0.6427223682403564,0.020249664783477783,609.6395263671875 +1769682215,114425344,0.6635723114013672,0.02062854915857315,609.6018676757812 +1769682215,150853632,0.690416157245636,0.02112489938735962,609.550048828125 +1769682215,181174784,0.7096025347709656,0.02147415280342102,609.5101928710938 +1769682215,213793280,0.7286855578422546,0.021834060549736023,609.4696044921875 +1769682215,258285312,0.7560700178146362,0.02235954999923706,609.413818359375 +1769682215,281172992,0.7766503095626831,0.0227673202753067,609.3705444335938 +1769682215,314899200,0.7973412871360779,0.023189112544059753,609.325927734375 +1769682215,347693824,0.8252719044685364,0.023797065019607544,609.2643432617188 +1769682215,382423040,0.8463760018348694,0.02426964044570923,609.2164916992188 +1769682215,415555840,0.8675685524940491,0.024750977754592896,609.167236328125 +1769682215,449410560,0.8959264159202576,0.025415167212486267,609.0990600585938 +1769682215,480963328,0.9173049926757812,0.025928333401679993,609.0462036132812 +1769682215,514875136,0.9387401342391968,0.026460111141204834,608.9918823242188 +1769682216,15371264,1.2956031560897827,0.03644898533821106,607.8302612304688 +1769682216,54428416,1.323475956916809,0.03704670071601868,607.7158203125 +1769682216,82000128,1.3442500829696655,0.037444889545440674,607.6276245117188 +1769682216,113999616,1.365081787109375,0.03781035542488098,607.5376586914062 +1769682216,149875456,1.3925522565841675,0.03862786293029785,607.41552734375 +1769682216,172985600,1.4062726497650146,0.03891664743423462,607.3536987304688 +1769682216,216479744,1.433323860168457,0.040424853563308716,607.2280883789062 +1769682216,248570880,1.4603185653686523,0.041661977767944336,607.099609375 +1769682216,281504512,1.480518102645874,0.04258468747138977,607.001220703125 +1769682216,314105344,1.5007197856903076,0.04349642992019653,606.9009399414062 +1769682216,351474432,1.5277384519577026,0.04470476508140564,606.7640380859375 +1769682216,381028608,1.5480738878250122,0.04566621780395508,606.6588745117188 +1769682216,414101504,1.5683039426803589,0.046616554260253906,606.5511474609375 +1769682216,451370752,1.595153570175171,0.04786956310272217,606.4036254882812 +1769682216,481918464,1.6152143478393555,0.04884052276611328,606.289794921875 +1769682216,513860096,1.6351344585418701,0.04978346824645996,606.1732788085938 +1769682216,561142784,1.6617722511291504,0.051036834716796875,606.0137939453125 +1769682216,569040640,1.6750487089157104,0.051442235708236694,605.9320678710938 +1769682217,114829056,2.024792432785034,0.06842169165611267,603.1353759765625 +1769682217,150020864,2.0496199131011963,0.06974920630455017,602.880615234375 +1769682217,181135360,2.0680625438690186,0.07074320316314697,602.6859130859375 +1769682217,214512896,2.0864369869232178,0.07172095775604248,602.4879760742188 +1769682217,250469888,2.110809803009033,0.07300496101379395,602.2194213867188 +1769682217,281689856,2.1290431022644043,0.07397621870040894,602.0144653320312 +1769682217,314854144,2.1471028327941895,0.07489514350891113,601.8065185546875 +1769682217,352030720,2.171006441116333,0.07603180408477783,601.524658203125 +1769682217,382893056,2.1888668537139893,0.0768468976020813,601.3101806640625 +1769682217,415529216,2.206591844558716,0.07760864496231079,601.0931396484375 +1769682217,449263104,2.230024576187134,0.07863503694534302,600.7999267578125 +1769682217,473219328,2.24169659614563,0.07823199033737183,600.6515502929688 +1769682217,514353664,2.2649683952331543,0.07992446422576904,600.3512573242188 +1769682217,547707136,2.288137674331665,0.08047938346862793,600.0459594726562 +1769682217,581801472,2.3053128719329834,0.08104324340820312,599.8130493164062 +1769682217,615286272,2.3215482234954834,0.0817708969116211,599.5763549804688 +1769682217,648750848,2.3428876399993896,0.08313459157943726,599.2550048828125 +1769682217,682823936,2.358797073364258,0.08429133892059326,599.0093994140625 +1769682217,714868224,2.3746285438537598,0.08551663160324097,598.7595825195312 +1769682218,214104064,2.60992431640625,0.11176192760467529,593.9683227539062 +1769682218,260209152,2.6259915828704834,0.1137920618057251,593.5325317382812 +1769682218,280855552,2.6379234790802,0.11523598432540894,593.2008666992188 +1769682218,314087936,2.6496224403381348,0.11655247211456299,592.8651123046875 +1769682218,347826944,2.6648786067962646,0.11837798357009888,592.411376953125 +1769682218,381497088,2.676172971725464,0.1197577714920044,592.0662231445312 +1769682218,414872064,2.6872620582580566,0.12116950750350952,591.7166748046875 +1769682218,448879872,2.701831340789795,0.12310820817947388,591.243408203125 +1769682218,482205184,2.7126426696777344,0.12470752000808716,590.8828735351562 +1769682218,514742272,2.723262071609497,0.1263074278831482,590.5169677734375 +1769682218,549879808,2.73726224899292,0.12868422269821167,590.0211791992188 +1769682218,581385216,2.7475945949554443,0.1306949257850647,589.6431884765625 +1769682218,614417664,2.7579495906829834,0.13244974613189697,589.259765625 +1769682218,658602240,2.771883964538574,0.13407325744628906,588.7384033203125 +1769682218,680763136,2.7821788787841797,0.13520121574401855,588.3397827148438 +1769682218,714463744,2.7924137115478516,0.13628172874450684,587.9348754882812 +1769682218,760718848,2.8058784008026123,0.13769912719726562,587.3855590820312 +1769682218,768067072,2.812584161758423,0.13700520992279053,587.1072998046875 +1769682219,281264640,2.9619827270507812,0.16224157810211182,579.3280029296875 +1769682219,314994688,2.9692230224609375,0.16354310512542725,578.8350830078125 +1769682219,351509760,2.9785866737365723,0.16581511497497559,578.1719970703125 +1769682219,381148160,2.985398292541504,0.1676245927810669,577.6698608398438 +1769682219,416422656,2.992027997970581,0.1693969964981079,577.163330078125 +1769682219,451839232,3.0006935596466064,0.17166686058044434,576.4806518554688 +1769682219,480901120,3.0070383548736572,0.17338240146636963,575.9632568359375 +1769682219,514323712,3.0132033824920654,0.1750890016555786,575.4414672851562 +1769682219,559220992,3.0213663578033447,0.17734122276306152,574.7388916015625 +1769682219,581066752,3.027401924133301,0.17903196811676025,574.2069091796875 +1769682219,615183360,3.0333893299102783,0.18065428733825684,573.6703491210938 +1769682219,649313792,3.0411977767944336,0.1826002597808838,572.9481811523438 +1769682219,685675264,3.04707932472229,0.18385612964630127,572.4008178710938 +1769682219,714441984,3.052924871444702,0.18496441841125488,571.84912109375 +1769682219,766531584,3.0605356693267822,0.18636715412139893,571.1068725585938 +1769682219,772660992,3.0646045207977295,0.1818525791168213,570.73291015625 +1769682219,814243072,3.0717644691467285,0.1882873773574829,569.9796142578125 +1769682220,358793728,3.157902240753174,0.21350741386413574,559.0431518554688 +1769682220,381307648,3.162076950073242,0.21513962745666504,558.3922729492188 +1769682220,414526720,3.1662607192993164,0.21670663356781006,557.7373046875 +1769682220,448191744,3.1716723442077637,0.21872448921203613,556.8578491210938 +1769682220,472167936,3.174564838409424,0.21577811241149902,556.4155883789062 +1769682220,514971904,3.1793811321258545,0.22168588638305664,555.5258178710938 +1769682220,548999168,3.1841957569122314,0.22354602813720703,554.6292114257812 +1769682220,581433088,3.1876282691955566,0.2248220443725586,553.952392578125 +1769682220,614877952,3.190836191177368,0.2260533571243286,553.2715454101562 +1769682220,648373504,3.19492244720459,0.22763586044311523,552.3576049804688 +1769682220,681779712,3.197789192199707,0.2286992073059082,551.66748046875 +1769682220,714551296,3.200552463531494,0.2298896312713623,550.9733276367188 +1769682220,749452288,3.204064130783081,0.2310163974761963,550.0404052734375 +1769682220,781481728,3.2064647674560547,0.23190736770629883,549.3345947265625 +1769682220,815639808,3.208625555038452,0.23274433612823486,548.6240234375 +1769682220,860748544,3.2112667560577393,0.2337968349456787,547.6697998046875 +1769682220,869486080,3.212711811065674,0.2311255931854248,547.1902465820312 +1769682220,914784256,3.2146639823913574,0.23509609699249268,546.2269897460938 +1769682220,948059648,3.216716766357422,0.23575162887573242,545.2590942382812 +1769682221,383920640,3.2227940559387207,0.24900352954864502,534.6292114257812 +1769682221,415661056,3.2222769260406494,0.25018179416656494,533.8701782226562 +1769682221,452448000,3.2214250564575195,0.25170910358428955,532.8531494140625 +1769682221,482677248,3.2207255363464355,0.2528672218322754,532.0865478515625 +1769682221,514694656,3.219949245452881,0.2539944648742676,531.3165283203125 +1769682221,548813312,3.218905448913574,0.25536656379699707,530.2849731445312 +1769682221,581344256,3.218184471130371,0.25636208057403564,529.5078735351562 +1769682221,614788864,3.2174510955810547,0.25732409954071045,528.7281494140625 +1769682221,653980160,3.216538667678833,0.25860774517059326,527.6845703125 +1769682221,682299136,3.2159481048583984,0.2595553398132324,526.8989868164062 +1769682221,714618880,3.2154157161712646,0.2604731321334839,526.11083984375 +1769682221,749705216,3.214677095413208,0.26160264015197754,525.0562744140625 +1769682221,783798016,3.214050769805908,0.26237523555755615,524.2623901367188 +1769682221,815033856,3.2134478092193604,0.26305651664733887,523.4661254882812 +1769682221,850742272,3.212834358215332,0.2638152837753296,522.4012451171875 +1769682221,881207552,3.212493419647217,0.2643120288848877,521.6005859375 +1769682221,916864512,3.2122528553009033,0.2649264335632324,520.7984619140625 +1769682221,957552128,3.21199631690979,0.26540541648864746,519.7257080078125 +1769682222,482626560,3.21395206451416,0.25331807136535645,505.7213439941406 +1769682222,514863872,3.2109153270721436,0.2524813413619995,504.9518127441406 +1769682222,548831744,3.2076656818389893,0.25124162435531616,503.93450927734375 +1769682222,581821952,3.206486940383911,0.25036197900772095,503.17718505859375 +1769682222,617517312,3.206105947494507,0.24948465824127197,502.4239501953125 +1769682222,652703488,3.2045271396636963,0.24808990955352783,501.4254455566406 +1769682222,681211648,3.2030189037323,0.24711906909942627,500.6814270019531 +1769682222,714743808,3.2013115882873535,0.24609047174453735,499.9416198730469 +1769682222,758190592,3.199012041091919,0.24447423219680786,498.96270751953125 +1769682222,771592448,3.196281671524048,0.23735278844833374,498.47686767578125 +1769682222,814609920,3.188858985900879,0.24090224504470825,497.5151062011719 +1769682222,850384896,3.1822423934936523,0.23839318752288818,496.5672302246094 +1769682222,883341312,3.1787943840026855,0.23670589923858643,495.8645324707031 +1769682222,915484672,3.176863193511963,0.23516839742660522,495.16754150390625 +1769682222,948517376,3.1749351024627686,0.23311489820480347,494.24505615234375 +1769682222,981682432,3.173989772796631,0.23136776685714722,493.55743408203125 +1769682223,16192000,3.1735544204711914,0.2295720875263214,492.8731994628906 +1769682223,48303616,3.173124313354492,0.2271462082862854,491.9662780761719 +1769682223,82659584,3.173424243927002,0.22529056668281555,491.2903747558594 +1769682223,114579712,3.1740739345550537,0.22337058186531067,490.6185302734375 +1769682223,148581120,3.175323963165283,0.22062602639198303,489.72967529296875 +1769682223,181209856,3.176405191421509,0.21853819489479065,489.0691223144531 +1769682223,215245824,3.1778669357299805,0.21672847867012024,488.4140930175781 +1769682223,249088000,3.180328607559204,0.21443602442741394,487.54937744140625 +1769682223,282373632,3.182634115219116,0.212680846452713,486.9071350097656 +1769682223,314788608,3.1852288246154785,0.21084672212600708,486.2704162597656 +1769682223,349064448,3.188873052597046,0.2077530473470688,485.4297180175781 +1769682235,250595840,0.0,-0.0,451.21014404296875 +1769682235,283861504,0.0,-0.0,451.210205078125 +1769682235,306318592,0.0,-0.0,451.210205078125 +1769682235,350250240,0.0,-0.0,451.210205078125 +1769682235,382697728,0.0,-0.0,451.210205078125 +1769682235,416664832,0.0,-0.0,451.21026611328125 +1769682235,453504256,0.0,-0.0,451.21026611328125 +1769682235,469904384,0.0,-0.0,451.21026611328125 +1769682235,516407296,0.0,-0.0,451.2103271484375 +1769682235,550402304,0.0,-0.0,451.2103271484375 +1769682235,570142208,0.0,-0.0,451.2103271484375 +1769682235,615940096,0.0,-0.0,451.2103576660156 diff --git a/userland/Cargo.toml b/userland/Cargo.toml index ab94f86dc..c6fac4eaa 100644 --- a/userland/Cargo.toml +++ b/userland/Cargo.toml @@ -66,6 +66,10 @@ optional = true path = "../applications/tests/test_dag" optional = true +[dependencies.test_autoware] +path = "../applications/tests/test_autoware" +optional = true + [dependencies.test_dvfs] path = "../applications/tests/test_dvfs" optional = true @@ -75,7 +79,7 @@ path = "../applications/tests/test_voluntary_preemption" optional = true [features] -default = ["test_dag"] +default = ["test_autoware"] perf = ["awkernel_services/perf"] # Evaluation applications @@ -93,4 +97,5 @@ test_gedf = ["dep:test_gedf"] test_measure_channel = ["dep:test_measure_channel"] test_measure_channel_heavy = ["dep:test_measure_channel_heavy"] test_dag = ["dep:test_dag"] +test_autoware = ["dep:test_autoware"] test_voluntary_preemption = ["dep:test_voluntary_preemption"] From dda7c64835458676e776adef9c3bc9d269247cd0 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Tue, 17 Mar 2026 17:00:22 +0900 Subject: [PATCH 02/60] fix: perf features and test_dag for sending period info Signed-off-by: nokosaaan --- applications/tests/test_dag/src/lib.rs | 52 +- awkernel_async_lib/src/dag.rs | 239 +++++++++- awkernel_async_lib/src/pubsub.rs | 80 +++- awkernel_async_lib/src/task.rs | 608 +++++++++++++++++++++++- awkernel_async_lib/src/time_interval.rs | 13 +- 5 files changed, 932 insertions(+), 60 deletions(-) diff --git a/applications/tests/test_dag/src/lib.rs b/applications/tests/test_dag/src/lib.rs index a7330457f..4b17b9746 100644 --- a/applications/tests/test_dag/src/lib.rs +++ b/applications/tests/test_dag/src/lib.rs @@ -1,13 +1,15 @@ #![no_std] extern crate alloc; -use alloc::{borrow::Cow, vec}; +use alloc::{borrow::Cow, vec, sync::Arc}; use awkernel_async_lib::dag::{create_dag, finish_create_dags}; use awkernel_async_lib::scheduler::SchedulerType; use awkernel_lib::delay::wait_microsec; use core::time::Duration; +use awkernel_async_lib::task::perf::get_period_count; -const LOG_ENABLE: bool = true; +const LOG_ENABLE: bool = false; +const DATA_SIZE: usize = 128; pub async fn run() { wait_microsec(1000000); @@ -18,16 +20,18 @@ pub async fn run() { log::debug!("period is {} [ns]", period.as_nanos()); let dag = create_dag(); + let dag_id = dag.get_id(); - dag.register_periodic_reactor::<_, (i32,)>( + dag.register_periodic_reactor::<_, ((Arc<[u8; DATA_SIZE]>, u32),)>( "reactor_source_node".into(), - move || -> (i32,) { + move || -> ((Arc<[u8; DATA_SIZE]>, u32),) { wait_microsec(exe_time); - let number: i32 = 1; + let data: Arc<[u8; DATA_SIZE]> = Arc::new([0; DATA_SIZE]); + let period_id = get_period_count(dag_id as usize) as u32; if LOG_ENABLE { - log::debug!("value={number} in reactor_source_node"); + log::debug!("Sending data[0]={}, period_id={}, size={} in reactor_source_node", data[0], period_id, DATA_SIZE); } - (number,) + ((data, period_id),) }, vec![Cow::from("topic0")], SchedulerType::GEDF(5), @@ -35,15 +39,14 @@ pub async fn run() { ) .await; - dag.register_reactor::<_, (i32,), (i32, i32)>( + dag.register_reactor::<_, ((Arc<[u8; DATA_SIZE]>, u32),), ((Arc<[u8; DATA_SIZE]>, u32), (Arc<[u8; DATA_SIZE]>, u32))>( "reactor_node1".into(), - |(a,): (i32,)| -> (i32, i32) { - let value = a + 1; + move |((data, period),): ((Arc<[u8; DATA_SIZE]>, u32),)| -> ((Arc<[u8; DATA_SIZE]>, u32), (Arc<[u8; DATA_SIZE]>, u32)) { if LOG_ENABLE { - log::debug!("value={value} in reactor_node1"); + log::debug!("Processing data[0]={}, period={}, size={} in reactor_node1", data[0], period, DATA_SIZE); } - (value, value + 1) + ((data.clone(), period), (data, period)) }, vec![Cow::from("topic0")], vec![Cow::from("topic1"), Cow::from("topic2")], @@ -51,14 +54,13 @@ pub async fn run() { ) .await; - dag.register_reactor::<_, (i32,), (i32,)>( + dag.register_reactor::<_, ((Arc<[u8; DATA_SIZE]>, u32),), ((Arc<[u8; DATA_SIZE]>, u32),)>( "reactor_node2".into(), - |(a,): (i32,)| -> (i32,) { - let value = a * 2; + |((data, period),): ((Arc<[u8; DATA_SIZE]>, u32),)| -> ((Arc<[u8; DATA_SIZE]>, u32),) { if LOG_ENABLE { - log::debug!("value={value} in reactor_node2"); + log::debug!("Processing data[0]={}, period={}, size={} in reactor_node2", data[0], period, DATA_SIZE); } - (value,) + ((data, period),) }, vec![Cow::from("topic1")], vec![Cow::from("topic3")], @@ -66,14 +68,13 @@ pub async fn run() { ) .await; - dag.register_reactor::<_, (i32,), (i32,)>( + dag.register_reactor::<_, ((Arc<[u8; DATA_SIZE]>, u32),), ((Arc<[u8; DATA_SIZE]>, u32),)>( "reactor_node3".into(), - |(a,): (i32,)| -> (i32,) { - let value = a * 3; + |((data, period),): ((Arc<[u8; DATA_SIZE]>, u32),)| -> ((Arc<[u8; DATA_SIZE]>, u32),) { if LOG_ENABLE { - log::debug!("value={value} in reactor_node3"); + log::debug!("Processing data[0]={}, period={}, size={} in reactor_node3", data[0], period, DATA_SIZE); } - (value,) + ((data, period),) }, vec![Cow::from("topic2")], vec![Cow::from("topic4")], @@ -81,12 +82,11 @@ pub async fn run() { ) .await; - dag.register_sink_reactor::<_, (i32, i32)>( + dag.register_sink_reactor::<_, ((Arc<[u8; DATA_SIZE]>, u32), (Arc<[u8; DATA_SIZE]>, u32))>( "reactor_node4".into(), - |(a, b): (i32, i32)| { - let value = a + b; + |((data1, period1), (data2, period2)): ((Arc<[u8; DATA_SIZE]>, u32), (Arc<[u8; DATA_SIZE]>, u32))| { if LOG_ENABLE { - log::debug!("value={value} in reactor_node4"); + log::debug!("Received data1[0]={}, data2[0]={}, period1={}, period2={}, size={} in reactor_node4", data1[0], data2[0], period1, period2, DATA_SIZE); } }, vec![Cow::from("topic3"), Cow::from("topic4")], diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index fa150a48f..533b6bdab 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -54,18 +54,17 @@ mod visit; mod performance; use crate::{ + Attribute, MultipleReceiver, MultipleSender, VectorToPublishers, VectorToSubscribers, dag::{ - graph::{ - algo::{connected_components, is_cyclic_directed}, - direction::Direction, - NodeIndex, - }, - visit::{EdgeRef, IntoNodeReferences, NodeRef}, - }, - scheduler::SchedulerType, - task::DagInfo, - time_interval::interval, - Attribute, MultipleReceiver, MultipleSender, VectorToPublishers, VectorToSubscribers, + self, graph::{ + NodeIndex, algo::{connected_components, is_cyclic_directed}, direction::Direction + }, visit::{EdgeRef, IntoNodeReferences, NodeRef} + }, + scheduler::SchedulerType, + task::{ + DagInfo, perf::{NodeRecord, get_period_count, get_pub_count, get_sink_count, get_sub_count, increment_period_count, increment_pub_count, increment_sink_count, increment_sub_count, node_finish, node_start, publish_timestamp_at, subscribe_timestamp_at, update_fin_recv_outer_timestamp_at, update_pre_send_outer_timestamp_at}, + }, + time_interval::interval }; use alloc::{ borrow::Cow, @@ -76,6 +75,7 @@ use alloc::{ }; use awkernel_lib::sync::mutex::{MCSNode, Mutex}; use core::{future::Future, pin::Pin, time::Duration}; +use core::sync::atomic::Ordering; #[cfg(feature = "perf")] use performance::ResponseInfo; @@ -111,6 +111,73 @@ impl_tuple_size!(); impl_tuple_size!(T1); impl_tuple_size!(T1, T2); impl_tuple_size!(T1, T2, T3); +impl_tuple_size!(T1, T2, T3, T4); +impl_tuple_size!(T1, T2, T3, T4, T5); +impl_tuple_size!(T1, T2, T3, T4, T5, T6); +impl_tuple_size!(T1, T2, T3, T4, T5, T6, T7); +impl_tuple_size!(T1, T2, T3, T4, T5, T6, T7, T8); + +// Trait to extract the period (u32) carried in the last element of +// subscriber tuples. Each subscriber tuple element is expected to be +// a `(value, u32)` pair; implementations below return the u32 from +// the last tuple element. The trait is public so `get_period` bounds +// in other functions can reference it. +pub trait GetPeriod { + fn get_period(&self) -> u32; +} + +impl GetPeriod for ((V, u32),) { + fn get_period(&self) -> u32 { + self.0 .1 + } +} + +impl GetPeriod for ((V1, u32), (V2, u32)) { + fn get_period(&self) -> u32 { + self.1 .1 + } +} + +impl GetPeriod for ((V1, u32), (V2, u32), (V3, u32)) { + fn get_period(&self) -> u32 { + self.2 .1 + } +} + +impl GetPeriod for ((V1, u32), (V2, u32), (V3, u32), (V4, u32)) { + fn get_period(&self) -> u32 { + self.3 .1 + } +} + +impl GetPeriod for ((V1, u32), (V2, u32), (V3, u32), (V4, u32), (V5, u32)) { + fn get_period(&self) -> u32 { + self.4 .1 + } +} + +impl GetPeriod for ((V1, u32), (V2, u32), (V3, u32), (V4, u32), (V5, u32), (V6, u32)) { + fn get_period(&self) -> u32 { + self.5 .1 + } +} + +impl GetPeriod for ((V1, u32), (V2, u32), (V3, u32), (V4, u32), (V5, u32), (V6, u32), (V7, u32)) { + fn get_period(&self) -> u32 { + self.6 .1 + } +} + +impl GetPeriod for ((V1, u32), (V2, u32), (V3, u32), (V4, u32), (V5, u32), (V6, u32), (V7, u32), (V8, u32)) { + fn get_period(&self) -> u32 { + self.7 .1 + } +} + +/// Convenience helper to extract period from a subscriber tuple by reference. +pub fn get_period(args: &T) -> u32 { + args.get_period() +} #[derive(Clone)] pub enum DagError { @@ -298,8 +365,8 @@ impl Dag { Ret: VectorToPublishers, Ret::Publishers: Send, Args::Subscribers: Send, - ::Item: TupleSize, - ::Item: TupleSize, + ::Item: TupleSize + GetPeriod + Send, + ::Item: TupleSize + Send, { let node_idx = self.add_node_with_topic_edges(&subscribe_topic_names, &publish_topic_names); self.check_subscribe_mismatch::(&subscribe_topic_names, node_idx); @@ -391,8 +458,8 @@ impl Dag { ) where F: Fn(::Item) + Send + 'static, Args: VectorToSubscribers, - Args::Subscribers: Send, - ::Item: TupleSize, + Args::Subscribers: Send, + ::Item: TupleSize + GetPeriod + Send, { let node_idx = self.add_node_with_topic_edges(&subscribe_topic_names, &Vec::new()); self.set_relative_deadline(node_idx, relative_deadline); @@ -612,6 +679,51 @@ pub async fn finish_create_dags(dags: &[Arc]) -> Result<(), Vec> } } +pub fn reset_all_dags() { + { + let mut dags_node = MCSNode::new(); + let mut dags = DAGS.lock(&mut dags_node); + dags.id_to_dag.clear(); + dags.candidate_id = 1; + } + + { + let mut pending_node = MCSNode::new(); + let mut pending_tasks = PENDING_TASKS.lock(&mut pending_node); + pending_tasks.clear(); + } + + { + let mut source_pending_node = MCSNode::new(); + let mut source_pending_tasks = SOURCE_PENDING_TASKS.lock(&mut source_pending_node); + source_pending_tasks.clear(); + } + + { + let mut node = MCSNode::new(); + let mut mismatch_subscribe = MISMATCH_SUBSCRIBE_NODES.lock(&mut node); + mismatch_subscribe.clear(); + } + + { + let mut node = MCSNode::new(); + let mut mismatch_publish = MISMATCH_PUBLISH_NODES.lock(&mut node); + mismatch_publish.clear(); + } + + { + let mut node = MCSNode::new(); + let mut duplicate_subscribe = DUPLICATE_SUBSCRIBE_NODES.lock(&mut node); + duplicate_subscribe.clear(); + } + + { + let mut node = MCSNode::new(); + let mut duplicate_publish = DUPLICATE_PUBLISH_NODES.lock(&mut node); + duplicate_publish.clear(); + } +} + fn remove_dag(id: u32) { let mut dags_node = MCSNode::new(); let mut dags = DAGS.lock(&mut dags_node); @@ -915,6 +1027,8 @@ where Ret: VectorToPublishers, Ret::Publishers: Send, Args::Subscribers: Send, + ::Item: TupleSize + GetPeriod + Send, + ::Item: TupleSize + Send, { let future = async move { let publishers = ::create_publishers( @@ -928,8 +1042,33 @@ where loop { let args: <::Subscribers as MultipleReceiver>::Item = subscribers.recv_all().await; + // [end] pubsub communication latency + let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + let index_subscribe = get_period(&args).clone() as usize; + let count_st = get_period(&args); + subscribe_timestamp_at(count_st as usize, end, 1, dag_info.node_id.clone()); + + // period count from message to TaskInfo + let cpu_id = awkernel_lib::cpu::cpu_id(); + if let Some(task_id) = crate::task::get_current_task(cpu_id) { + crate::task::set_task_period(task_id, Some(count_st)); + } + // let noderecord = NodeRecord { + // period_count: count_st, + // dag_info: DagInfo { dag_id: dag_info.dag_id.clone(), node_id: dag_info.node_id.clone() }, + // }; + // node_period_count(noderecord.clone()); + // let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + // node_start(noderecord.clone(), start); let results = f(args); - publishers.send_all(results).await; + + // node_finish(noderecord.clone(), end); + // let index_publish = get_period(&args) as usize; + + // [start] pubsub communication latency + let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + publish_timestamp_at(count_st as usize, end,1, dag_info.node_id.clone()); + publishers.send_all_with_meta(results, 1, count_st as usize, dag_info.node_id).await; } }; @@ -966,13 +1105,42 @@ where Attribute::default(), ); - let mut interval = interval(period); + let mut interval = interval(period, dag_info.dag_id.clone() as u32); // Consume the first tick here to start the loop's main body without an initial delay. interval.tick().await; loop { + let index = get_period_count(dag_info.dag_id.clone() as usize) as usize; + let cpu_id = awkernel_lib::cpu::cpu_id(); + if let Some(task_id) = crate::task::get_current_task(cpu_id) { + crate::task::set_task_period(task_id, Some(index as u32)); + } + // [node] per node + // let noderecord = NodeRecord { + // period_count: index as u32, + // dag_info: DagInfo { dag_id: dag_info.dag_id.clone(), node_id: dag_info.node_id.clone() }, + // }; + // node_period_count(noderecord.clone()); + // let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + // node_start(noderecord.clone(), start); + if index != 0 { + let release_time = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + update_pre_send_outer_timestamp_at(index, release_time, dag_info.dag_id.clone()); + } let results = f(); - publishers.send_all(results).await; + // let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + // node_finish(noderecord.clone(), end); + + // let index_publish = get_pub_count(0) as usize; + + // [start] pubsub communication latency + let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + publish_timestamp_at(index, end, 0, dag_info.node_id); + publishers.send_all_with_meta(results, 0, index, dag_info.node_id).await; + + + increment_period_count(dag_info.dag_id.clone() as usize); + increment_pub_count(0); #[cfg(feature = "perf")] periodic_measure(); @@ -1000,6 +1168,7 @@ where F: Fn(::Item) + Send + 'static, Args: VectorToSubscribers, Args::Subscribers: Send, + ::Item: TupleSize + GetPeriod + Send, { let future = async move { let subscribers: ::Subscribers = @@ -1007,9 +1176,41 @@ where loop { let args: ::Item = subscribers.recv_all().await; + // [end] pubsub communication latency + let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + let index_subscribe = get_period(&args) as usize; + let count_st = get_period(&args); + subscribe_timestamp_at(count_st as usize, end, 2, dag_info.node_id.clone()); + increment_pub_count(1); + increment_sub_count(1); + increment_sub_count(2); + + // period count from message to TaskInfo + let cpu_id = awkernel_lib::cpu::cpu_id(); + if let Some(task_id) = crate::task::get_current_task(cpu_id) { + crate::task::set_task_period(task_id, Some(count_st)); + } + + // [node] per node + // let noderecord = NodeRecord { + // period_count: count_st, + // dag_info: DagInfo { dag_id: dag_info.dag_id.clone(), node_id: dag_info.node_id.clone() }, + // }; + // node_period_count(noderecord.clone()); + // let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + // node_start(noderecord.clone(), start); f(args); + // let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + // node_finish(noderecord.clone(), end); + let timenow = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + let counter = get_sink_count(dag_info.dag_id.clone() as usize) as usize; + if count_st != 0 { + // update_fin_recv_outer_timestamp_at(counter, timenow, dag_info.dag_id.clone()); + update_fin_recv_outer_timestamp_at(count_st as usize, timenow, dag_info.dag_id); + } + increment_sink_count(dag_info.dag_id.clone() as usize); } }; crate::task::spawn_with_dag_info(reactor_name, future, sched_type, dag_info) -} +} \ No newline at end of file diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index c216bae0b..807c44d14 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -52,6 +52,10 @@ use core::{ use futures::Future; use pin_project::pin_project; +use crate::task; +use crate::task::{DagInfo}; +use crate::task::perf::{PUB_COUNT,get_pub_count, publish_timestamp_at}; + /// Data and timestamp. #[derive(Clone)] pub struct Data { @@ -381,9 +385,22 @@ impl Publisher where T: Clone + Sync + Send, { + /// Send with metadata forwarded from `send_all_with_meta`. + pub async fn send_with_meta(&self, data: T, pub_id: u32, index: usize, node_id: u32) { + // record publish timestamp at send start + // let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + // publish_timestamp_at(index, start, pub_id, node_id); + + let sender = Sender::new(self, data); + sender.await; + + r#yield().await; + } + pub async fn send(&self, data: T) { let sender = Sender::new(self, data); sender.await; + r#yield().await; } } @@ -761,7 +778,18 @@ pub trait MultipleReceiver { pub trait MultipleSender { type Item; - fn send_all(&self, item: Self::Item) -> Pin + Send + '_>>; + fn send_all(&self, item: Self::Item) -> Pin + Send + '_>> { + // default to pub_id = 1 (intermediate), index = 0, node_id = 0 + self.send_all_with_meta(item, 1, 0, 0) + } + + fn send_all_with_meta( + &self, + item: Self::Item, + pub_id: u32, + index: usize, + node_id: u32, + ) -> Pin + Send + '_>>; } pub trait VectorToPublishers { type Publishers: MultipleSender; @@ -825,6 +853,11 @@ impl_tuple_to_pub_sub!(); impl_tuple_to_pub_sub!(A); impl_tuple_to_pub_sub!(A, B); impl_tuple_to_pub_sub!(A, B, C); +impl_tuple_to_pub_sub!(T0, T1, T2, T3); +impl_tuple_to_pub_sub!(T0, T1, T2, T3, T4); +impl_tuple_to_pub_sub!(T0, T1, T2, T3, T4, T5); +impl_tuple_to_pub_sub!(T0, T1, T2, T3, T4, T5, T6); +impl_tuple_to_pub_sub!(T0, T1, T2, T3, T4, T5, T6, T7); macro_rules! impl_async_receiver_for_tuple { () => { @@ -838,8 +871,7 @@ macro_rules! impl_async_receiver_for_tuple { impl MultipleSender for () { type Item = (); - - fn send_all(&self, _item: Self::Item) -> Pin + Send + '_>> { + fn send_all_with_meta(&self, _item: Self::Item, _pub_id: u32, _index: usize, _node_id: u32) -> Pin + Send + '_>> { Box::pin(async move{}) } } @@ -859,12 +891,15 @@ macro_rules! impl_async_receiver_for_tuple { impl<$($T: Clone + Sync + Send + 'static),+> MultipleSender for ($(Publisher<$T>,)+) { type Item = ($($T,)+); - fn send_all(&self, item: Self::Item) -> Pin + Send + '_>> { + fn send_all_with_meta(&self, item: Self::Item, pub_id: u32, index: usize, node_id: u32) -> Pin + Send + '_>> { let ($($idx,)+) = self; let ($($idx2,)+) = item; Box::pin(async move { $( - $idx.send($idx2).await; + // let now = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + // publish_timestamp_at(index, now, pub_id, node_id); + // $idx.send($idx2).await; + $idx.send_with_meta($idx2, pub_id, index, node_id).await; )+ }) } @@ -876,6 +911,41 @@ impl_async_receiver_for_tuple!(); impl_async_receiver_for_tuple!((A, a, p)); impl_async_receiver_for_tuple!((A, a, p), (B, b, q)); impl_async_receiver_for_tuple!((A, a, p), (B, b, q), (C, c, r)); +impl_async_receiver_for_tuple!((T0, v0, p0), (T1, v1, p1), (T2, v2, p2), (T3, v3, p3)); +impl_async_receiver_for_tuple!( + (T0, v0, p0), + (T1, v1, p1), + (T2, v2, p2), + (T3, v3, p3), + (T4, v4, p4) +); +impl_async_receiver_for_tuple!( + (T0, v0, p0), + (T1, v1, p1), + (T2, v2, p2), + (T3, v3, p3), + (T4, v4, p4), + (T5, v5, p5) +); +impl_async_receiver_for_tuple!( + (T0, v0, p0), + (T1, v1, p1), + (T2, v2, p2), + (T3, v3, p3), + (T4, v4, p4), + (T5, v5, p5), + (T6, v6, p6) +); +impl_async_receiver_for_tuple!( + (T0, v0, p0), + (T1, v1, p1), + (T2, v2, p2), + (T3, v3, p3), + (T4, v4, p4), + (T5, v5, p5), + (T6, v6, p6), + (T7, v7, p7) +); #[cfg(test)] mod tests { diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index bdb73c447..59393ea01 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -158,6 +158,7 @@ pub struct TaskInfo { pub(crate) need_preemption: bool, panicked: bool, pub(crate) dag_info: Option, + pub(crate) current_period: Option, #[cfg(not(feature = "no_preempt"))] thread: Option, @@ -225,6 +226,16 @@ impl TaskInfo { pub fn get_dag_info(&self) -> Option { self.dag_info.clone() } + + #[inline(always)] + pub fn set_current_period(&mut self, p: Option) { + self.current_period = p; + } + + #[inline(always)] + pub fn get_current_period(&self) -> Option { + self.current_period + } } /// State of task. @@ -246,7 +257,7 @@ struct Tasks { id_to_task: BTreeMap>, } -#[derive(Clone)] +#[derive(Debug, Clone)] pub struct DagInfo { pub dag_id: u32, pub node_id: u32, @@ -286,6 +297,7 @@ impl Tasks { need_preemption: false, panicked: false, dag_info, + current_period: None, #[cfg(not(feature = "no_preempt"))] thread: None, @@ -454,8 +466,13 @@ fn get_next_task(execution_ensured: bool) -> Option> { #[cfg(feature = "perf")] pub mod perf { - use awkernel_lib::cpu::NUM_MAX_CPU; - use core::ptr::{read_volatile, write_volatile}; + use alloc::string::{String, ToString}; + use awkernel_lib::{cpu::NUM_MAX_CPU, device_tree::node}; + use core::{ptr::{read_volatile, write_volatile}}; + use crate::task::{self}; + use core::sync::atomic::{AtomicU32, Ordering}; + use array_macro::array; + #[derive(Debug, Clone, PartialEq, Eq)] #[repr(u8)] @@ -464,6 +481,7 @@ pub mod perf { Kernel, Task, ContextSwitch, + ContextSwitchMain, Interrupt, Idle, } @@ -475,12 +493,18 @@ pub mod perf { 1 => Self::Kernel, 2 => Self::Task, 3 => Self::ContextSwitch, - 4 => Self::Interrupt, - 5 => Self::Idle, + 4 => Self::ContextSwitchMain, + 5 => Self::Interrupt, + 6 => Self::Idle, _ => panic!("From for PerfState::from: invalid value"), } } } + #[derive(Debug, Clone)] + pub struct NodeRecord{ + pub period_count: u32, + pub dag_info: task::DagInfo, + } static mut PERF_STATES: [u8; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; @@ -490,6 +514,7 @@ pub mod perf { static mut TASK_TIME: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; static mut INTERRUPT_TIME: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; static mut CONTEXT_SWITCH_TIME: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; + static mut CONTEXT_SWITCH_MAIN_TIME: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; static mut IDLE_TIME: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; static mut PERF_TIME: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; @@ -497,6 +522,7 @@ pub mod perf { static mut TASK_WCET: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; static mut INTERRUPT_WCET: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; static mut CONTEXT_SWITCH_WCET: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; + static mut CONTEXT_SWITCH_MAIN_WCET: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; static mut IDLE_WCET: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; static mut PERF_WCET: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; @@ -504,9 +530,409 @@ pub mod perf { static mut TASK_COUNT: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; static mut INTERRUPT_COUNT: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; static mut CONTEXT_SWITCH_COUNT: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; + static mut CONTEXT_SWITCH_MAIN_COUNT: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; static mut IDLE_COUNT: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; static mut PERF_COUNT: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; + use awkernel_lib::sync::{mcs::MCSNode, mutex::Mutex}; + const MAX_LOGS: usize = 8192; + + static SEND_OUTER_TIMESTAMP: Mutex> = Mutex::new(None); + static RECV_OUTER_TIMESTAMP: Mutex> = Mutex::new(None); + static ABSOLUTE_DEADLINE: Mutex> = Mutex::new(None); + static RELATIVE_DEADLINE: Mutex> = Mutex::new(None); + static DAG_PREEMPT_COUNT: Mutex> = Mutex::new(None); + + //DAG+1 + const MAX_DAGS: usize = 4; + pub static PERIOD_COUNT: [AtomicU32; MAX_DAGS] = array![_ => AtomicU32::new(0); MAX_DAGS]; + pub static SINK_COUNT: [AtomicU32; MAX_DAGS] = array![_ => AtomicU32::new(0); MAX_DAGS]; + + const MAX_NODES: usize = 20; + static NODE_START: Mutex> = Mutex::new(None); + static NODE_FINISH: Mutex> = Mutex::new(None); + static NODE_PREEMPT_COUNT: Mutex> = Mutex::new(None); + static NODE_CORE: Mutex> = Mutex::new(None); + + //pubsub + const MAX_PUBSUB: usize = 3; + static PUBLISH: Mutex> = Mutex::new(None); + static SUBSCRIBE: Mutex> = Mutex::new(None); + pub static PUB_COUNT: [AtomicU32; MAX_PUBSUB] = array![_ => AtomicU32::new(0); MAX_PUBSUB]; + pub static SUB_COUNT: [AtomicU32; MAX_PUBSUB] = array![_ => AtomicU32::new(0); MAX_PUBSUB]; + + pub fn reset_perf_logs() { + for i in 0..MAX_PUBSUB { + PUB_COUNT[i].store(0, Ordering::Relaxed); + SUB_COUNT[i].store(0, Ordering::Relaxed); + } + for i in 0..MAX_DAGS { + PERIOD_COUNT[i].store(0, Ordering::Relaxed); + SINK_COUNT[i].store(0, Ordering::Relaxed); + } + *SEND_OUTER_TIMESTAMP.lock(&mut MCSNode::new()) = None; + *RECV_OUTER_TIMESTAMP.lock(&mut MCSNode::new()) = None; + *ABSOLUTE_DEADLINE.lock(&mut MCSNode::new()) = None; + *RELATIVE_DEADLINE.lock(&mut MCSNode::new()) = None; + *NODE_START.lock(&mut MCSNode::new()) = None; + *NODE_FINISH.lock(&mut MCSNode::new()) = None; + } + + pub fn increment_pub_count(pub_id: usize) { + assert!(pub_id < MAX_PUBSUB, "Pub ID out of bounds"); + PUB_COUNT[pub_id].fetch_add(1, Ordering::Relaxed); + } + + pub fn increment_sub_count(sub_id: usize) { + assert!(sub_id < MAX_PUBSUB, "Sub ID out of bounds"); + SUB_COUNT[sub_id].fetch_add(1, Ordering::Relaxed); + } + + pub fn get_pub_count(pub_id: usize) -> u32 { + assert!(pub_id < MAX_PUBSUB, "Pub ID out of bounds"); + PUB_COUNT[pub_id].load(Ordering::Relaxed) + } + + pub fn get_sub_count(sub_id: usize) -> u32 { + assert!(sub_id < MAX_PUBSUB, "Sub ID out of bounds"); + SUB_COUNT[sub_id].load(Ordering::Relaxed) + } + + pub fn increment_period_count(dag_id: usize) { + assert!(dag_id < MAX_DAGS, "DAG ID out of bounds"); + PERIOD_COUNT[dag_id].fetch_add(1, Ordering::Relaxed); + } + + pub fn get_period_count(dag_id: usize) -> u32 { + assert!(dag_id < MAX_DAGS, "DAG ID out of bounds"); + PERIOD_COUNT[dag_id].load(Ordering::Relaxed) + } + + pub fn increment_sink_count(dag_id: usize) { + assert!(dag_id < MAX_DAGS, "DAG ID out of bounds"); + SINK_COUNT[dag_id].fetch_add(1, Ordering::Relaxed); + } + + pub fn get_sink_count(dag_id: usize) -> u32 { + assert!(dag_id < MAX_DAGS, "DAG ID out of bounds"); + SINK_COUNT[dag_id].load(Ordering::Relaxed) + } + + pub fn update_pre_send_outer_timestamp_at(index: usize, new_timestamp: u64, dag_id: u32) { + assert!(index < MAX_LOGS, "Timestamp index out of bounds"); + + let mut node = MCSNode::new(); + let mut recorder_opt = SEND_OUTER_TIMESTAMP.lock(&mut node); + + let recorder = recorder_opt.get_or_insert_with(|| [[0; MAX_DAGS]; MAX_LOGS]); + + if recorder[index][dag_id as usize] == 0 { + recorder[index][dag_id as usize] = new_timestamp; + } + } + + pub fn update_fin_recv_outer_timestamp_at(index: usize, new_timestamp: u64, dag_id: u32) { + assert!(index < MAX_LOGS, "Timestamp index out of bounds"); + + let mut node = MCSNode::new(); + let mut recorder_opt = RECV_OUTER_TIMESTAMP.lock(&mut node); + + let recorder = recorder_opt.get_or_insert_with(|| [[0; MAX_DAGS]; MAX_LOGS]); + + if (dag_id as usize) < recorder[0].len() { + recorder[index][dag_id as usize] = new_timestamp; + } + } + + pub fn update_absolute_deadline_timestamp_at(index: usize, deadline: u64, dag_id: u32){ + assert!(index < MAX_LOGS, "Timestamp index out of bounds"); + + let mut node = MCSNode::new(); + let mut recorder_opt = ABSOLUTE_DEADLINE.lock(&mut node); + + let recorder = recorder_opt.get_or_insert_with(|| [[0; MAX_DAGS]; MAX_LOGS]); + + if recorder[index][dag_id as usize] == 0 { + recorder[index][dag_id as usize] = deadline; + } + + } + + pub fn update_relative_deadline_timestamp_at(index: usize, deadline: u64, dag_id: u32){ + assert!(index < MAX_LOGS, "Timestamp index out of bounds"); + + let mut node = MCSNode::new(); + let mut recorder_opt = RELATIVE_DEADLINE.lock(&mut node); + + let recorder = recorder_opt.get_or_insert_with(|| [[0; MAX_DAGS]; MAX_LOGS]); + + if recorder[index][dag_id as usize] == 0 { + recorder[index][dag_id as usize] = deadline; + } + + } + + pub fn node_start(node:NodeRecord, start: u64){ + // assert!(index < MAX_LOGS, "Node log index out of bounds"); + assert!((node.dag_info.node_id as usize) < MAX_NODES, "Node ID out of bounds"); + + let mut mcs_node = MCSNode::new(); + let mut recorder_opt = NODE_START.lock(&mut mcs_node); + + let recorder = recorder_opt.get_or_insert_with(|| [[0; MAX_NODES]; MAX_LOGS]); + + if recorder[node.period_count as usize][node.dag_info.node_id as usize] == 0 { + recorder[node.period_count as usize][node.dag_info.node_id as usize] = start; + } + } + + pub fn node_finish(node:NodeRecord, finish: u64){ + // assert!(index < MAX_LOGS, "Node log index out of bounds"); + assert!((node.dag_info.node_id as usize) < MAX_NODES, "Node ID out of bounds"); + + let mut mcs_node = MCSNode::new(); + let mut recorder_opt = NODE_FINISH.lock(&mut mcs_node); + + let recorder = recorder_opt.get_or_insert_with(|| [[0; MAX_NODES]; MAX_LOGS]); + + if recorder[node.period_count as usize][node.dag_info.node_id as usize] == 0 { + recorder[node.period_count as usize][node.dag_info.node_id as usize] = finish; + } + } + + pub fn node_preempt(node:NodeRecord){ + // assert!(index < MAX_LOGS, "Node log index out of bounds"); + assert!((node.dag_info.node_id as usize) < MAX_NODES, "Node ID out of bounds"); + + let mut mcs_node = MCSNode::new(); + let mut recorder_opt = NODE_PREEMPT_COUNT.lock(&mut mcs_node); + + let recorder = recorder_opt.get_or_insert_with(|| [[0; MAX_NODES]; MAX_LOGS]); + + recorder[node.period_count as usize][node.dag_info.node_id as usize] += 1; + } + + pub fn dag_preempt(node:NodeRecord){ + // assert!(index < MAX_LOGS, "Node log index out of bounds"); + assert!((node.dag_info.dag_id as usize) < MAX_DAGS, "DAG ID out of bounds"); + + let mut mcs_node = MCSNode::new(); + let mut recorder_opt = DAG_PREEMPT_COUNT.lock(&mut mcs_node); + + let recorder = recorder_opt.get_or_insert_with(|| [[0; MAX_DAGS]; MAX_LOGS]); + + recorder[node.period_count as usize][node.dag_info.dag_id as usize] += 1; + } + + pub fn publish_timestamp_at(index: usize, new_timestamp: u64, pub_id: u32, node_id: u32) { + assert!(index < MAX_LOGS, "Timestamp index out of bounds"); + assert!((pub_id as usize) < MAX_PUBSUB, "Publish ID out of bounds"); + + let mut node = MCSNode::new(); + let mut recorder_opt = PUBLISH.lock(&mut node); + + let recorder = recorder_opt.get_or_insert_with(|| [[[0; MAX_NODES]; MAX_PUBSUB]; MAX_LOGS]); + + if recorder[index][pub_id as usize][node_id as usize] == 0 { + recorder[index][pub_id as usize][node_id as usize] = new_timestamp; + } + } + + pub fn subscribe_timestamp_at(index: usize, new_timestamp: u64, sub_id: u32, node_id: u32) { + assert!(index < MAX_LOGS, "Timestamp index out of bounds"); + assert!((sub_id as usize) < MAX_PUBSUB, "Subscribe ID out of bounds"); + + let mut node = MCSNode::new(); + let mut recorder_opt = SUBSCRIBE.lock(&mut node); + + let recorder = recorder_opt.get_or_insert_with(|| [[[0; MAX_NODES]; MAX_PUBSUB]; MAX_LOGS]); + + if recorder[index][sub_id as usize][node_id as usize] == 0 { + recorder[index][sub_id as usize][node_id as usize] = new_timestamp; + } + } + + // For precision of the cycle + pub fn print_timestamp_table() { + let mut node1 = MCSNode::new(); + let mut node2 = MCSNode::new(); + let mut node3 = MCSNode::new(); + let mut node4 = MCSNode::new(); + let mut node5 = MCSNode::new(); + + let send_outer_opt = SEND_OUTER_TIMESTAMP.lock(&mut node1); + let recv_outer_opt = RECV_OUTER_TIMESTAMP.lock(&mut node2); + let absolute_deadline_opt = ABSOLUTE_DEADLINE.lock(&mut node3); + let relative_deadline_opt = RELATIVE_DEADLINE.lock(&mut node4); + let dag_preempt_opt = DAG_PREEMPT_COUNT.lock(&mut node5); + + log::info!("--- Timestamp Summary (in nanoseconds) ---"); + log::info!( + "{: ^5} | {: ^5} | {: ^14} | {: ^14} | {: ^14} | {: ^14} | {: ^14} | {: ^14}", + "Index", + "DAG-ID", + "Send-Outer", + "Recv-Outer", + "Latency", + "Absolute Deadline", + "Relative Deadline", + "DAG Preemptions" + ); + + log::info!("-----|--------|----------------|----------------|----------------|--------------------|--------------------|--------------------|--------------------"); + + for i in 0..MAX_LOGS { + for j in 1..MAX_DAGS { + let pre_send_outer = send_outer_opt.as_ref().map_or(0, |arr| arr[i][j]); + let fin_recv_outer = recv_outer_opt.as_ref().map_or(0, |arr| arr[i][j]); + let absolute_deadline = absolute_deadline_opt.as_ref().map_or(0, |arr| arr[i][j]); + let relative_deadline = relative_deadline_opt.as_ref().map_or(0, |arr| arr[i][j]); + let dag_preempt = dag_preempt_opt.as_ref().map_or(0, |arr| arr[i][j]); + + if pre_send_outer != 0 || fin_recv_outer != 0 || absolute_deadline != 0 || relative_deadline != 0 || dag_preempt != 0 { + let format_ts = |ts: u64| -> String { + if ts == 0 { + "-".to_string() + } else { + ts.to_string() + } + }; + + let latency_str = if pre_send_outer != 0 && fin_recv_outer != 0 { + fin_recv_outer.saturating_sub(pre_send_outer).to_string() + } else { + "-".to_string() + }; + + log::info!( + "{: >5} | {: >5} | {: >14} | {: >14} | {: >14} | {: >20} | {: >20} | {: >20}", + i, + format_ts(j as u64), + format_ts(pre_send_outer), + format_ts(fin_recv_outer), + latency_str, + format_ts(absolute_deadline), + format_ts(relative_deadline), + format_ts(dag_preempt as u64), + ); + } + } + } + log::info!("----------------------------------------------------------"); + } + + /// Print per-node timing table. + /// Columns: DAG ID | node id | period | start(ns) | end(ns) | duration(ns) | preemptions | core + /// not used now + pub fn print_node_table() { + let mut node1 = MCSNode::new(); + let mut node2 = MCSNode::new(); + let mut node3 = MCSNode::new(); + let mut node4 = MCSNode::new(); + + let node_start_opt = NODE_START.lock(&mut node1); + let node_finish_opt = NODE_FINISH.lock(&mut node2); + let node_preempt_opt = NODE_PREEMPT_COUNT.lock(&mut node3); + let node_core_opt = NODE_CORE.lock(&mut node4); + + log::info!("--- Per-node Timing Summary (in nanoseconds) ---"); + log::info!( + "{:<5} | {:<6} | {:<7} | {:<20} | {:<20} | {:<20} | {:<12} | {:<4}", + "Index", + "DAG-ID", + "NODE-ID", + "start(ns)", + "end(ns)", + "duration(ns)", + "preemptions", + "core" + ); + log::info!("------|--------|---------|----------------------|----------------------|----------------------|-----"); + + for i in 0..MAX_LOGS { + for j in 0..MAX_NODES { + let start = node_start_opt.as_ref().map_or(0, |arr| arr[i][j]); + let finish = node_finish_opt.as_ref().map_or(0, |arr| arr[i][j]); + let preempt_count = node_preempt_opt.as_ref().map_or(0, |arr| arr[i][j]); + let core_id = node_core_opt.as_ref().map_or(0, |arr| arr[i][j]); + + if start != 0 || finish != 0 || preempt_count != 0 { + + let format_ts = |ts: u64| -> String { + ts.to_string() + }; + + let duration = if start != 0 && finish != 0 { + finish.saturating_sub(start).to_string() + } else { + "-".to_string() + }; + + log::info!( + "{:<5} | {:<6} | {:<7} | {:<20} | {:<20} | {:<20} | {:<12} | {:<4}", + i, + 1, // DAG ID (assumed 1 for simplicity) + format_ts(j as u64), + format_ts(start), + format_ts(finish), + duration, + format_ts(preempt_count as u64), + format_ts(core_id as u64), + ); + } + } + } + log::info!("--------------------------------------------------------------"); + } + + // For pubsub communication latency + pub fn print_pubsub_table() { + let mut node1 = MCSNode::new(); + let mut node2 = MCSNode::new(); + + let publish_opt = PUBLISH.lock(&mut node1); + let subscribe_opt = SUBSCRIBE.lock(&mut node2); + + log::info!("--- Pub/Sub Timestamp Summary (in nanoseconds) ---"); + log::info!( + "{: ^5} | {: ^10} | {: ^7} | {: ^14} | {: ^14}", + "Index", + "Pub/Sub ID", + "Node ID", + "Publish Time", + "Subscribe Time" + ); + log::info!("-----|------------|---------|----------------|----------------"); + for i in 0..MAX_LOGS { + for j in 0..MAX_PUBSUB { + for k in 0..MAX_NODES { + let publish_time = publish_opt.as_ref().map_or(0, |arr| arr[i][j][k]); + let subscribe_time = subscribe_opt.as_ref().map_or(0, |arr| arr[i][j][k]); + + if publish_time != 0 || subscribe_time != 0 { + let format_ts = |ts: u64| -> String { + if ts == 0 { + "-".to_string() + } else { + ts.to_string() + } + }; + + log::info!( + "{: >5} | {: >10} | {: >7} | {: >14} | {: >14}", + i, + j, + k, + format_ts(publish_time), + format_ts(subscribe_time), + ); + } + } + } + } + log::info!("--------------------------------------------------------------"); + } + fn update_time_and_state(next_state: PerfState) { let end = awkernel_lib::delay::cpu_counter(); let cpu_id = awkernel_lib::cpu::cpu_id(); @@ -554,6 +980,101 @@ pub mod perf { let wcet = read_volatile(&CONTEXT_SWITCH_WCET[cpu_id]); write_volatile(&mut CONTEXT_SWITCH_WCET[cpu_id], wcet.max(diff)); }, + PerfState::ContextSwitchMain => unsafe { + let t = read_volatile(&CONTEXT_SWITCH_MAIN_TIME[cpu_id]); + write_volatile(&mut CONTEXT_SWITCH_MAIN_TIME[cpu_id], t + diff); + let c = read_volatile(&CONTEXT_SWITCH_MAIN_COUNT[cpu_id]); + write_volatile(&mut CONTEXT_SWITCH_MAIN_COUNT[cpu_id], c + 1); + let wcet = read_volatile(&CONTEXT_SWITCH_MAIN_WCET[cpu_id]); + write_volatile(&mut CONTEXT_SWITCH_MAIN_WCET[cpu_id], wcet.max(diff)); + }, + PerfState::Idle => unsafe { + let t = read_volatile(&IDLE_TIME[cpu_id]); + write_volatile(&mut IDLE_TIME[cpu_id], t + diff); + let c = read_volatile(&IDLE_COUNT[cpu_id]); + write_volatile(&mut IDLE_COUNT[cpu_id], c + 1); + let wcet = read_volatile(&IDLE_WCET[cpu_id]); + write_volatile(&mut IDLE_WCET[cpu_id], wcet.max(diff)); + }, + PerfState::Boot => (), + } + } + + let cnt = awkernel_lib::delay::cpu_counter(); + + unsafe { + // Overhead of this. + let t = read_volatile(&PERF_TIME[cpu_id]); + write_volatile(&mut PERF_TIME[cpu_id], t + (cnt - end)); + let c = read_volatile(&PERF_COUNT[cpu_id]); + write_volatile(&mut PERF_COUNT[cpu_id], c + 1); + let wcet = read_volatile(&PERF_WCET[cpu_id]); + write_volatile(&mut PERF_WCET[cpu_id], wcet.max(cnt - end)); + + // State transition. + write_volatile(&mut START_TIME[cpu_id], cnt); + write_volatile(&mut PERF_STATES[cpu_id], next_state as u8); + } + } + + fn update_time_and_state_for_dag(next_state: PerfState) { + let end = awkernel_lib::delay::cpu_counter(); + let cpu_id = awkernel_lib::cpu::cpu_id(); + + let state: PerfState = unsafe { read_volatile(&PERF_STATES[cpu_id]) }.into(); + if state == next_state { + return; + } + + let start = unsafe { read_volatile(&START_TIME[cpu_id]) }; + + if start > 0 && start <= end { + let diff = end - start; + + match state { + PerfState::Kernel => unsafe { + let t = read_volatile(&KERNEL_TIME[cpu_id]); + write_volatile(&mut KERNEL_TIME[cpu_id], t + diff); + let c = read_volatile(&KERNEL_COUNT[cpu_id]); + write_volatile(&mut KERNEL_COUNT[cpu_id], c + 1); + let wcet = read_volatile(&KERNEL_WCET[cpu_id]); + write_volatile(&mut KERNEL_WCET[cpu_id], wcet.max(diff)); + }, + PerfState::Task => unsafe { + let t = read_volatile(&TASK_TIME[cpu_id]); + write_volatile(&mut TASK_TIME[cpu_id], t + diff); + let c = read_volatile(&TASK_COUNT[cpu_id]); + write_volatile(&mut TASK_COUNT[cpu_id], c + 1); + let wcet = read_volatile(&TASK_WCET[cpu_id]); + write_volatile(&mut TASK_WCET[cpu_id], wcet.max(diff)); + }, + PerfState::Interrupt => unsafe { + // log::info!("PreemptionTime CPU:{} Diff:{}", cpu_id, diff); + let t = read_volatile(&INTERRUPT_TIME[cpu_id]); + write_volatile(&mut INTERRUPT_TIME[cpu_id], t + diff); + let c = read_volatile(&INTERRUPT_COUNT[cpu_id]); + write_volatile(&mut INTERRUPT_COUNT[cpu_id], c + 1); + let wcet = read_volatile(&INTERRUPT_WCET[cpu_id]); + write_volatile(&mut INTERRUPT_WCET[cpu_id], wcet.max(diff)); + }, + PerfState::ContextSwitch => unsafe { + // log::info!("ContextSwitchTime CPU:{} Diff:{}", cpu_id, diff); + let t = read_volatile(&CONTEXT_SWITCH_TIME[cpu_id]); + write_volatile(&mut CONTEXT_SWITCH_TIME[cpu_id], t + diff); + let c = read_volatile(&CONTEXT_SWITCH_COUNT[cpu_id]); + write_volatile(&mut CONTEXT_SWITCH_COUNT[cpu_id], c + 1); + let wcet = read_volatile(&CONTEXT_SWITCH_WCET[cpu_id]); + write_volatile(&mut CONTEXT_SWITCH_WCET[cpu_id], wcet.max(diff)); + }, + PerfState::ContextSwitchMain => unsafe { + // log::info!("ContextSwitchMainTime CPU:{} Diff:{}", cpu_id, diff); + let t = read_volatile(&CONTEXT_SWITCH_MAIN_TIME[cpu_id]); + write_volatile(&mut CONTEXT_SWITCH_MAIN_TIME[cpu_id], t + diff); + let c = read_volatile(&CONTEXT_SWITCH_MAIN_COUNT[cpu_id]); + write_volatile(&mut CONTEXT_SWITCH_MAIN_COUNT[cpu_id], c + 1); + let wcet = read_volatile(&CONTEXT_SWITCH_MAIN_WCET[cpu_id]); + write_volatile(&mut CONTEXT_SWITCH_MAIN_WCET[cpu_id], wcet.max(diff)); + }, PerfState::Idle => unsafe { let t = read_volatile(&IDLE_TIME[cpu_id]); write_volatile(&mut IDLE_TIME[cpu_id], t + diff); @@ -598,7 +1119,24 @@ pub mod perf { pub fn start_interrupt() -> PerfState { let cpu_id = awkernel_lib::cpu::cpu_id(); let previous: PerfState = unsafe { read_volatile(&PERF_STATES[cpu_id]) }.into(); - update_time_and_state(PerfState::Interrupt); + + // Check the current task + if let Some(task_id) = task::get_current_task(cpu_id) { + if let Some(task) = task::get_task(task_id) { + let dag_info = task.info.lock(&mut task::MCSNode::new()).get_dag_info(); + if dag_info.is_some() { + // DAG task-specific handling + update_time_and_state_for_dag(PerfState::Interrupt); + } else { + // Normal task-specific handling + update_time_and_state(PerfState::Interrupt); + } + } + } else { + // Default handling if no task is running + update_time_and_state(PerfState::Interrupt); + } + previous } @@ -609,6 +1147,7 @@ pub mod perf { PerfState::Kernel => start_kernel(), PerfState::Task => start_task(), PerfState::ContextSwitch => start_context_switch(), + PerfState::ContextSwitchMain => start_context_switch_main(), PerfState::Interrupt => { start_interrupt(); } @@ -618,7 +1157,44 @@ pub mod perf { #[inline(always)] pub(crate) fn start_context_switch() { - update_time_and_state(PerfState::ContextSwitch); + let cpu_id = awkernel_lib::cpu::cpu_id(); + + if let Some(task_id) = task::get_current_task(cpu_id) { + if let Some(task) = task::get_task(task_id) { + let dag_info = task.info.lock(&mut task::MCSNode::new()).get_dag_info(); + if dag_info.is_some() { + // DAG task-specific handling + update_time_and_state_for_dag(PerfState::ContextSwitch); + } else { + // Normal task-specific handling + update_time_and_state(PerfState::ContextSwitch); + } + } + } else { + // Default handling if no task is running + update_time_and_state(PerfState::ContextSwitch); + } + } + + #[inline(always)] + pub(crate) fn start_context_switch_main() { + let cpu_id = awkernel_lib::cpu::cpu_id(); + + if let Some(task_id) = task::get_current_task(cpu_id) { + if let Some(task) = task::get_task(task_id) { + let dag_info = task.info.lock(&mut task::MCSNode::new()).get_dag_info(); + if dag_info.is_some() { + // DAG task-specific handling + update_time_and_state_for_dag(PerfState::ContextSwitchMain); + } else { + // Normal task-specific handling + update_time_and_state(PerfState::ContextSwitchMain); + } + } + } else { + // Default handling if no task is running + update_time_and_state(PerfState::ContextSwitchMain); + } } #[inline(always)] @@ -996,6 +1572,24 @@ pub fn get_scheduler_type_by_task_id(task_id: u32) -> Option { }) } +pub fn set_task_period(task_id: u32, period: Option) { + if let Some(task) = get_task(task_id) { + let mut node = MCSNode::new(); + let mut info = task.info.lock(&mut node); + info.set_current_period(period); + } +} + +pub fn get_task_period(task_id: u32) -> Option { + if let Some(task) = get_task(task_id) { + let mut node = MCSNode::new(); + let info = task.info.lock(&mut node); + info.get_current_period() + } else { + None + } +} + #[inline(always)] pub fn set_need_preemption(task_id: u32, cpu_id: usize) { let mut node = MCSNode::new(); diff --git a/awkernel_async_lib/src/time_interval.rs b/awkernel_async_lib/src/time_interval.rs index 96ce16219..ed188056b 100644 --- a/awkernel_async_lib/src/time_interval.rs +++ b/awkernel_async_lib/src/time_interval.rs @@ -29,6 +29,11 @@ //! SOFTWARE. use crate::sleep_task::Sleep; +use crate::{ + task::{ + perf::{update_pre_send_outer_timestamp_at, get_period_count}, + }, +}; use alloc::boxed::Box; use awkernel_lib::time::Time; use core::{ @@ -95,13 +100,15 @@ pub enum MissedTickBehavior { /// } /// ``` /// -pub fn interval(period: Duration) -> Interval { +pub fn interval(period: Duration, dag_id: u32) -> Interval { assert!(!period.is_zero(), "`period` must be non-zero."); - interval_at(Time::now(), period) + interval_at(Time::now(), period, dag_id) } -pub fn interval_at(start: Time, period: Duration) -> Interval { +pub fn interval_at(start: Time, period: Duration, dag_id: u32) -> Interval { assert!(!period.is_zero(), "`period` must be non-zero."); + let index = get_period_count(dag_id.clone() as usize) as usize; + update_pre_send_outer_timestamp_at(index, start.uptime().as_nanos() as u64, dag_id.clone()); Interval { delay: None, next_tick_target: start, From 29e5173ba1681d46f3de359794dc864d409f71ea Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Tue, 24 Mar 2026 07:26:24 +0900 Subject: [PATCH 03/60] fix: feature devision for test_autoware 1 Signed-off-by: nokosaaan --- applications/tests/test_autoware/Cargo.toml | 5 + .../test_autoware/ekf_localizer/src/lib.rs | 141 ++++--- .../test_autoware/gyro_odometer/src/lib.rs | 116 ++++-- .../test_autoware/imu_corrector/src/lib.rs | 170 ++++++--- .../tests/test_autoware/imu_driver/src/lib.rs | 79 ++-- applications/tests/test_autoware/src/lib.rs | 347 ++++++++++-------- .../vehicle_velocity_converter/src/lib.rs | 60 ++- applications/tests/test_dag/src/lib.rs | 25 +- awkernel_async_lib/Cargo.toml | 2 + awkernel_async_lib/src/dag.rs | 290 +++++++++------ awkernel_async_lib/src/pubsub.rs | 25 +- awkernel_async_lib/src/task.rs | 55 +-- awkernel_async_lib/src/time_interval.rs | 6 +- kernel/Cargo.toml | 1 + userland/src/lib.rs | 3 + x86bootdisk/src/main.rs | 2 +- 16 files changed, 799 insertions(+), 528 deletions(-) diff --git a/applications/tests/test_autoware/Cargo.toml b/applications/tests/test_autoware/Cargo.toml index 9ded42fb7..e625a69fb 100644 --- a/applications/tests/test_autoware/Cargo.toml +++ b/applications/tests/test_autoware/Cargo.toml @@ -7,6 +7,11 @@ edition = "2021" path = "src/lib.rs" crate-type = ["rlib"] +[features] +default = ["dag-no-period"] +dag-send-period = [] +dag-no-period = ["awkernel_async_lib/relax-get-period"] + [dependencies] log = "0.4" libm = "0.2" diff --git a/applications/tests/test_autoware/ekf_localizer/src/lib.rs b/applications/tests/test_autoware/ekf_localizer/src/lib.rs index 585ccb28b..6714aea03 100644 --- a/applications/tests/test_autoware/ekf_localizer/src/lib.rs +++ b/applications/tests/test_autoware/ekf_localizer/src/lib.rs @@ -3,10 +3,10 @@ extern crate alloc; -use core::f64::consts::PI; use alloc::{vec, vec::Vec}; -use nalgebra::{Matrix6, Vector6, Vector3}; -use libm::{sin, cos, atan2, asin}; +use core::f64::consts::PI; +use libm::{asin, atan2, cos, sin}; +use nalgebra::{Matrix6, Vector3, Vector6}; /// State indices for EKF #[derive(Debug, Clone, Copy, PartialEq)] @@ -168,7 +168,7 @@ impl EKFModule { let dim_x = 6; let mut state = StateVector::zeros(); let mut covariance = StateCovariance::identity() * 1e15; - + // Initialize covariance with reasonable values covariance[(StateIndex::Yaw as usize, StateIndex::Yaw as usize)] = 50.0; if params.enable_yaw_bias_estimation { @@ -180,7 +180,7 @@ impl EKFModule { let mut z_filter = Simple1DFilter::new(); let mut roll_filter = Simple1DFilter::new(); let mut pitch_filter = Simple1DFilter::new(); - + z_filter.set_proc_var(params.z_filter_proc_dev * params.z_filter_proc_dev); roll_filter.set_proc_var(params.roll_filter_proc_dev * params.roll_filter_proc_dev); pitch_filter.set_proc_var(params.pitch_filter_proc_dev * params.pitch_filter_proc_dev); @@ -240,9 +240,9 @@ impl EKFModule { // Normalize yaw to [-π, π] range (Autoware compatible) let yaw_next = yaw + wz * dt; x_next[StateIndex::Yaw as usize] = atan2(sin(yaw_next), cos(yaw_next)); - x_next[StateIndex::YawBias as usize] = yaw_bias; // yaw bias doesn't change - x_next[StateIndex::Vx as usize] = vx; // velocity doesn't change in predict - x_next[StateIndex::Wz as usize] = wz; // angular velocity doesn't change in predict + x_next[StateIndex::YawBias as usize] = yaw_bias; // yaw bias doesn't change + x_next[StateIndex::Vx as usize] = vx; // velocity doesn't change in predict + x_next[StateIndex::Wz as usize] = wz; // angular velocity doesn't change in predict x_next } @@ -259,11 +259,11 @@ impl EKFModule { F[(StateIndex::X as usize, StateIndex::Yaw as usize)] = -vx * sin(yaw + yaw_bias) * dt; F[(StateIndex::X as usize, StateIndex::YawBias as usize)] = -vx * sin(yaw + yaw_bias) * dt; F[(StateIndex::X as usize, StateIndex::Vx as usize)] = cos(yaw + yaw_bias) * dt; - + F[(StateIndex::Y as usize, StateIndex::Yaw as usize)] = vx * cos(yaw + yaw_bias) * dt; F[(StateIndex::Y as usize, StateIndex::YawBias as usize)] = vx * cos(yaw + yaw_bias) * dt; F[(StateIndex::Y as usize, StateIndex::Vx as usize)] = sin(yaw + yaw_bias) * dt; - + F[(StateIndex::Yaw as usize, StateIndex::Wz as usize)] = dt; F @@ -273,20 +273,20 @@ impl EKFModule { /// Q represents the uncertainty in the motion model fn process_noise_covariance(&self, dt: f64) -> Matrix6 { let mut Q = Matrix6::zeros(); - + // Process noise for each state variable - Q[(StateIndex::Vx as usize, StateIndex::Vx as usize)] = + Q[(StateIndex::Vx as usize, StateIndex::Vx as usize)] = self.params.proc_stddev_vx_c * self.params.proc_stddev_vx_c * dt * dt; - Q[(StateIndex::Wz as usize, StateIndex::Wz as usize)] = + Q[(StateIndex::Wz as usize, StateIndex::Wz as usize)] = self.params.proc_stddev_wz_c * self.params.proc_stddev_wz_c * dt * dt; - Q[(StateIndex::Yaw as usize, StateIndex::Yaw as usize)] = + Q[(StateIndex::Yaw as usize, StateIndex::Yaw as usize)] = self.params.proc_stddev_yaw_c * self.params.proc_stddev_yaw_c * dt * dt; - + // No process noise for position and yaw bias Q[(StateIndex::X as usize, StateIndex::X as usize)] = 0.0; Q[(StateIndex::Y as usize, StateIndex::Y as usize)] = 0.0; Q[(StateIndex::YawBias as usize, StateIndex::YawBias as usize)] = 0.0; - + Q } @@ -325,12 +325,12 @@ impl EKFModule { let z = self.z_filter.get_x(); let roll = self.roll_filter.get_x(); let pitch = self.pitch_filter.get_x(); - + let x = self.state[StateIndex::X as usize]; let y = self.state[StateIndex::Y as usize]; let biased_yaw = self.state[StateIndex::Yaw as usize]; let yaw_bias = self.state[StateIndex::YawBias as usize]; - + let yaw = if get_biased_yaw { biased_yaw } else { @@ -363,10 +363,10 @@ impl EKFModule { pub fn get_current_pose_with_covariance(&self) -> PoseWithCovariance { // Get current pose let pose = self.get_current_pose(false); - + // Get covariance matrix let pose_covariance = self.get_current_pose_covariance(); - + // Create and return PoseWithCovariance PoseWithCovariance { pose, @@ -377,30 +377,30 @@ impl EKFModule { /// Get pose covariance (simplified 6x6 to 36-element array) pub fn get_current_pose_covariance(&self) -> [f64; 36] { let mut cov = [0.0; 36]; - + // Copy 6x6 covariance matrix to 36-element array for i in 0..6 { for j in 0..6 { cov[i * 6 + j] = self.covariance[(i, j)]; } } - + // Add z, roll, pitch variances - cov[14] = self.z_filter.get_var(); // Z_Z - cov[21] = self.roll_filter.get_var(); // ROLL_ROLL - cov[28] = self.pitch_filter.get_var(); // PITCH_PITCH - + cov[14] = self.z_filter.get_var(); // Z_Z + cov[21] = self.roll_filter.get_var(); // ROLL_ROLL + cov[28] = self.pitch_filter.get_var(); // PITCH_PITCH + cov } /// Get twist covariance pub fn get_current_twist_covariance(&self) -> [f64; 36] { let mut cov = [0.0; 36]; - + // Simplified: only vx and wz have significant covariance - cov[0] = self.covariance[(StateIndex::Vx as usize, StateIndex::Vx as usize)]; // VX_VX + cov[0] = self.covariance[(StateIndex::Vx as usize, StateIndex::Vx as usize)]; // VX_VX cov[35] = self.covariance[(StateIndex::Wz as usize, StateIndex::Wz as usize)]; // WZ_WZ - + cov } @@ -414,27 +414,25 @@ impl EKFModule { // Simple measurement update using Kalman gain // This assumes direct observation of velocity states - + // Measurement variance (assumed) let vx_obs_var = 1.0; let wz_obs_var = 0.1; - + // Update Vx let vx_var = self.covariance[(StateIndex::Vx as usize, StateIndex::Vx as usize)]; let vx_gain = vx_var / (vx_var + vx_obs_var); - self.state[StateIndex::Vx as usize] = - self.state[StateIndex::Vx as usize] + - vx_gain * (vx_measurement - self.state[StateIndex::Vx as usize]); - self.covariance[(StateIndex::Vx as usize, StateIndex::Vx as usize)] = + self.state[StateIndex::Vx as usize] = self.state[StateIndex::Vx as usize] + + vx_gain * (vx_measurement - self.state[StateIndex::Vx as usize]); + self.covariance[(StateIndex::Vx as usize, StateIndex::Vx as usize)] = (1.0 - vx_gain) * vx_var; - + // Update Wz let wz_var = self.covariance[(StateIndex::Wz as usize, StateIndex::Wz as usize)]; let wz_gain = wz_var / (wz_var + wz_obs_var); - self.state[StateIndex::Wz as usize] = - self.state[StateIndex::Wz as usize] + - wz_gain * (wz_measurement - self.state[StateIndex::Wz as usize]); - self.covariance[(StateIndex::Wz as usize, StateIndex::Wz as usize)] = + self.state[StateIndex::Wz as usize] = self.state[StateIndex::Wz as usize] + + wz_gain * (wz_measurement - self.state[StateIndex::Wz as usize]); + self.covariance[(StateIndex::Wz as usize, StateIndex::Wz as usize)] = (1.0 - wz_gain) * wz_var; } @@ -455,10 +453,10 @@ impl EKFModule { if len == 0 { return; } - + let last_time = self.accumulated_delay_times[len - 1]; let new_time = last_time + dt; - + // Shift and add new time for i in 0..len - 1 { self.accumulated_delay_times[i] = self.accumulated_delay_times[i + 1]; @@ -480,7 +478,7 @@ impl EKFModule { // Simple linear search for closest value let mut closest_index = 0; let mut min_diff = f64::MAX; - + for i in 0..len { let time = self.accumulated_delay_times[i]; let diff = (target_value - time).abs(); @@ -489,13 +487,16 @@ impl EKFModule { closest_index = i; } } - + closest_index } // Utility functions for quaternion and euler angle conversions fn quaternion_to_yaw(&self, q: Quaternion) -> f64 { - atan2(2.0 * (q.w * q.z + q.x * q.y), 1.0 - 2.0 * (q.y * q.y + q.z * q.z)) + atan2( + 2.0 * (q.w * q.z + q.x * q.y), + 1.0 - 2.0 * (q.y * q.y + q.z * q.z), + ) } fn rpy_to_quaternion(&self, roll: f64, pitch: f64, yaw: f64) -> Quaternion { @@ -545,14 +546,23 @@ mod tests { fn test_ekf_initialization() { let params = EKFParameters::default(); let mut ekf = EKFModule::new(params); - + let initial_pose = Pose { - position: Point3D { x: 1.0, y: 2.0, z: 0.0 }, - orientation: Quaternion { x: 0.0, y: 0.0, z: 0.0, w: 1.0 }, + position: Point3D { + x: 1.0, + y: 2.0, + z: 0.0, + }, + orientation: Quaternion { + x: 0.0, + y: 0.0, + z: 0.0, + w: 1.0, + }, }; - + ekf.initialize(initial_pose); - + let pose = ekf.get_current_pose(false); assert!((pose.position.x - 1.0).abs() < 1e-6); assert!((pose.position.y - 2.0).abs() < 1e-6); @@ -562,14 +572,14 @@ mod tests { fn test_quaternion_conversions() { let params = EKFParameters::default(); let ekf = EKFModule::new(params); - + let roll = 0.1; let pitch = 0.2; let yaw = 0.3; - + let q = ekf.rpy_to_quaternion(roll, pitch, yaw); let (r, p, y) = ekf.quaternion_to_rpy(q); - + assert!((roll - r).abs() < 1e-6); assert!((pitch - p).abs() < 1e-6); assert!((yaw - y).abs() < 1e-6); @@ -579,21 +589,30 @@ mod tests { fn test_pose_with_covariance_generation() { let params = EKFParameters::default(); let mut ekf = EKFModule::new(params); - + let initial_pose = Pose { - position: Point3D { x: 1.0, y: 2.0, z: 0.0 }, - orientation: Quaternion { x: 0.0, y: 0.0, z: 0.0, w: 1.0 }, + position: Point3D { + x: 1.0, + y: 2.0, + z: 0.0, + }, + orientation: Quaternion { + x: 0.0, + y: 0.0, + z: 0.0, + w: 1.0, + }, }; - + ekf.initialize(initial_pose); - + let pose_with_cov = ekf.get_current_pose_with_covariance(); - + // Check pose assert!((pose_with_cov.pose.position.x - 1.0).abs() < 1e-6); assert!((pose_with_cov.pose.position.y - 2.0).abs() < 1e-6); - + // Check covariance array assert_eq!(pose_with_cov.covariance.len(), 36); } -} \ No newline at end of file +} diff --git a/applications/tests/test_autoware/gyro_odometer/src/lib.rs b/applications/tests/test_autoware/gyro_odometer/src/lib.rs index 8851bda3c..c6659acb7 100644 --- a/applications/tests/test_autoware/gyro_odometer/src/lib.rs +++ b/applications/tests/test_autoware/gyro_odometer/src/lib.rs @@ -4,14 +4,15 @@ extern crate alloc; use alloc::{borrow::Cow, collections::VecDeque, string::String, vec::Vec}; use core::time::Duration; // Global instance and lazy initialization support -use core::sync::atomic::{AtomicPtr, Ordering as AtomicOrdering}; use core::ptr::null_mut; +use core::sync::atomic::{AtomicPtr, Ordering as AtomicOrdering}; // Re-export common types for consistency with other libraries -pub use imu_driver::{Header, Vector3, Quaternion, ImuMsg}; -pub use vehicle_velocity_converter::{Odometry, TwistWithCovarianceStamped, TwistWithCovariance, Twist}; -pub use imu_corrector::{ImuWithCovariance, Transform, transform_covariance}; - +pub use imu_corrector::{transform_covariance, ImuWithCovariance, Transform}; +pub use imu_driver::{Header, ImuMsg, Quaternion, Vector3}; +pub use vehicle_velocity_converter::{ + Odometry, Twist, TwistWithCovariance, TwistWithCovarianceStamped, +}; static GYRO_ODOMETER_INSTANCE: AtomicPtr = AtomicPtr::new(null_mut()); @@ -49,7 +50,7 @@ impl GyroOdometerCore { let queue_size = config.queue_size; let output_frame = config.output_frame.clone(); let message_timeout_sec = config.message_timeout_sec; - + Ok(Self { output_frame, message_timeout_sec, @@ -61,13 +62,14 @@ impl GyroOdometerCore { }) } - - /// Main processing function (matching C++ concat_gyro_and_odometer) - /// + /// /// # Arguments /// * `current_time` - Current system time in nanoseconds (matching C++ this->now()) - pub fn concat_gyro_and_odometer(&mut self, current_time: u64) -> Result> { + pub fn concat_gyro_and_odometer( + &mut self, + current_time: u64, + ) -> Result> { // Check if first messages have arrived (matching C++ implementation) if !self.vehicle_twist_arrived { self.vehicle_twist_queue.clear(); @@ -83,25 +85,30 @@ impl GyroOdometerCore { // Check timeout (matching C++ implementation) // C++: vehicle_twist_dt = std::abs((this->now() - latest_vehicle_twist_ros_time_).seconds()) if !self.vehicle_twist_queue.is_empty() && !self.gyro_queue.is_empty() { - let latest_vehicle_twist_stamp = self.vehicle_twist_queue.back().unwrap().header.timestamp; + let latest_vehicle_twist_stamp = + self.vehicle_twist_queue.back().unwrap().header.timestamp; let latest_imu_stamp = self.gyro_queue.back().unwrap().header.timestamp; - + // Check vehicle twist timeout (matching C++ vehicle_twist_dt > message_timeout_sec_) - if Self::check_timeout(current_time, latest_vehicle_twist_stamp, self.message_timeout_sec) { + if Self::check_timeout( + current_time, + latest_vehicle_twist_stamp, + self.message_timeout_sec, + ) { self.vehicle_twist_queue.clear(); self.gyro_queue.clear(); - return Err(GyroOdometerError::TimeoutError( - String::from("Vehicle twist message timeout") - )); + return Err(GyroOdometerError::TimeoutError(String::from( + "Vehicle twist message timeout", + ))); } - + // Check IMU timeout (matching C++ imu_dt > message_timeout_sec_) if Self::check_timeout(current_time, latest_imu_stamp, self.message_timeout_sec) { self.vehicle_twist_queue.clear(); self.gyro_queue.clear(); - return Err(GyroOdometerError::TimeoutError( - String::from("IMU message timeout") - )); + return Err(GyroOdometerError::TimeoutError(String::from( + "IMU message timeout", + ))); } } @@ -159,7 +166,7 @@ impl GyroOdometerCore { // Create result (matching C++ implementation) let latest_vehicle_twist_stamp = self.vehicle_twist_queue.back().unwrap().header.timestamp; let latest_imu_stamp = self.gyro_queue.back().unwrap().header.timestamp; - + let result_timestamp = if latest_vehicle_twist_stamp < latest_imu_stamp { latest_imu_stamp } else { @@ -181,15 +188,15 @@ impl GyroOdometerCore { }; // Set covariance (matching C++ implementation exactly) - result.twist.covariance[COV_IDX_XYZRPY_X_X] = + result.twist.covariance[COV_IDX_XYZRPY_X_X] = vx_covariance_original / self.vehicle_twist_queue.len() as f64; result.twist.covariance[COV_IDX_XYZRPY_Y_Y] = 100000.0; result.twist.covariance[COV_IDX_XYZRPY_Z_Z] = 100000.0; - result.twist.covariance[COV_IDX_XYZRPY_ROLL_ROLL] = + result.twist.covariance[COV_IDX_XYZRPY_ROLL_ROLL] = gyro_covariance_original.x / self.gyro_queue.len() as f64; - result.twist.covariance[COV_IDX_XYZRPY_PITCH_PITCH] = + result.twist.covariance[COV_IDX_XYZRPY_PITCH_PITCH] = gyro_covariance_original.y / self.gyro_queue.len() as f64; - result.twist.covariance[COV_IDX_XYZRPY_YAW_YAW] = + result.twist.covariance[COV_IDX_XYZRPY_YAW_YAW] = gyro_covariance_original.z / self.gyro_queue.len() as f64; // Clear queues (matching C++ implementation) @@ -221,7 +228,10 @@ impl GyroOdometerCore { } /// Process result and apply vehicle stop logic - pub fn process_result(&self, twist_with_cov_raw: TwistWithCovarianceStamped) -> TwistWithCovarianceStamped { + pub fn process_result( + &self, + twist_with_cov_raw: TwistWithCovarianceStamped, + ) -> TwistWithCovarianceStamped { // 車両が停止している場合の処理 (matching C++ implementation exactly) if twist_with_cov_raw.twist.twist.angular.z.abs() < 0.01 && twist_with_cov_raw.twist.twist.linear.x.abs() < 0.01 @@ -237,7 +247,11 @@ impl GyroOdometerCore { } /// Convert vehicle velocity data to twist format - pub fn convert_vehicle_velocity_to_twist(&self, odometry: &Odometry, timestamp: u64) -> TwistWithCovarianceStamped { + pub fn convert_vehicle_velocity_to_twist( + &self, + odometry: &Odometry, + timestamp: u64, + ) -> TwistWithCovarianceStamped { TwistWithCovarianceStamped { header: Header { frame_id: "base_link", @@ -266,7 +280,10 @@ impl GyroOdometerCore { } /// Process queues and get result (matching test_autoware process_queues_and_get_result) - pub fn process_and_get_result(&mut self, current_time: u64) -> Option { + pub fn process_and_get_result( + &mut self, + current_time: u64, + ) -> Option { match self.concat_gyro_and_odometer(current_time) { Ok(result) => result, Err(_) => None, @@ -370,19 +387,28 @@ mod tests { assert_eq!(imu_msg.header.frame_id, converted_back.header.frame_id); assert_eq!(imu_msg.header.timestamp, converted_back.header.timestamp); - assert_eq!(imu_msg.angular_velocity.x, converted_back.angular_velocity.x); - assert_eq!(imu_msg.angular_velocity.y, converted_back.angular_velocity.y); - assert_eq!(imu_msg.angular_velocity.z, converted_back.angular_velocity.z); + assert_eq!( + imu_msg.angular_velocity.x, + converted_back.angular_velocity.x + ); + assert_eq!( + imu_msg.angular_velocity.y, + converted_back.angular_velocity.y + ); + assert_eq!( + imu_msg.angular_velocity.z, + converted_back.angular_velocity.z + ); } #[test] fn test_vehicle_velocity_conversion() { let config = GyroOdometerConfig::default(); let core = GyroOdometerCore::new(config).unwrap(); - + let odometry = Odometry { velocity: 15.5 }; let twist = core.convert_vehicle_velocity_to_twist(&odometry, 123456789); - + assert_eq!(twist.header.frame_id, "base_link"); assert_eq!(twist.header.timestamp, 123456789); assert_eq!(twist.twist.twist.linear.x, 15.5); @@ -394,7 +420,7 @@ mod tests { fn test_imu_corrector_integration() { let config = GyroOdometerConfig::default(); let mut core = GyroOdometerCore::new(config).unwrap(); - + // Create IMU with covariance from imu_corrector let imu_with_cov = ImuWithCovariance { header: Header { @@ -410,7 +436,17 @@ mod tests { angular_velocity: Vector3::new(0.1, 0.2, 0.3), angular_velocity_covariance: [0.0009, 0.0, 0.0, 0.0, 0.0009, 0.0, 0.0, 0.0, 0.0009], // 0.03^2 linear_acceleration: Vector3::new(9.8, 0.0, 0.0), - linear_acceleration_covariance: [100000000.0, 0.0, 0.0, 0.0, 100000000.0, 0.0, 0.0, 0.0, 100000000.0], // 10000^2 + linear_acceleration_covariance: [ + 100000000.0, + 0.0, + 0.0, + 0.0, + 100000000.0, + 0.0, + 0.0, + 0.0, + 100000000.0, + ], // 10000^2 }; // Process IMU with covariance @@ -433,19 +469,19 @@ mod tests { /// This provides lazy initialization with thread-safe access pub fn get_or_initialize() -> Result<&'static mut GyroOdometerCore> { let ptr = GYRO_ODOMETER_INSTANCE.load(AtomicOrdering::Acquire); - + if !ptr.is_null() { return Ok(unsafe { &mut *ptr }); } - + // Not initialized, try to initialize let config = GyroOdometerConfig::default(); let core = GyroOdometerCore::new(config)?; - + // Allocate on heap and store pointer let boxed_core = alloc::boxed::Box::new(core); let new_ptr = alloc::boxed::Box::into_raw(boxed_core); - + // Try to store the pointer atomically match GYRO_ODOMETER_INSTANCE.compare_exchange( null_mut(), @@ -465,4 +501,4 @@ pub fn get_or_initialize() -> Result<&'static mut GyroOdometerCore> { Ok(unsafe { &mut *existing_ptr }) } } -} \ No newline at end of file +} diff --git a/applications/tests/test_autoware/imu_corrector/src/lib.rs b/applications/tests/test_autoware/imu_corrector/src/lib.rs index 3abe671ee..97db33846 100644 --- a/applications/tests/test_autoware/imu_corrector/src/lib.rs +++ b/applications/tests/test_autoware/imu_corrector/src/lib.rs @@ -1,9 +1,9 @@ #![no_std] extern crate alloc; -use nalgebra::{Matrix3, UnitQuaternion, Vector3 as NVector3, Quaternion as NQuaternion}; -use imu_driver::{ImuMsg, Vector3, Quaternion, Header}; use alloc::{format, string::String}; +use imu_driver::{Header, ImuMsg, Quaternion, Vector3}; +use nalgebra::{Matrix3, Quaternion as NQuaternion, UnitQuaternion, Vector3 as NVector3}; // Transform structure (simplified TF representation) #[derive(Clone, Debug)] @@ -55,7 +55,12 @@ impl Transform { // Dynamic TF listener interface (simplified version) pub trait TransformListener { fn get_latest_transform(&self, from_frame: &str, to_frame: &str) -> Option; - fn get_transform_at_time(&self, from_frame: &str, to_frame: &str, timestamp: u64) -> Option; + fn get_transform_at_time( + &self, + from_frame: &str, + to_frame: &str, + timestamp: u64, + ) -> Option; } // Mock TF listener for testing (can be replaced with actual ROS2 TF implementation) @@ -82,7 +87,12 @@ impl TransformListener for MockTransformListener { self.transforms.get(&key).cloned() } - fn get_transform_at_time(&self, from_frame: &str, to_frame: &str, _timestamp: u64) -> Option { + fn get_transform_at_time( + &self, + from_frame: &str, + to_frame: &str, + _timestamp: u64, + ) -> Option { // For mock implementation, ignore timestamp and return latest self.get_latest_transform(from_frame, to_frame) } @@ -199,11 +209,11 @@ impl ImuCorrector { let nalgebra_vec = self.to_nalgebra_vector3(vec); let nalgebra_quat = self.to_nalgebra_quaternion(&transform.rotation); let nalgebra_trans = self.to_nalgebra_vector3(&transform.translation); - + // Apply rotation and translation let rotated = nalgebra_quat * nalgebra_vec; let result = rotated + nalgebra_trans; - + // Convert back to imu_driver Vector3 self.to_imu_vector3(&result) } @@ -213,14 +223,14 @@ impl ImuCorrector { fn transform_covariance(&self, cov: &[f64; 9]) -> [f64; 9] { // Find maximum covariance value from diagonal elements (xx, yy, zz) let max_cov = cov[0].max(cov[4]).max(cov[8]); // X_X, Y_Y, Z_Z indices - + // Create new covariance matrix with max_cov on diagonal, zeros elsewhere let mut cov_transformed = [0.0; 9]; cov_transformed[0] = max_cov; // X_X cov_transformed[4] = max_cov; // Y_Y cov_transformed[8] = max_cov; // Z_Z - // Other elements remain 0.0 - + // Other elements remain 0.0 + cov_transformed } @@ -232,15 +242,25 @@ impl ImuCorrector { /// Convert Matrix3 to array format for compatibility fn matrix3_to_array(&self, matrix: &Matrix3) -> [f64; 9] { [ - matrix[(0, 0)], matrix[(0, 1)], matrix[(0, 2)], - matrix[(1, 0)], matrix[(1, 1)], matrix[(1, 2)], - matrix[(2, 0)], matrix[(2, 1)], matrix[(2, 2)], + matrix[(0, 0)], + matrix[(0, 1)], + matrix[(0, 2)], + matrix[(1, 0)], + matrix[(1, 1)], + matrix[(1, 2)], + matrix[(2, 0)], + matrix[(2, 1)], + matrix[(2, 2)], ] } /// Correct IMU data with covariance (enhanced version for gyro_odometer) /// This function matches the C++ callback_imu function more faithfully - pub fn correct_imu_with_covariance(&self, imu_msg: &ImuMsg, transform: Option<&Transform>) -> ImuWithCovariance { + pub fn correct_imu_with_covariance( + &self, + imu_msg: &ImuMsg, + transform: Option<&Transform>, + ) -> ImuWithCovariance { // Start with a copy of the input IMU message (matches C++ line 82) let mut corrected_imu = ImuWithCovariance::from_imu_msg(imu_msg); @@ -251,11 +271,11 @@ impl ImuCorrector { // Calculate angular velocity covariance (matches C++ lines 89-93) // Convert to array format: [xx, xy, xz, yx, yy, yz, zx, zy, zz] - corrected_imu.angular_velocity_covariance[0] = + corrected_imu.angular_velocity_covariance[0] = self.config.angular_velocity_stddev_xx * self.config.angular_velocity_stddev_xx; // xx - corrected_imu.angular_velocity_covariance[4] = + corrected_imu.angular_velocity_covariance[4] = self.config.angular_velocity_stddev_yy * self.config.angular_velocity_stddev_yy; // yy - corrected_imu.angular_velocity_covariance[8] = + corrected_imu.angular_velocity_covariance[8] = self.config.angular_velocity_stddev_zz * self.config.angular_velocity_stddev_zz; // zz // Calculate acceleration covariance (matches C++ lines 98-103) @@ -267,17 +287,19 @@ impl ImuCorrector { // Apply TF transformation if provided (matches C++ lines 105-125) if let Some(tf) = transform { // Transform linear acceleration (matches C++ line 115) - corrected_imu.linear_acceleration = self.transform_vector3(&corrected_imu.linear_acceleration, tf); + corrected_imu.linear_acceleration = + self.transform_vector3(&corrected_imu.linear_acceleration, tf); // Transform linear acceleration covariance (matches C++ line 116) - corrected_imu.linear_acceleration_covariance = + corrected_imu.linear_acceleration_covariance = self.transform_covariance(&corrected_imu.linear_acceleration_covariance); - + // Transform angular velocity (matches C++ line 118) - corrected_imu.angular_velocity = self.transform_vector3(&corrected_imu.angular_velocity, tf); + corrected_imu.angular_velocity = + self.transform_vector3(&corrected_imu.angular_velocity, tf); // Transform angular velocity covariance (matches C++ line 119) - corrected_imu.angular_velocity_covariance = + corrected_imu.angular_velocity_covariance = self.transform_covariance(&corrected_imu.angular_velocity_covariance); - + // Update frame_id (matches C++ line 113) corrected_imu.header.frame_id = self.config.output_frame; } @@ -294,10 +316,9 @@ impl ImuCorrector { /// Correct IMU data with dynamic TF lookup (matches C++ callback_imu function) pub fn correct_imu_with_dynamic_tf(&self, imu_msg: &ImuMsg) -> Option { // Get latest transform dynamically (matches C++ lines 106-107) - let transform = self.transform_listener.get_latest_transform( - &imu_msg.header.frame_id, - self.config.output_frame - )?; + let transform = self + .transform_listener + .get_latest_transform(&imu_msg.header.frame_id, self.config.output_frame)?; // Apply correction with the dynamic transform let corrected_with_cov = self.correct_imu_with_covariance(imu_msg, Some(&transform)); @@ -305,12 +326,14 @@ impl ImuCorrector { } /// Correct IMU data with dynamic TF lookup and covariance - pub fn correct_imu_with_dynamic_tf_covariance(&self, imu_msg: &ImuMsg) -> Option { + pub fn correct_imu_with_dynamic_tf_covariance( + &self, + imu_msg: &ImuMsg, + ) -> Option { // Get latest transform dynamically (matches C++ lines 106-107) - let transform = self.transform_listener.get_latest_transform( - &imu_msg.header.frame_id, - self.config.output_frame - )?; + let transform = self + .transform_listener + .get_latest_transform(&imu_msg.header.frame_id, self.config.output_frame)?; // Apply correction with the dynamic transform Some(self.correct_imu_with_covariance(imu_msg, Some(&transform))) @@ -327,7 +350,7 @@ impl ImuCorrector { // Update frame_id corrected_msg.header.frame_id = self.config.output_frame; - + corrected_msg } @@ -348,14 +371,14 @@ impl ImuCorrector { pub fn transform_covariance(cov: &[f64; 9]) -> [f64; 9] { // Find maximum covariance value from diagonal elements (xx, yy, zz) let max_cov = cov[0].max(cov[4]).max(cov[8]); // X_X, Y_Y, Z_Z indices - + // Create new covariance matrix with max_cov on diagonal, zeros elsewhere let mut cov_transformed = [0.0; 9]; cov_transformed[0] = max_cov; // X_X cov_transformed[4] = max_cov; // Y_Y cov_transformed[8] = max_cov; // Z_Z - // Other elements remain 0.0 - + // Other elements remain 0.0 + cov_transformed } @@ -383,7 +406,7 @@ mod tests { let corrected_msg = corrector.correct_imu_simple(&imu_msg); assert_eq!(corrected_msg.header.frame_id, "base_link"); - + // Check that offset correction was applied (no offset in default config) assert_eq!(corrected_msg.angular_velocity.x, 0.1); assert_eq!(corrected_msg.angular_velocity.y, 0.2); @@ -396,10 +419,10 @@ mod tests { config.angular_velocity_offset_x = 0.05; config.angular_velocity_offset_y = 0.1; config.angular_velocity_offset_z = 0.15; - + let mut corrector = ImuCorrector::new(); corrector.set_config(config); - + let imu_msg = ImuMsg { header: Header { frame_id: "imu_link", @@ -416,7 +439,7 @@ mod tests { }; let corrected_msg = corrector.correct_imu_simple(&imu_msg); - + // Check that offset correction was applied assert_eq!(corrected_msg.angular_velocity.x, 0.1 - 0.05); assert_eq!(corrected_msg.angular_velocity.y, 0.2 - 0.1); @@ -442,32 +465,50 @@ mod tests { }; let corrected_with_cov = corrector.correct_imu_with_covariance(&imu_msg, None); - + // Check that covariance was calculated correctly let expected_angular_var = 0.03 * 0.03; // stddev^2 - assert_eq!(corrected_with_cov.angular_velocity_covariance[0], expected_angular_var); // xx - assert_eq!(corrected_with_cov.angular_velocity_covariance[4], expected_angular_var); // yy - assert_eq!(corrected_with_cov.angular_velocity_covariance[8], expected_angular_var); // zz - + assert_eq!( + corrected_with_cov.angular_velocity_covariance[0], + expected_angular_var + ); // xx + assert_eq!( + corrected_with_cov.angular_velocity_covariance[4], + expected_angular_var + ); // yy + assert_eq!( + corrected_with_cov.angular_velocity_covariance[8], + expected_angular_var + ); // zz + let expected_accel_var = 10000.0 * 10000.0; // stddev^2 - assert_eq!(corrected_with_cov.linear_acceleration_covariance[0], expected_accel_var); // xx - assert_eq!(corrected_with_cov.linear_acceleration_covariance[4], expected_accel_var); // yy - assert_eq!(corrected_with_cov.linear_acceleration_covariance[8], expected_accel_var); // zz + assert_eq!( + corrected_with_cov.linear_acceleration_covariance[0], + expected_accel_var + ); // xx + assert_eq!( + corrected_with_cov.linear_acceleration_covariance[4], + expected_accel_var + ); // yy + assert_eq!( + corrected_with_cov.linear_acceleration_covariance[8], + expected_accel_var + ); // zz } #[test] fn test_transform_covariance() { let corrector = ImuCorrector::new(); - + // Test covariance transformation (matches C++ transform_covariance function) let input_cov = [1.0, 0.5, 0.3, 0.5, 2.0, 0.4, 0.3, 0.4, 3.0]; // xx=1, yy=2, zz=3 let transformed_cov = corrector.transform_covariance(&input_cov); - + // Should take maximum value (3.0) and apply to diagonal assert_eq!(transformed_cov[0], 3.0); // xx assert_eq!(transformed_cov[4], 3.0); // yy assert_eq!(transformed_cov[8], 3.0); // zz - + // Off-diagonal elements should be 0 assert_eq!(transformed_cov[1], 0.0); // xy assert_eq!(transformed_cov[2], 0.0); // xz @@ -482,12 +523,12 @@ mod tests { // Test the public transform_covariance function let input_cov = [1.0, 0.5, 0.3, 0.5, 2.0, 0.4, 0.3, 0.4, 3.0]; // xx=1, yy=2, zz=3 let transformed_cov = transform_covariance(&input_cov); - + // Should take maximum value (3.0) and apply to diagonal assert_eq!(transformed_cov[0], 3.0); // xx assert_eq!(transformed_cov[4], 3.0); // yy assert_eq!(transformed_cov[8], 3.0); // zz - + // Off-diagonal elements should be 0 assert_eq!(transformed_cov[1], 0.0); // xy assert_eq!(transformed_cov[2], 0.0); // xz @@ -526,15 +567,24 @@ mod tests { }; let corrected_with_cov = corrector.correct_imu_with_covariance(&imu_msg, Some(&transform)); - + // Check that frame_id was updated assert_eq!(corrected_with_cov.header.frame_id, "base_link"); - + // Check that covariance was transformed (should use max value) let expected_angular_var = 0.03 * 0.03; // stddev^2 - assert_eq!(corrected_with_cov.angular_velocity_covariance[0], expected_angular_var); // xx - assert_eq!(corrected_with_cov.angular_velocity_covariance[4], expected_angular_var); // yy - assert_eq!(corrected_with_cov.angular_velocity_covariance[8], expected_angular_var); // zz + assert_eq!( + corrected_with_cov.angular_velocity_covariance[0], + expected_angular_var + ); // xx + assert_eq!( + corrected_with_cov.angular_velocity_covariance[4], + expected_angular_var + ); // yy + assert_eq!( + corrected_with_cov.angular_velocity_covariance[8], + expected_angular_var + ); // zz } #[test] @@ -550,7 +600,7 @@ mod tests { }, }; transform_listener.add_transform("imu_link", "base_link", transform); - + let corrector = ImuCorrector::with_transform_listener(transform_listener); let imu_msg = ImuMsg { header: Header { @@ -569,11 +619,11 @@ mod tests { let corrected_msg = corrector.correct_imu_with_dynamic_tf(&imu_msg); assert!(corrected_msg.is_some()); - + let corrected_msg = corrected_msg.unwrap(); // Check that frame_id was updated assert_eq!(corrected_msg.header.frame_id, "base_link"); - + // Check that translation was applied (linear acceleration should be transformed) // With translation of (1.0, 0.0, 0.0), the acceleration should be affected assert_eq!(corrected_msg.linear_acceleration.x, 9.8); // No change for identity rotation diff --git a/applications/tests/test_autoware/imu_driver/src/lib.rs b/applications/tests/test_autoware/imu_driver/src/lib.rs index 9d7f29837..09c2d6882 100644 --- a/applications/tests/test_autoware/imu_driver/src/lib.rs +++ b/applications/tests/test_autoware/imu_driver/src/lib.rs @@ -1,9 +1,9 @@ #![no_std] extern crate alloc; -use alloc::{vec, vec::Vec, format,string::String}; +use alloc::{format, string::String, vec, vec::Vec}; //use awkernel_lib::time::Time; -use core::{f64::consts::PI}; +use core::f64::consts::PI; // IMU message structure #[derive(Clone, Debug)] @@ -68,23 +68,28 @@ pub struct TamagawaImuParser { impl TamagawaImuParser { pub fn new(frame_id: &'static str) -> Self { - Self { + Self { frame_id, dummy_counter: 0, } } /// Parse binary IMU data from Tamagawa sensor - /// + /// /// # Arguments /// * `data` - Raw binary data from sensor (expected length 58 bytes) /// * `timestamp` - Current timestamp in nanoseconds - /// + /// /// # Returns /// * `Option` - Parsed IMU message if data is valid, None otherwise pub fn parse_binary_data(&self, data: &[u8], timestamp: u64) -> Option { // Check if data is valid BIN format and correct length - if data.len() != 58 || data[5] != b'B' || data[6] != b'I' || data[7] != b'N' || data[8] != b',' { + if data.len() != 58 + || data[5] != b'B' + || data[6] != b'I' + || data[7] != b'N' + || data[8] != b',' + { return None; } @@ -125,12 +130,12 @@ impl TamagawaImuParser { } /// Generate dummy binary data for testing - /// + /// /// # Arguments /// * `timestamp` - Current timestamp in nanoseconds /// * `angular_velocity` - Angular velocity values in rad/s /// * `linear_acceleration` - Linear acceleration values in m/s² - /// + /// /// # Returns /// * `Vec` - 58-byte binary data in Tamagawa format pub fn generate_dummy_binary_data( @@ -140,29 +145,29 @@ impl TamagawaImuParser { linear_acceleration: Vector3, ) -> Vec { let mut data = vec![0u8; 58]; - + // Header: $TSC,BIN, data[0..5].copy_from_slice(b"$TSC,"); data[5] = b'B'; data[6] = b'I'; data[7] = b'N'; data[8] = b','; - + // Counter (bytes 11-12) data[11] = (self.dummy_counter >> 8) as u8; data[12] = (self.dummy_counter & 0xFF) as u8; self.dummy_counter = self.dummy_counter.wrapping_add(1); - + // Convert angular velocity from rad/s to LSB let angular_vel_x_lsb = self.convert_angular_velocity_to_lsb(angular_velocity.x); let angular_vel_y_lsb = self.convert_angular_velocity_to_lsb(angular_velocity.y); let angular_vel_z_lsb = self.convert_angular_velocity_to_lsb(angular_velocity.z); - + // Convert acceleration from m/s² to LSB let accel_x_lsb = self.convert_acceleration_to_lsb(linear_acceleration.x); let accel_y_lsb = self.convert_acceleration_to_lsb(linear_acceleration.y); let accel_z_lsb = self.convert_acceleration_to_lsb(linear_acceleration.z); - + // Angular velocity data (bytes 15-20) data[15] = (angular_vel_x_lsb >> 8) as u8; data[16] = (angular_vel_x_lsb & 0xFF) as u8; @@ -170,7 +175,7 @@ impl TamagawaImuParser { data[18] = (angular_vel_y_lsb & 0xFF) as u8; data[19] = (angular_vel_z_lsb >> 8) as u8; data[20] = (angular_vel_z_lsb & 0xFF) as u8; - + // Linear acceleration data (bytes 21-26) data[21] = (accel_x_lsb >> 8) as u8; data[22] = (accel_x_lsb & 0xFF) as u8; @@ -178,48 +183,48 @@ impl TamagawaImuParser { data[24] = (accel_y_lsb & 0xFF) as u8; data[25] = (accel_z_lsb >> 8) as u8; data[26] = (accel_z_lsb & 0xFF) as u8; - + data } /// Generate sinusoidal dummy data for realistic simulation - /// + /// /// # Arguments /// * `timestamp` - Current timestamp in nanoseconds /// * `time_offset` - Time offset for phase calculation - /// + /// /// # Returns /// * `Vec` - 58-byte binary data with sinusoidal motion /* pub fn generate_sinusoidal_dummy_data(&mut self, timestamp: u64, time_offset: f64) -> Vec { // Convert timestamp to seconds for sinusoidal calculation let time_sec = (timestamp as f64) / 1_000_000_000.0 + time_offset; - + // Generate sinusoidal angular velocity (rotation around Z-axis) let angular_vel_z = 0.5 * (2.0 * PI * 0.1 * time_sec).sin(); // 0.1 Hz, ±0.5 rad/s - + // Generate sinusoidal acceleration (oscillation in X-axis) let accel_x = 9.8 + 2.0 * (2.0 * PI * 0.05 * time_sec).sin(); // 0.05 Hz, 9.8±2.0 m/s² - + let angular_velocity = Vector3::new(0.1, 0.2, angular_vel_z); let linear_acceleration = Vector3::new(accel_x, 0.0, 9.8); - + self.generate_dummy_binary_data(timestamp, angular_velocity, linear_acceleration) } */ /// Generate static dummy data with fixed values - /// + /// /// # Arguments /// * `timestamp` - Current timestamp in nanoseconds - /// + /// /// # Returns /// * `Vec` - 58-byte binary data with static values // Autoware側と統一:加速度は重力加速度のみ pub fn generate_static_dummy_data(&mut self, timestamp: u64) -> Vec { let angular_velocity = Vector3::new(0.1, 0.2, 0.01); - let linear_acceleration = Vector3::new(0.0, 0.0, 9.80665); // z方向のみ重力加速度 - + let linear_acceleration = Vector3::new(0.0, 0.0, 9.80665); // z方向のみ重力加速度 + self.generate_dummy_binary_data(timestamp, angular_velocity, linear_acceleration) } @@ -237,7 +242,7 @@ impl TamagawaImuParser { } /// Parse signed 16-bit value from 2 bytes - /// + /// /// This matches the C++ implementation: /// raw_data = ((((rbuf[15] << 8) & 0xFFFFFF00) | (rbuf[16] & 0x000000FF))); fn parse_signed_16bit(&self, data: &[u8]) -> i16 { @@ -252,7 +257,7 @@ impl TamagawaImuParser { } /// Convert raw angular velocity data to rad/s - /// + /// /// Raw data is in LSB units with range ±200 deg/s /// Conversion: raw * (200 / 2^15) * π / 180 fn convert_angular_velocity(&self, raw_data: i16) -> f64 { @@ -262,7 +267,7 @@ impl TamagawaImuParser { } /// Convert raw acceleration data to m/s² - /// + /// /// Raw data is in LSB units with range ±100 m/s² /// Conversion: raw * (100 / 2^15) fn convert_acceleration(&self, raw_data: i16) -> f64 { @@ -291,8 +296,6 @@ impl TamagawaImuParser { } } - - #[cfg(test)] mod tests { use super::*; @@ -301,13 +304,13 @@ mod tests { fn example_usage() { // Create parser instance let mut parser = TamagawaImuParser::new("imu_link"); - + // Generate commands let version_cmd = TamagawaImuParser::generate_version_request(); let binary_cmd = TamagawaImuParser::generate_binary_request(30); let offset_cmd = TamagawaImuParser::generate_offset_cancel_request(123); let heading_cmd = TamagawaImuParser::generate_heading_reset_request(); - + // Example 1: Generate static dummy data let static_dummy_data = parser.generate_static_dummy_data(123456789); if let Some(imu_msg) = parser.parse_binary_data(&static_dummy_data, 123456789) { @@ -315,7 +318,7 @@ mod tests { let _angular_vel = imu_msg.angular_velocity; let _acceleration = imu_msg.linear_acceleration; } - + // Example 2: Generate sinusoidal dummy data for realistic simulation let sinusoidal_dummy_data = parser.generate_sinusoidal_dummy_data(123456789, 0.0); if let Some(imu_msg) = parser.parse_binary_data(&sinusoidal_dummy_data, 123456789) { @@ -323,14 +326,14 @@ mod tests { let _angular_vel = imu_msg.angular_velocity; let _acceleration = imu_msg.linear_acceleration; } - + // Example 3: Generate custom dummy data let custom_angular_velocity = Vector3::new(0.5, -0.3, 1.2); let custom_acceleration = Vector3::new(8.5, 2.1, 10.2); let custom_dummy_data = parser.generate_dummy_binary_data( - 123456789, - custom_angular_velocity, - custom_acceleration + 123456789, + custom_angular_velocity, + custom_acceleration, ); if let Some(imu_msg) = parser.parse_binary_data(&custom_dummy_data, 123456789) { // Use the parsed IMU message with custom values @@ -338,4 +341,4 @@ mod tests { let _acceleration = imu_msg.linear_acceleration; } } -} \ No newline at end of file +} diff --git a/applications/tests/test_autoware/src/lib.rs b/applications/tests/test_autoware/src/lib.rs index 4ea886cb6..0ac57c330 100644 --- a/applications/tests/test_autoware/src/lib.rs +++ b/applications/tests/test_autoware/src/lib.rs @@ -1,39 +1,38 @@ #![no_std] extern crate alloc; -use alloc::{borrow::Cow, vec, vec::Vec, collections::VecDeque, string::String, format, sync::Arc}; +use alloc::{borrow::Cow, collections::VecDeque, format, string::String, sync::Arc, vec, vec::Vec}; use awkernel_async_lib::dag::{create_dag, finish_create_dags}; +use awkernel_async_lib::net::IpAddr; use awkernel_async_lib::scheduler::SchedulerType; +#[cfg(feature = "dag-send-period")] use awkernel_async_lib::task::perf::get_period_count; -use awkernel_lib::net::{add_ipv4_addr, poll_interface, get_all_interface}; -use awkernel_async_lib::net::{tcp::TcpStream, tcp::TcpConfig, udp::{UdpConfig, UdpSocketError},IpAddr}; use awkernel_lib::delay::wait_microsec; use awkernel_lib::sync::mutex::{MCSNode, Mutex}; -use core::time::Duration; use core::net::Ipv4Addr; -use csv_core::{Reader, ReadRecordResult}; +use core::time::Duration; +use csv_core::{ReadRecordResult, Reader}; // Thread-safe state management using atomic operations -use core::sync::atomic::{AtomicBool, AtomicU64, AtomicUsize,Ordering}; +use core::sync::atomic::{AtomicBool, AtomicU64, AtomicUsize, Ordering}; // Global gyro odometer core instance with proper synchronization -use core::sync::atomic::{AtomicPtr, Ordering as AtomicOrdering}; use core::ptr::null_mut; - +use core::sync::atomic::{AtomicPtr, Ordering as AtomicOrdering}; // IMU ドライバーライブラリをインポート -use imu_driver::{ImuMsg,TamagawaImuParser, Header, Vector3}; use imu_corrector::{ImuCorrector, ImuWithCovariance, Transform}; +use imu_driver::{Header, ImuMsg, TamagawaImuParser, Vector3}; // Vehicle Velocity Converter ライブラリをインポート(C++のpubsub機能に対応) use vehicle_velocity_converter::{ - VehicleVelocityConverter, VelocityReport, TwistWithCovarianceStamped, - TwistWithCovariance, Twist, reactor_helpers}; + reactor_helpers, Twist, TwistWithCovariance, TwistWithCovarianceStamped, + VehicleVelocityConverter, VelocityReport, +}; // Gyro Odometer ライブラリをインポート -use gyro_odometer::{ - GyroOdometerCore, GyroOdometerConfig}; +use gyro_odometer::{GyroOdometerConfig, GyroOdometerCore}; // EKF Localizer ライブラリをインポート -use ekf_localizer::{EKFModule, EKFParameters, Pose, Point3D, Quaternion, PoseWithCovariance}; +use ekf_localizer::{EKFModule, EKFParameters, Point3D, Pose, PoseWithCovariance, Quaternion}; // COMMENTED OUT: 手動積分用の関数をコメントアウトしたためlibmは不要 // use libm::{atan2, cos, sin}; @@ -46,8 +45,7 @@ pub struct EKFOdometry { pub twist: TwistWithCovariance, } -const LOG_ENABLE: bool = false; - +const LOG_ENABLE: bool = true; // EKF pose covariance (6x6 matrix flattened to array) // Layout: [x, xy, xz, xr, xp, xy_yaw, @@ -57,12 +55,9 @@ const LOG_ENABLE: bool = false; // px, py, pz, pr, p, p_yaw, // yaw_x, yaw_y, yaw_z, yaw_r, yaw_p, yaw] const EKF_POSE_COVARIANCE: [f64; 36] = [ - 0.0225, 0.0, 0.0, 0.0, 0.0, 0.0, - 0.0, 0.0225, 0.0, 0.0, 0.0, 0.0, - 0.0, 0.0, 0.0225, 0.0, 0.0, 0.0, - 0.0, 0.0, 0.0, 0.000625, 0.0, 0.0, - 0.0, 0.0, 0.0, 0.0, 0.000625, 0.0, - 0.0, 0.0, 0.0, 0.0, 0.0, 0.000625, + 0.0225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0225, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.000625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000625, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.000625, ]; // EKF twist covariance (6x6 matrix flattened to array) @@ -75,12 +70,9 @@ const EKF_POSE_COVARIANCE: [f64; 36] = [ // wz_x, wz_y, wz_z, wz_rx, wz_ry, wz] // Based on Autoware's typical twist uncertainty (0.01 m/s for linear, 0.01 rad/s for angular) const EKF_TWIST_COVARIANCE: [f64; 36] = [ - 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, - 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, - 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, - 0.0, 0.0, 0.0, 0.0001, 0.0, 0.0, - 0.0, 0.0, 0.0, 0.0, 0.0001, 0.0, - 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001, + 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0001, ]; static LAST_DR_TIMESTAMP: AtomicU64 = AtomicU64::new(0); @@ -133,14 +125,47 @@ static mut VELOCITY_CSV_DATA: Option> = None; static IMU_CSV_COUNT: Mutex = Mutex::new(0); static VELOCITY_CSV_COUNT: Mutex = Mutex::new(0); - // Global EKF Localizer instance with proper synchronization static EKF_LOCALIZER: AtomicPtr = AtomicPtr::new(null_mut()); +#[cfg(feature = "dag-send-period")] +type DagMsg = (T, u32); +#[cfg(not(feature = "dag-send-period"))] +type DagMsg = T; + +#[cfg(feature = "dag-send-period")] +fn pack_dag_msg(value: T, period_id: u32) -> DagMsg { + (value, period_id) +} + +#[cfg(not(feature = "dag-send-period"))] +fn pack_dag_msg(value: T, _period_id: u32) -> DagMsg { + value +} + +#[cfg(feature = "dag-send-period")] +fn unpack_dag_msg(msg: DagMsg) -> (T, u32) { + msg +} + +#[cfg(not(feature = "dag-send-period"))] +fn unpack_dag_msg(msg: DagMsg) -> (T, u32) { + (msg, 0) +} + +#[cfg(feature = "dag-send-period")] +fn current_period_id(dag_id: u32) -> u32 { + get_period_count(dag_id as usize) as u32 +} + +#[cfg(not(feature = "dag-send-period"))] +fn current_period_id(_dag_id: u32) -> u32 { + 0 +} + // COMMENTED OUT: 手動積分用のDR_POSEはEKF内部状態からポーズを取得するようになったため不要 // static mut DR_POSE: Option = None; - pub async fn run() { wait_microsec(1000000); @@ -149,7 +174,7 @@ pub async fn run() { } log::info!("Starting Autoware test application with simplified TCP networking"); - + // 初期ネットワークインターフェース情報を表示 //print_network_interfaces(); @@ -159,27 +184,36 @@ pub async fn run() { // ダミーデータ送信用リアクター // MODIFIED: 周期を10msから50msに変更(Autowareのekf_data_publisher.pyと同じ周期) // これにより、CSVデータの消費速度が両システムで一致する - dag.register_periodic_reactor::<_, ((i32, u32), (i32, u32), (i32, u32))>( + dag.register_periodic_reactor::<_, (DagMsg, DagMsg, DagMsg)>( "start_dummy_data".into(), - move || -> ((i32, u32), (i32, u32), (i32, u32)) { - let period_id = get_period_count(dag_id as usize) as u32; - return ((1, period_id), (2, period_id), (3, period_id)); // 通常のデータ処理用の値 + move || -> (DagMsg, DagMsg, DagMsg) { + let period_id = current_period_id(dag_id); + ( + pack_dag_msg(1, period_id), + pack_dag_msg(2, period_id), + pack_dag_msg(3, period_id), + ) }, - vec![Cow::from("start_imu"),Cow::from("start_vel"),Cow::from("start_pose")], + vec![ + Cow::from("start_imu"), + Cow::from("start_vel"), + Cow::from("start_pose"), + ], SchedulerType::GEDF(5), - Duration::from_millis(50) // CHANGED: 10ms -> 50ms (Autowareと同じ) + Duration::from_millis(50), // CHANGED: 10ms -> 50ms (Autowareと同じ) ) .await; // IMU driver node (periodic_reactor) - Dummy data generator - dag.register_reactor::<_, ((i32, u32),), ((ImuMsg, u32),)>( + dag.register_reactor::<_, (DagMsg,), (DagMsg,)>( "imu_driver".into(), - move |((_a, period_id),): ((i32, u32),)| -> ((ImuMsg, u32),) { + move |(start_msg,): (DagMsg,)| -> (DagMsg,) { + let (_a, period_id) = unpack_dag_msg(start_msg); let mut node = MCSNode::new(); let mut count_guard = IMU_CSV_COUNT.lock(&mut node); let count = *count_guard; let data = unsafe { IMU_CSV_DATA.as_ref() }; - + let imu_msg = if let Some(csv_data) = data { if csv_data.is_empty() { let mut parser = TamagawaImuParser::new("imu_link"); @@ -210,7 +244,7 @@ pub async fn run() { .parse_binary_data(&static_dummy_data, awkernel_timestamp) .unwrap_or_default() }; - + *count_guard += 1; if *count_guard >= 5700 { *count_guard = 0; @@ -221,11 +255,12 @@ pub async fn run() { if LOG_ENABLE { log::debug!( "IMU data in imu_driver_node,num={}, timestamp={}", - count, imu_msg.header.timestamp + count, + imu_msg.header.timestamp ); } - ((imu_msg, period_id),) + (pack_dag_msg(imu_msg, period_id),) }, vec![Cow::from("start_imu")], vec![Cow::from("imu_data")], @@ -234,9 +269,10 @@ pub async fn run() { .await; // Vehicle Velocity Converter node - VelocityReport to TwistWithCovarianceStamped converter - dag.register_reactor::<_, ((i32, u32),), ((TwistWithCovarianceStamped, u32),)>( + dag.register_reactor::<_, (DagMsg,), (DagMsg,)>( "vehicle_velocity_converter".into(), - move |((_b, period_id),): ((i32, u32),)| -> ((TwistWithCovarianceStamped, u32),) { + move |(start_msg,): (DagMsg,)| -> (DagMsg,) { + let (_b, period_id) = unpack_dag_msg(start_msg); let converter = VehicleVelocityConverter::default(); let mut node = MCSNode::new(); @@ -275,7 +311,7 @@ pub async fn run() { ); } - ((twist_msg, period_id),) + (pack_dag_msg(twist_msg, period_id),) }, vec![Cow::from("start_vel")], // Subscribe to start_vel topic vec![Cow::from("velocity_twist")], // Publish to twist_with_covariance topic @@ -284,17 +320,17 @@ pub async fn run() { .await; //Imu Corrector - dag.register_reactor::<_, ((ImuMsg, u32),), ((ImuWithCovariance, u32),)>( + dag.register_reactor::<_, (DagMsg,), (DagMsg,)>( "imu_corrector".into(), - |((imu_msg, period_id),): ((ImuMsg, u32),)| -> ((ImuWithCovariance, u32),) { - + |(imu_msg,): (DagMsg,)| -> (DagMsg,) { + let (imu_msg, period_id) = unpack_dag_msg(imu_msg); let corrector = ImuCorrector::new(); // Use the enhanced corrector that outputs ImuWithCovariance let corrected = corrector.correct_imu_with_covariance(&imu_msg, None); // if LOG_ENABLE { // log::debug!("IMU corrected in imu_corrector node with covariance"); // } - ((corrected, period_id),) + (pack_dag_msg(corrected, period_id),) }, vec![Cow::from("imu_data")], vec![Cow::from("corrected_imu_data")], @@ -303,9 +339,11 @@ pub async fn run() { .await; // Gyro Odometer node - Simplified single processing step - dag.register_reactor::<_, ((ImuWithCovariance, u32), (TwistWithCovarianceStamped, u32)), ((TwistWithCovarianceStamped, u32),)>( + dag.register_reactor::<_, (DagMsg, DagMsg), (DagMsg,)>( "gyro_odometer".into(), - |((imu_with_cov, period_imu), (vehicle_twist, _period_twist)): ((ImuWithCovariance, u32), (TwistWithCovarianceStamped, u32))| -> ((TwistWithCovarianceStamped, u32),) { + |(imu_msg, vehicle_msg): (DagMsg, DagMsg)| -> (DagMsg,) { + let (imu_with_cov, period_imu) = unpack_dag_msg(imu_msg); + let (vehicle_twist, _period_twist) = unpack_dag_msg(vehicle_msg); let current_timestamp = imu_with_cov.header.timestamp; let current_time = get_awkernel_uptime_timestamp(); @@ -313,7 +351,7 @@ pub async fn run() { let gyro_odometer = match gyro_odometer::get_or_initialize() { Ok(core) => core, Err(_) => { - return ((reactor_helpers::create_empty_twist(current_timestamp), period_imu),); + return (pack_dag_msg(reactor_helpers::create_empty_twist(current_timestamp), period_imu),); } }; @@ -323,8 +361,8 @@ pub async fn run() { // Process once with current time and return result match gyro_odometer.process_and_get_result(current_time) { - Some(result) => ((gyro_odometer.process_result(result), period_imu),), - None => ((reactor_helpers::create_empty_twist(current_timestamp), period_imu),) + Some(result) => (pack_dag_msg(gyro_odometer.process_result(result), period_imu),), + None => (pack_dag_msg(reactor_helpers::create_empty_twist(current_timestamp), period_imu),) } }, vec![Cow::from("corrected_imu_data"),Cow::from("velocity_twist")], @@ -334,27 +372,28 @@ pub async fn run() { .await; // Pose dummy data generator reactor - dag.register_reactor::<_, ((i32, u32),), ((Pose, u32),)>( + dag.register_reactor::<_, (DagMsg,), (DagMsg,)>( "pose_dummy_generator".into(), - move |((_counter, period_id),): ((i32, u32),)| -> ((Pose, u32),) { + move |(start_msg,): (DagMsg,)| -> (DagMsg,) { + let (_counter, period_id) = unpack_dag_msg(start_msg); // Generate dummy pose data that moves in a circle // let time = counter as f64 * 0.1; // Time progression // let radius = 10.0; // Circle radius // let angular_velocity = 0.5; // rad/s - + // aip_x1_description/config/sensors_calibration.yaml // if needed, comment out and use fixed values below // let x = 0.86419; // let y = 0.0; // let z = 2.18096; // let yaw = angular_velocity * time; - // for initial pose + // for initial pose let x = 0.0; let y = 0.0; let z = 0.0; - + let pose = Pose { - position: Point3D { x,y,z}, + position: Point3D { x, y, z }, orientation: Quaternion { x: 0.0, y: 0.0, @@ -362,13 +401,13 @@ pub async fn run() { w: 1.0, }, }; - + // if LOG_ENABLE { // log::debug!("Generated dummy pose: x={:.3}, y={:.3}, yaw={:.3}, counter={}", // pose.position.x, pose.position.y, yaw, counter); // } - - ((pose, period_id),) + + (pack_dag_msg(pose, period_id),) }, vec![Cow::from("start_pose")], vec![Cow::from("dummy_pose")], @@ -378,16 +417,18 @@ pub async fn run() { // EKF Localizer reactor - combines pose and twist data // MODIFIED: 手動積分(integrated_pose)を廃止し、EKFの内部状態から直接ポーズを取得するように変更 - dag.register_reactor::<_, ((Pose, u32), (TwistWithCovarianceStamped, u32)), ((Pose, u32), (EKFOdometry, u32))>( + dag.register_reactor::<_, (DagMsg, DagMsg), (DagMsg, DagMsg)>( "ekf_localizer".into(), - |((pose, period_pose), (twist, _period_twist)): ((Pose, u32), (TwistWithCovarianceStamped, u32))| -> ((Pose, u32), (EKFOdometry, u32)) { + |(pose_msg, twist_msg): (DagMsg, DagMsg)| -> (DagMsg, DagMsg) { + let (pose, period_pose) = unpack_dag_msg(pose_msg); + let (twist, _period_twist) = unpack_dag_msg(twist_msg); // Initialize EKF Localizer if not already done if get_ekf_localizer().is_none() { if let Err(e) = initialize_ekf_localizer() { // if LOG_ENABLE { // log::error!("Failed to initialize EKF Localizer: {}", e); // } - return ((pose, period_pose), (EKFOdometry { + return (pack_dag_msg(pose, period_pose), pack_dag_msg(EKFOdometry { header: imu_driver::Header { frame_id: "map", timestamp: twist.header.timestamp, @@ -525,7 +566,7 @@ pub async fn run() { // COMMENTED OUT: 手動積分のポーズを返していた // (integrated_pose, odometry) // MODIFIED: EKFの推定ポーズを返す - ((ekf_pose, period_pose), (odometry, period_pose)) + (pack_dag_msg(ekf_pose, period_pose), pack_dag_msg(odometry, period_pose)) }, vec![Cow::from("dummy_pose"), Cow::from("twist_with_covariance")], vec![Cow::from("estimated_pose"), Cow::from("ekf_odometry")], @@ -534,9 +575,11 @@ pub async fn run() { .await; // Sink reactor for EKF Localizer output with TCP sending - dag.register_sink_reactor::<_, ((Pose, u32), (EKFOdometry, u32))>( + dag.register_sink_reactor::<_, (DagMsg, DagMsg)>( "ekf_sink".into(), - move|((_pose, _period_pose), (ekf_odom, _period_odom)): ((Pose, u32), (EKFOdometry, u32))| { + move |(pose_msg, odom_msg): (DagMsg, DagMsg)| { + let (_pose, _period_pose) = unpack_dag_msg(pose_msg); + let (ekf_odom, _period_odom) = unpack_dag_msg(odom_msg); // log::info!("=== EKF Sink Reactor 実行 ==="); // if LOG_ENABLE { @@ -621,32 +664,36 @@ pub async fn run() { log::info!("インターフェースID: {}", INTERFACE_ID); log::info!("インターフェースIP: {}", INTERFACE_ADDR); log::info!("宛先IP: {}", UDP_TCP_DST_ADDR); - // + // awkernel_lib::net::add_ipv4_addr(INTERFACE_ID, INTERFACE_ADDR, 24); - log::info!("IPv4アドレス設定完了: {} をインターフェース {} に追加", INTERFACE_ADDR, INTERFACE_ID); + log::info!( + "IPv4アドレス設定完了: {} をインターフェース {} に追加", + INTERFACE_ADDR, + INTERFACE_ID + ); // ネットワークスタックの初期化を待つ log::info!("ネットワークスタック初期化のため待機中..."); awkernel_async_lib::sleep(Duration::from_secs(2)).await; - + // リアクターAPIに干渉しない周期UDP送信タスクを開始 log::info!("周期UDP送信タスクを開始します"); start_periodic_udp_sender().await; - + // または、設定可能な周期で開始する場合 // start_configurable_udp_sender(2).await; // 2秒間隔 - + // JSONデータが準備されるまで待機(最大3秒) log::info!("JSONデータの準備を待機中..."); let mut wait_count = 0; const MAX_WAIT_COUNT: u32 = 3; - + while !JSON_DATA_READY.load(Ordering::Relaxed) && wait_count < MAX_WAIT_COUNT { // log::info!("JSONデータ待機中... ({}/{})", wait_count + 1, MAX_WAIT_COUNT); awkernel_async_lib::sleep(Duration::from_secs(1)).await; wait_count += 1; } - + if JSON_DATA_READY.load(Ordering::Relaxed) { // log::info!("JSONデータが準備されました。周期UDP送信タスクが動作中です"); // 周期UDP送信タスクは既に動作中なので、ここでは何もしない @@ -765,7 +812,8 @@ where let mut header_skipped = false; loop { - let (result, in_read, _out_written, num_fields) = reader.read_record(input, &mut output, &mut ends); + let (result, in_read, _out_written, num_fields) = + reader.read_record(input, &mut output, &mut ends); input = &input[in_read..]; if matches!(result, ReadRecordResult::OutputFull) { @@ -818,7 +866,9 @@ fn parse_u64(field: &str) -> Result { if trimmed.is_empty() { return Ok(0); } - trimmed.parse::().map_err(|_| "u64パースに失敗しました") + trimmed + .parse::() + .map_err(|_| "u64パースに失敗しました") } fn parse_f64(field: &str) -> Result { @@ -826,39 +876,41 @@ fn parse_f64(field: &str) -> Result { if trimmed.is_empty() { return Ok(0.0); } - trimmed.parse::().map_err(|_| "f64パースに失敗しました") + trimmed + .parse::() + .map_err(|_| "f64パースに失敗しました") } // fn find_first_moving_velocity_index() -> usize { - // const EPS: f64 = 1.0e-6; - // let data = unsafe { VELOCITY_CSV_DATA.as_ref() }; - // if let Some(rows) = data { - // for (idx, row) in rows.iter().enumerate() { - // if row.longitudinal_velocity.abs() > EPS || row.lateral_velocity.abs() > EPS { - // return idx; - // } - // } - // } - // 0 +// const EPS: f64 = 1.0e-6; +// let data = unsafe { VELOCITY_CSV_DATA.as_ref() }; +// if let Some(rows) = data { +// for (idx, row) in rows.iter().enumerate() { +// if row.longitudinal_velocity.abs() > EPS || row.lateral_velocity.abs() > EPS { +// return idx; // } -// +// } +// } +// 0 +// } +// // fn find_first_active_imu_index() -> usize { - // const EPS: f64 = 1.0e-6; - // let data = unsafe { IMU_CSV_DATA.as_ref() }; - // if let Some(rows) = data { - // for (idx, row) in rows.iter().enumerate() { - // if row.angular_velocity.x.abs() > EPS - // || row.angular_velocity.y.abs() > EPS - // || row.angular_velocity.z.abs() > EPS - // || row.linear_acceleration.x.abs() > EPS - // || row.linear_acceleration.y.abs() > EPS - // || row.linear_acceleration.z.abs() > EPS - // { - // return idx; - // } - // } - // } - // 0 +// const EPS: f64 = 1.0e-6; +// let data = unsafe { IMU_CSV_DATA.as_ref() }; +// if let Some(rows) = data { +// for (idx, row) in rows.iter().enumerate() { +// if row.angular_velocity.x.abs() > EPS +// || row.angular_velocity.y.abs() > EPS +// || row.angular_velocity.z.abs() > EPS +// || row.linear_acceleration.x.abs() > EPS +// || row.linear_acceleration.y.abs() > EPS +// || row.linear_acceleration.z.abs() > EPS +// { +// return idx; +// } +// } +// } +// 0 // } // Awkernel起動時間からのタイムスタンプを取得する関数 @@ -877,7 +929,7 @@ fn get_awkernel_uptime_timestamp() -> u64 { // リアクターAPIに干渉しないUDP送信タスク(一定周期実行) pub async fn start_periodic_udp_sender() { // log::info!("=== 周期UDP送信タスク開始 ==="); - + // 独立したタスクとして実行 awkernel_async_lib::spawn( "periodic_udp_sender".into(), @@ -885,20 +937,20 @@ pub async fn start_periodic_udp_sender() { awkernel_async_lib::scheduler::SchedulerType::PrioritizedFIFO(0), ) .await; - + // log::info!("周期UDP送信タスクを開始しました"); } // 周期UDP送信タスクの実装 async fn periodic_udp_sender_task() { // log::info!("周期UDP送信タスク: 開始"); - + // UDPソケットを作成(一度だけ) let socket_result = awkernel_async_lib::net::udp::UdpSocket::bind_on_interface( INTERFACE_ID, &Default::default(), ); - + let mut socket = match socket_result { Ok(socket) => { // log::info!("周期UDP送信タスク: UDPソケット作成成功"); @@ -909,10 +961,10 @@ async fn periodic_udp_sender_task() { return; } }; - + let dst_addr = IpAddr::new_v4(UDP_TCP_DST_ADDR); let mut counter = 0; - + // 無限ループで一定周期実行 loop { // JSONデータの準備チェック @@ -921,29 +973,36 @@ async fn periodic_udp_sender_task() { awkernel_async_lib::sleep(Duration::from_secs(1)).await; continue; } - + // 安全にJSONデータを取得 - let json_data = unsafe { - LATEST_JSON_DATA.as_ref().map(|s| s.clone()) - }; - + let json_data = unsafe { LATEST_JSON_DATA.as_ref().map(|s| s.clone()) }; + if let Some(data) = json_data { // UDP送信を実行 match socket.send(data.as_bytes(), &dst_addr, UDP_DST_PORT).await { Ok(_) => { counter += 1; - log::info!("周期UDP送信タスク: 送信成功 #{} ({} bytes)", counter, data.len()); - + log::info!( + "周期UDP送信タスク: 送信成功 #{} ({} bytes)", + counter, + data.len() + ); + // レスポンス受信(オプション、タイムアウト付き) let mut buf = [0u8; 1024]; - if let Some(Ok((n, src_addr, src_port))) = - awkernel_async_lib::timeout( - Duration::from_millis(100), // 短いタイムアウト - socket.recv(&mut buf) - ).await { + if let Some(Ok((n, src_addr, src_port))) = awkernel_async_lib::timeout( + Duration::from_millis(100), // 短いタイムアウト + socket.recv(&mut buf), + ) + .await + { if let Ok(response) = core::str::from_utf8(&buf[..n]) { - log::debug!("周期UDP送信タスク: レスポンス受信: {}:{} - {}", - src_addr.get_addr(), src_port, response); + log::debug!( + "周期UDP送信タスク: レスポンス受信: {}:{} - {}", + src_addr.get_addr(), + src_port, + response + ); } } } @@ -954,7 +1013,7 @@ async fn periodic_udp_sender_task() { } else { log::warn!("周期UDP送信タスク: JSONデータが取得できませんでした"); } - + // 一定周期で待機(例: 2秒間隔 - DAGの実行周期と衝突を避けるため) awkernel_async_lib::sleep(Duration::from_millis(5)).await; } @@ -963,7 +1022,7 @@ async fn periodic_udp_sender_task() { // リアクターAPIに干渉しないUDP送信タスク(設定可能な周期) // pub async fn start_configurable_udp_sender(interval_sec: u64) { // log::info!("=== 設定可能周期UDP送信タスク開始 (間隔: {}秒) ===", interval_sec); - + // // 独立したタスクとして実行 // awkernel_async_lib::spawn( // "configurable_udp_sender".into(), @@ -971,20 +1030,20 @@ async fn periodic_udp_sender_task() { // awkernel_async_lib::scheduler::SchedulerType::GEDF(5), // ) // .await; - + // log::info!("設定可能周期UDP送信タスクを開始しました"); // } // 設定可能な周期UDP送信タスクの実装 // async fn configurable_udp_sender_task(interval_sec: u64) { // log::info!("設定可能周期UDP送信タスク: 開始 (間隔: {}秒)", interval_sec); - + // // UDPソケットを作成 // let socket_result = awkernel_async_lib::net::udp::UdpSocket::bind_on_interface( // INTERFACE_ID, // &Default::default(), // ); - + // let mut socket = match socket_result { // Ok(socket) => { // log::info!("設定可能周期UDP送信タスク: UDPソケット作成成功"); @@ -995,10 +1054,10 @@ async fn periodic_udp_sender_task() { // return; // } // }; - + // let dst_addr = IpAddr::new_v4(UDP_TCP_DST_ADDR); // let mut counter = 0; - + // loop { // // ネットワーク初期化チェック // if !NETWORK_INITIALIZED.load(Ordering::Relaxed) { @@ -1006,25 +1065,25 @@ async fn periodic_udp_sender_task() { // awkernel_async_lib::sleep(Duration::from_secs(1)).await; // continue; // } - + // // JSONデータの準備チェック // if !JSON_DATA_READY.load(Ordering::Relaxed) { // log::debug!("設定可能周期UDP送信タスク: JSONデータ未準備、待機中..."); // awkernel_async_lib::sleep(Duration::from_secs(1)).await; // continue; // } - + // // 安全にJSONデータを取得 // let json_data = unsafe { // LATEST_JSON_DATA.as_ref().map(|s| s.clone()) // }; - + // if let Some(data) = json_data { // // UDP送信を実行 // match socket.send(data.as_bytes(), &dst_addr, UDP_DST_PORT).await { // Ok(_) => { // counter += 1; -// log::info!("設定可能周期UDP送信タスク: 送信成功 #{} ({} bytes, 間隔: {}秒)", +// log::info!("設定可能周期UDP送信タスク: 送信成功 #{} ({} bytes, 間隔: {}秒)", // counter, data.len(), interval_sec); // } // Err(e) => { @@ -1034,7 +1093,7 @@ async fn periodic_udp_sender_task() { // } else { // log::warn!("設定可能周期UDP送信タスク: JSONデータが取得できませんでした"); // } - + // // 設定された周期で待機 // awkernel_async_lib::sleep(Duration::from_secs(interval_sec)).await; // } @@ -1066,11 +1125,11 @@ fn get_transform_safely(from_frame: &str, to_frame: &str) -> Result Result<(), &'static str> { let params = EKFParameters::default(); let ekf = EKFModule::new(params); - + // Allocate on heap and store pointer let boxed_ekf = alloc::boxed::Box::new(ekf); let ptr = alloc::boxed::Box::into_raw(boxed_ekf); - + // Try to store the pointer atomically let old_ptr = EKF_LOCALIZER.compare_exchange( null_mut(), @@ -1078,7 +1137,7 @@ fn initialize_ekf_localizer() -> Result<(), &'static str> { AtomicOrdering::Acquire, AtomicOrdering::Relaxed, ); - + match old_ptr { Ok(_) => Ok(()), Err(_) => { @@ -1099,7 +1158,7 @@ fn initialize_ekf_localizer() -> Result<(), &'static str> { // let cosy_cosp = 1.0 - 2.0 * (q.y * q.y + q.z * q.z); // atan2(siny_cosp, cosy_cosp) // } -// +// // fn yaw_to_quaternion(yaw: f64) -> Quaternion { // let half = yaw * 0.5; // Quaternion { @@ -1118,4 +1177,4 @@ fn get_ekf_localizer() -> Option<&'static mut EKFModule> { } else { unsafe { Some(&mut *ptr) } } -} \ No newline at end of file +} diff --git a/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs b/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs index b529630b8..7ef0aba5b 100644 --- a/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs +++ b/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs @@ -14,7 +14,7 @@ #![no_std] -use imu_driver::{Vector3, Header}; +use imu_driver::{Header, Vector3}; /// 速度レポートメッセージの構造体 #[derive(Debug, Clone)] @@ -53,10 +53,10 @@ pub struct Odometry { /// 車両速度変換器の構造体 pub struct VehicleVelocityConverter { - frame_id: &'static str, // → frame_id: base_link - stddev_vx: f64, // → velocity_stddev_xx: 0.2 - stddev_wz: f64, // → angular_velocity_stddev_zz: 0.1 - speed_scale_factor: f64, // → speed_scale_factor: 1.0 + frame_id: &'static str, // → frame_id: base_link + stddev_vx: f64, // → velocity_stddev_xx: 0.2 + stddev_wz: f64, // → angular_velocity_stddev_zz: 0.1 + speed_scale_factor: f64, // → speed_scale_factor: 1.0 } impl VehicleVelocityConverter { @@ -123,21 +123,21 @@ impl VehicleVelocityConverter { /// 共分散行列を作成 fn create_covariance_matrix(&self) -> [f64; 36] { let mut covariance = [0.0; 36]; - + // 線形速度の分散 (x方向) covariance[0 + 0 * 6] = self.stddev_vx * self.stddev_vx; - + // その他の線形速度成分は大きな値(低い信頼度)を設定 covariance[1 + 1 * 6] = 10000.0; // y方向 covariance[2 + 2 * 6] = 10000.0; // z方向 - + // 角速度成分は大きな値(低い信頼度)を設定 covariance[3 + 3 * 6] = 10000.0; // x方向 covariance[4 + 4 * 6] = 10000.0; // y方向 - + // 角速度の分散 (z方向) covariance[5 + 5 * 6] = self.stddev_wz * self.stddev_wz; - + covariance } @@ -172,8 +172,16 @@ pub mod reactor_helpers { }, twist: TwistWithCovariance { twist: Twist { - linear: Vector3 { x: 0.0, y: 0.0, z: 0.0 }, - angular: Vector3 { x: 0.0, y: 0.0, z: 0.0 }, + linear: Vector3 { + x: 0.0, + y: 0.0, + z: 0.0, + }, + angular: Vector3 { + x: 0.0, + y: 0.0, + z: 0.0, + }, }, covariance: [0.0; 36], }, @@ -187,12 +195,7 @@ mod tests { #[test] fn test_vehicle_velocity_converter_creation() { - let converter = VehicleVelocityConverter::new( - "base_link", - 0.1, - 0.1, - 1.0, - ); + let converter = VehicleVelocityConverter::new("base_link", 0.1, 0.1, 1.0); assert_eq!(converter.get_frame_id(), "base_link"); assert_eq!(converter.get_stddev_vx(), 0.1); @@ -211,12 +214,7 @@ mod tests { #[test] fn test_convert_velocity_report_success() { - let converter = VehicleVelocityConverter::new( - "base_link", - 0.1, - 0.1, - 1.0, - ); + let converter = VehicleVelocityConverter::new("base_link", 0.1, 0.1, 1.0); let velocity_report = VelocityReport { header: Header { @@ -241,12 +239,7 @@ mod tests { #[test] fn test_convert_velocity_report_wrong_frame_id() { - let converter = VehicleVelocityConverter::new( - "base_link", - 0.1, - 0.1, - 1.0, - ); + let converter = VehicleVelocityConverter::new("base_link", 0.1, 0.1, 1.0); let velocity_report = VelocityReport { header: Header { @@ -279,12 +272,7 @@ mod tests { #[test] fn test_from_params_array_with_defaults() { - let converter = VehicleVelocityConverter::from_params_array( - None, - None, - None, - "base_link", - ); + let converter = VehicleVelocityConverter::from_params_array(None, None, None, "base_link"); assert_eq!(converter.get_stddev_vx(), 0.1); assert_eq!(converter.get_stddev_wz(), 0.1); diff --git a/applications/tests/test_dag/src/lib.rs b/applications/tests/test_dag/src/lib.rs index 4b17b9746..f36b830d6 100644 --- a/applications/tests/test_dag/src/lib.rs +++ b/applications/tests/test_dag/src/lib.rs @@ -1,12 +1,12 @@ #![no_std] extern crate alloc; -use alloc::{borrow::Cow, vec, sync::Arc}; +use alloc::{borrow::Cow, sync::Arc, vec}; use awkernel_async_lib::dag::{create_dag, finish_create_dags}; use awkernel_async_lib::scheduler::SchedulerType; +use awkernel_async_lib::task::perf::get_period_count; use awkernel_lib::delay::wait_microsec; use core::time::Duration; -use awkernel_async_lib::task::perf::get_period_count; const LOG_ENABLE: bool = false; const DATA_SIZE: usize = 128; @@ -29,7 +29,12 @@ pub async fn run() { let data: Arc<[u8; DATA_SIZE]> = Arc::new([0; DATA_SIZE]); let period_id = get_period_count(dag_id as usize) as u32; if LOG_ENABLE { - log::debug!("Sending data[0]={}, period_id={}, size={} in reactor_source_node", data[0], period_id, DATA_SIZE); + log::debug!( + "Sending data[0]={}, period_id={}, size={} in reactor_source_node", + data[0], + period_id, + DATA_SIZE + ); } ((data, period_id),) }, @@ -58,7 +63,12 @@ pub async fn run() { "reactor_node2".into(), |((data, period),): ((Arc<[u8; DATA_SIZE]>, u32),)| -> ((Arc<[u8; DATA_SIZE]>, u32),) { if LOG_ENABLE { - log::debug!("Processing data[0]={}, period={}, size={} in reactor_node2", data[0], period, DATA_SIZE); + log::debug!( + "Processing data[0]={}, period={}, size={} in reactor_node2", + data[0], + period, + DATA_SIZE + ); } ((data, period),) }, @@ -72,7 +82,12 @@ pub async fn run() { "reactor_node3".into(), |((data, period),): ((Arc<[u8; DATA_SIZE]>, u32),)| -> ((Arc<[u8; DATA_SIZE]>, u32),) { if LOG_ENABLE { - log::debug!("Processing data[0]={}, period={}, size={} in reactor_node3", data[0], period, DATA_SIZE); + log::debug!( + "Processing data[0]={}, period={}, size={} in reactor_node3", + data[0], + period, + DATA_SIZE + ); } ((data, period),) }, diff --git a/awkernel_async_lib/Cargo.toml b/awkernel_async_lib/Cargo.toml index 1abcf8e9c..61fe6104d 100644 --- a/awkernel_async_lib/Cargo.toml +++ b/awkernel_async_lib/Cargo.toml @@ -40,8 +40,10 @@ features = ["awkernel"] [features] default = [] +x86 = [] std = ["awkernel_lib/std", "no_preempt"] no_preempt = [] spinlock = ["awkernel_lib/spinlock"] clippy = [] perf = [] +relax-get-period = [] diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index 533b6bdab..47a6bf2f3 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -54,17 +54,27 @@ mod visit; mod performance; use crate::{ - Attribute, MultipleReceiver, MultipleSender, VectorToPublishers, VectorToSubscribers, dag::{ - self, graph::{ - NodeIndex, algo::{connected_components, is_cyclic_directed}, direction::Direction - }, visit::{EdgeRef, IntoNodeReferences, NodeRef} - }, - scheduler::SchedulerType, + self, + graph::{ + algo::{connected_components, is_cyclic_directed}, + direction::Direction, + NodeIndex, + }, + visit::{EdgeRef, IntoNodeReferences, NodeRef}, + }, + scheduler::SchedulerType, task::{ - DagInfo, perf::{NodeRecord, get_period_count, get_pub_count, get_sink_count, get_sub_count, increment_period_count, increment_pub_count, increment_sink_count, increment_sub_count, node_finish, node_start, publish_timestamp_at, subscribe_timestamp_at, update_fin_recv_outer_timestamp_at, update_pre_send_outer_timestamp_at}, - }, - time_interval::interval + perf::{ + get_period_count, get_pub_count, get_sink_count, get_sub_count, increment_period_count, + increment_pub_count, increment_sink_count, increment_sub_count, node_finish, + node_start, publish_timestamp_at, subscribe_timestamp_at, + update_fin_recv_outer_timestamp_at, update_pre_send_outer_timestamp_at, NodeRecord, + }, + DagInfo, + }, + time_interval::interval, + Attribute, MultipleReceiver, MultipleSender, VectorToPublishers, VectorToSubscribers, }; use alloc::{ borrow::Cow, @@ -74,8 +84,8 @@ use alloc::{ vec::Vec, }; use awkernel_lib::sync::mutex::{MCSNode, Mutex}; -use core::{future::Future, pin::Pin, time::Duration}; use core::sync::atomic::Ordering; +use core::{future::Future, pin::Pin, time::Duration}; #[cfg(feature = "perf")] use performance::ResponseInfo; @@ -126,54 +136,111 @@ pub trait GetPeriod { fn get_period(&self) -> u32; } +#[cfg(not(feature = "relax-get-period"))] +pub trait DagSubscriberItem: TupleSize + GetPeriod + Send {} + +#[cfg(not(feature = "relax-get-period"))] +impl DagSubscriberItem for T where T: TupleSize + GetPeriod + Send {} + +#[cfg(feature = "relax-get-period")] +pub trait DagSubscriberItem: TupleSize + Send {} + +#[cfg(feature = "relax-get-period")] +impl DagSubscriberItem for T where T: TupleSize + Send {} + +#[cfg(not(feature = "relax-get-period"))] impl GetPeriod for ((V, u32),) { fn get_period(&self) -> u32 { self.0 .1 } } +#[cfg(not(feature = "relax-get-period"))] impl GetPeriod for ((V1, u32), (V2, u32)) { fn get_period(&self) -> u32 { self.1 .1 } } +#[cfg(not(feature = "relax-get-period"))] impl GetPeriod for ((V1, u32), (V2, u32), (V3, u32)) { fn get_period(&self) -> u32 { self.2 .1 } } +#[cfg(not(feature = "relax-get-period"))] impl GetPeriod for ((V1, u32), (V2, u32), (V3, u32), (V4, u32)) { fn get_period(&self) -> u32 { self.3 .1 } } +#[cfg(not(feature = "relax-get-period"))] impl GetPeriod for ((V1, u32), (V2, u32), (V3, u32), (V4, u32), (V5, u32)) { fn get_period(&self) -> u32 { self.4 .1 } } -impl GetPeriod for ((V1, u32), (V2, u32), (V3, u32), (V4, u32), (V5, u32), (V6, u32)) { +#[cfg(not(feature = "relax-get-period"))] +impl GetPeriod + for ( + (V1, u32), + (V2, u32), + (V3, u32), + (V4, u32), + (V5, u32), + (V6, u32), + ) +{ fn get_period(&self) -> u32 { self.5 .1 } } -impl GetPeriod for ((V1, u32), (V2, u32), (V3, u32), (V4, u32), (V5, u32), (V6, u32), (V7, u32)) { +#[cfg(not(feature = "relax-get-period"))] +impl GetPeriod + for ( + (V1, u32), + (V2, u32), + (V3, u32), + (V4, u32), + (V5, u32), + (V6, u32), + (V7, u32), + ) +{ fn get_period(&self) -> u32 { self.6 .1 } } -impl GetPeriod for ((V1, u32), (V2, u32), (V3, u32), (V4, u32), (V5, u32), (V6, u32), (V7, u32), (V8, u32)) { +#[cfg(not(feature = "relax-get-period"))] +impl GetPeriod + for ( + (V1, u32), + (V2, u32), + (V3, u32), + (V4, u32), + (V5, u32), + (V6, u32), + (V7, u32), + (V8, u32), + ) +{ fn get_period(&self) -> u32 { self.7 .1 } } +#[cfg(feature = "relax-get-period")] +impl GetPeriod for T { + fn get_period(&self) -> u32 { + 0 + } +} + /// Convenience helper to extract period from a subscriber tuple by reference. pub fn get_period(args: &T) -> u32 { args.get_period() @@ -365,8 +432,8 @@ impl Dag { Ret: VectorToPublishers, Ret::Publishers: Send, Args::Subscribers: Send, - ::Item: TupleSize + GetPeriod + Send, - ::Item: TupleSize + Send, + ::Item: DagSubscriberItem, + ::Item: TupleSize + Send, { let node_idx = self.add_node_with_topic_edges(&subscribe_topic_names, &publish_topic_names); self.check_subscribe_mismatch::(&subscribe_topic_names, node_idx); @@ -458,8 +525,8 @@ impl Dag { ) where F: Fn(::Item) + Send + 'static, Args: VectorToSubscribers, - Args::Subscribers: Send, - ::Item: TupleSize + GetPeriod + Send, + Args::Subscribers: Send, + ::Item: DagSubscriberItem, { let node_idx = self.add_node_with_topic_edges(&subscribe_topic_names, &Vec::new()); self.set_relative_deadline(node_idx, relative_deadline); @@ -1027,8 +1094,8 @@ where Ret: VectorToPublishers, Ret::Publishers: Send, Args::Subscribers: Send, - ::Item: TupleSize + GetPeriod + Send, - ::Item: TupleSize + Send, + ::Item: DagSubscriberItem, + ::Item: TupleSize + Send, { let future = async move { let publishers = ::create_publishers( @@ -1042,33 +1109,40 @@ where loop { let args: <::Subscribers as MultipleReceiver>::Item = subscribers.recv_all().await; - // [end] pubsub communication latency - let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - let index_subscribe = get_period(&args).clone() as usize; - let count_st = get_period(&args); - subscribe_timestamp_at(count_st as usize, end, 1, dag_info.node_id.clone()); - - // period count from message to TaskInfo - let cpu_id = awkernel_lib::cpu::cpu_id(); - if let Some(task_id) = crate::task::get_current_task(cpu_id) { - crate::task::set_task_period(task_id, Some(count_st)); + + #[cfg(not(feature = "relax-get-period"))] + { + // [end] pubsub communication latency + let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + let count_st = get_period(&args); + subscribe_timestamp_at(count_st as usize, end, 1, dag_info.node_id.clone()); + + // period count from message to TaskInfo + let cpu_id = awkernel_lib::cpu::cpu_id(); + if let Some(task_id) = crate::task::get_current_task(cpu_id) { + crate::task::set_task_period(task_id, Some(count_st)); + } + // let noderecord = NodeRecord { + // period_count: count_st, + // dag_info: DagInfo { dag_id: dag_info.dag_id.clone(), node_id: dag_info.node_id.clone() }, + // }; + // node_period_count(noderecord.clone()); + // let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + // node_start(noderecord.clone(), start); + let results = f(args); + // [start] pubsub communication latency + let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + publish_timestamp_at(count_st as usize, end, 1, dag_info.node_id.clone()); + publishers + .send_all_with_meta(results, 1, count_st as usize, dag_info.node_id) + .await; + } + + #[cfg(feature = "relax-get-period")] + { + let results = f(args); + publishers.send_all(results).await; } - // let noderecord = NodeRecord { - // period_count: count_st, - // dag_info: DagInfo { dag_id: dag_info.dag_id.clone(), node_id: dag_info.node_id.clone() }, - // }; - // node_period_count(noderecord.clone()); - // let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - // node_start(noderecord.clone(), start); - let results = f(args); - - // node_finish(noderecord.clone(), end); - // let index_publish = get_period(&args) as usize; - - // [start] pubsub communication latency - let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - publish_timestamp_at(count_st as usize, end,1, dag_info.node_id.clone()); - publishers.send_all_with_meta(results, 1, count_st as usize, dag_info.node_id).await; } }; @@ -1110,37 +1184,46 @@ where interval.tick().await; loop { - let index = get_period_count(dag_info.dag_id.clone() as usize) as usize; - let cpu_id = awkernel_lib::cpu::cpu_id(); - if let Some(task_id) = crate::task::get_current_task(cpu_id) { - crate::task::set_task_period(task_id, Some(index as u32)); - } - // [node] per node - // let noderecord = NodeRecord { - // period_count: index as u32, - // dag_info: DagInfo { dag_id: dag_info.dag_id.clone(), node_id: dag_info.node_id.clone() }, - // }; - // node_period_count(noderecord.clone()); - // let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - // node_start(noderecord.clone(), start); - if index != 0 { - let release_time = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - update_pre_send_outer_timestamp_at(index, release_time, dag_info.dag_id.clone()); + #[cfg(not(feature = "relax-get-period"))] + { + let index = get_period_count(dag_info.dag_id.clone() as usize) as usize; + let cpu_id = awkernel_lib::cpu::cpu_id(); + if let Some(task_id) = crate::task::get_current_task(cpu_id) { + crate::task::set_task_period(task_id, Some(index as u32)); + } + // [node] per node + // let noderecord = NodeRecord { + // period_count: index as u32, + // dag_info: DagInfo { dag_id: dag_info.dag_id.clone(), node_id: dag_info.node_id.clone() }, + // }; + // node_period_count(noderecord.clone()); + // let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + // node_start(noderecord.clone(), start); + if index != 0 { + let release_time = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + update_pre_send_outer_timestamp_at( + index, + release_time, + dag_info.dag_id.clone(), + ); + } + let results = f(); + // [start] pubsub communication latency + let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + publish_timestamp_at(index, end, 0, dag_info.node_id); + publishers + .send_all_with_meta(results, 0, index, dag_info.node_id) + .await; + + increment_period_count(dag_info.dag_id.clone() as usize); + increment_pub_count(0); } - let results = f(); - // let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - // node_finish(noderecord.clone(), end); - - // let index_publish = get_pub_count(0) as usize; - - // [start] pubsub communication latency - let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - publish_timestamp_at(index, end, 0, dag_info.node_id); - publishers.send_all_with_meta(results, 0, index, dag_info.node_id).await; - - increment_period_count(dag_info.dag_id.clone() as usize); - increment_pub_count(0); + #[cfg(feature = "relax-get-period")] + { + let results = f(); + publishers.send_all(results).await; + } #[cfg(feature = "perf")] periodic_measure(); @@ -1168,7 +1251,7 @@ where F: Fn(::Item) + Send + 'static, Args: VectorToSubscribers, Args::Subscribers: Send, - ::Item: TupleSize + GetPeriod + Send, + ::Item: DagSubscriberItem, { let future = async move { let subscribers: ::Subscribers = @@ -1176,41 +1259,34 @@ where loop { let args: ::Item = subscribers.recv_all().await; - // [end] pubsub communication latency - let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - let index_subscribe = get_period(&args) as usize; - let count_st = get_period(&args); - subscribe_timestamp_at(count_st as usize, end, 2, dag_info.node_id.clone()); - increment_pub_count(1); - increment_sub_count(1); - increment_sub_count(2); - - // period count from message to TaskInfo - let cpu_id = awkernel_lib::cpu::cpu_id(); - if let Some(task_id) = crate::task::get_current_task(cpu_id) { - crate::task::set_task_period(task_id, Some(count_st)); - } - // [node] per node - // let noderecord = NodeRecord { - // period_count: count_st, - // dag_info: DagInfo { dag_id: dag_info.dag_id.clone(), node_id: dag_info.node_id.clone() }, - // }; - // node_period_count(noderecord.clone()); - // let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - // node_start(noderecord.clone(), start); - f(args); - // let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - // node_finish(noderecord.clone(), end); - let timenow = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - let counter = get_sink_count(dag_info.dag_id.clone() as usize) as usize; - if count_st != 0 { - // update_fin_recv_outer_timestamp_at(counter, timenow, dag_info.dag_id.clone()); - update_fin_recv_outer_timestamp_at(count_st as usize, timenow, dag_info.dag_id); + #[cfg(not(feature = "relax-get-period"))] + { + // [end] pubsub communication latency + let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + let count_st = get_period(&args); + subscribe_timestamp_at(count_st as usize, end, 2, dag_info.node_id.clone()); + increment_pub_count(1); + increment_sub_count(1); + increment_sub_count(2); + + // period count from message to TaskInfo + let cpu_id = awkernel_lib::cpu::cpu_id(); + if let Some(task_id) = crate::task::get_current_task(cpu_id) { + crate::task::set_task_period(task_id, Some(count_st)); + } + // f(args); + let timenow = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + let counter = get_sink_count(dag_info.dag_id.clone() as usize) as usize; + if count_st != 0 { + // update_fin_recv_outer_timestamp_at(counter, timenow, dag_info.dag_id.clone()); + update_fin_recv_outer_timestamp_at(count_st as usize, timenow, dag_info.dag_id); + } + increment_sink_count(dag_info.dag_id.clone() as usize); } - increment_sink_count(dag_info.dag_id.clone() as usize); + f(args); } }; crate::task::spawn_with_dag_info(reactor_name, future, sched_type, dag_info) -} \ No newline at end of file +} diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index 807c44d14..efb07ab17 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -53,8 +53,8 @@ use futures::Future; use pin_project::pin_project; use crate::task; -use crate::task::{DagInfo}; -use crate::task::perf::{PUB_COUNT,get_pub_count, publish_timestamp_at}; +use crate::task::perf::{get_pub_count, publish_timestamp_at, PUB_COUNT}; +use crate::task::DagInfo; /// Data and timestamp. #[derive(Clone)] @@ -778,10 +778,7 @@ pub trait MultipleReceiver { pub trait MultipleSender { type Item; - fn send_all(&self, item: Self::Item) -> Pin + Send + '_>> { - // default to pub_id = 1 (intermediate), index = 0, node_id = 0 - self.send_all_with_meta(item, 1, 0, 0) - } + fn send_all(&self, item: Self::Item) -> Pin + Send + '_>>; fn send_all_with_meta( &self, @@ -871,6 +868,9 @@ macro_rules! impl_async_receiver_for_tuple { impl MultipleSender for () { type Item = (); + fn send_all(&self, _item: Self::Item) -> Pin + Send + '_>> { + Box::pin(async move{}) + } fn send_all_with_meta(&self, _item: Self::Item, _pub_id: u32, _index: usize, _node_id: u32) -> Pin + Send + '_>> { Box::pin(async move{}) } @@ -891,14 +891,21 @@ macro_rules! impl_async_receiver_for_tuple { impl<$($T: Clone + Sync + Send + 'static),+> MultipleSender for ($(Publisher<$T>,)+) { type Item = ($($T,)+); + fn send_all(&self, item: Self::Item) -> Pin + Send + '_>> { + let ($($idx,)+) = self; + let ($($idx2,)+) = item; + Box::pin(async move { + $( + $idx.send($idx2).await; + )+ + }) + } + fn send_all_with_meta(&self, item: Self::Item, pub_id: u32, index: usize, node_id: u32) -> Pin + Send + '_>> { let ($($idx,)+) = self; let ($($idx2,)+) = item; Box::pin(async move { $( - // let now = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - // publish_timestamp_at(index, now, pub_id, node_id); - // $idx.send($idx2).await; $idx.send_with_meta($idx2, pub_id, index, node_id).await; )+ }) diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index 59393ea01..6eefb8118 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -466,13 +466,12 @@ fn get_next_task(execution_ensured: bool) -> Option> { #[cfg(feature = "perf")] pub mod perf { + use crate::task::{self}; use alloc::string::{String, ToString}; + use array_macro::array; use awkernel_lib::{cpu::NUM_MAX_CPU, device_tree::node}; - use core::{ptr::{read_volatile, write_volatile}}; - use crate::task::{self}; + use core::ptr::{read_volatile, write_volatile}; use core::sync::atomic::{AtomicU32, Ordering}; - use array_macro::array; - #[derive(Debug, Clone, PartialEq, Eq)] #[repr(u8)] @@ -501,7 +500,7 @@ pub mod perf { } } #[derive(Debug, Clone)] - pub struct NodeRecord{ + pub struct NodeRecord { pub period_count: u32, pub dag_info: task::DagInfo, } @@ -644,7 +643,7 @@ pub mod perf { } } - pub fn update_absolute_deadline_timestamp_at(index: usize, deadline: u64, dag_id: u32){ + pub fn update_absolute_deadline_timestamp_at(index: usize, deadline: u64, dag_id: u32) { assert!(index < MAX_LOGS, "Timestamp index out of bounds"); let mut node = MCSNode::new(); @@ -655,10 +654,9 @@ pub mod perf { if recorder[index][dag_id as usize] == 0 { recorder[index][dag_id as usize] = deadline; } - } - pub fn update_relative_deadline_timestamp_at(index: usize, deadline: u64, dag_id: u32){ + pub fn update_relative_deadline_timestamp_at(index: usize, deadline: u64, dag_id: u32) { assert!(index < MAX_LOGS, "Timestamp index out of bounds"); let mut node = MCSNode::new(); @@ -669,12 +667,14 @@ pub mod perf { if recorder[index][dag_id as usize] == 0 { recorder[index][dag_id as usize] = deadline; } - } - pub fn node_start(node:NodeRecord, start: u64){ + pub fn node_start(node: NodeRecord, start: u64) { // assert!(index < MAX_LOGS, "Node log index out of bounds"); - assert!((node.dag_info.node_id as usize) < MAX_NODES, "Node ID out of bounds"); + assert!( + (node.dag_info.node_id as usize) < MAX_NODES, + "Node ID out of bounds" + ); let mut mcs_node = MCSNode::new(); let mut recorder_opt = NODE_START.lock(&mut mcs_node); @@ -686,9 +686,12 @@ pub mod perf { } } - pub fn node_finish(node:NodeRecord, finish: u64){ + pub fn node_finish(node: NodeRecord, finish: u64) { // assert!(index < MAX_LOGS, "Node log index out of bounds"); - assert!((node.dag_info.node_id as usize) < MAX_NODES, "Node ID out of bounds"); + assert!( + (node.dag_info.node_id as usize) < MAX_NODES, + "Node ID out of bounds" + ); let mut mcs_node = MCSNode::new(); let mut recorder_opt = NODE_FINISH.lock(&mut mcs_node); @@ -700,9 +703,12 @@ pub mod perf { } } - pub fn node_preempt(node:NodeRecord){ + pub fn node_preempt(node: NodeRecord) { // assert!(index < MAX_LOGS, "Node log index out of bounds"); - assert!((node.dag_info.node_id as usize) < MAX_NODES, "Node ID out of bounds"); + assert!( + (node.dag_info.node_id as usize) < MAX_NODES, + "Node ID out of bounds" + ); let mut mcs_node = MCSNode::new(); let mut recorder_opt = NODE_PREEMPT_COUNT.lock(&mut mcs_node); @@ -712,9 +718,12 @@ pub mod perf { recorder[node.period_count as usize][node.dag_info.node_id as usize] += 1; } - pub fn dag_preempt(node:NodeRecord){ + pub fn dag_preempt(node: NodeRecord) { // assert!(index < MAX_LOGS, "Node log index out of bounds"); - assert!((node.dag_info.dag_id as usize) < MAX_DAGS, "DAG ID out of bounds"); + assert!( + (node.dag_info.dag_id as usize) < MAX_DAGS, + "DAG ID out of bounds" + ); let mut mcs_node = MCSNode::new(); let mut recorder_opt = DAG_PREEMPT_COUNT.lock(&mut mcs_node); @@ -789,7 +798,12 @@ pub mod perf { let relative_deadline = relative_deadline_opt.as_ref().map_or(0, |arr| arr[i][j]); let dag_preempt = dag_preempt_opt.as_ref().map_or(0, |arr| arr[i][j]); - if pre_send_outer != 0 || fin_recv_outer != 0 || absolute_deadline != 0 || relative_deadline != 0 || dag_preempt != 0 { + if pre_send_outer != 0 + || fin_recv_outer != 0 + || absolute_deadline != 0 + || relative_deadline != 0 + || dag_preempt != 0 + { let format_ts = |ts: u64| -> String { if ts == 0 { "-".to_string() @@ -857,10 +871,7 @@ pub mod perf { let core_id = node_core_opt.as_ref().map_or(0, |arr| arr[i][j]); if start != 0 || finish != 0 || preempt_count != 0 { - - let format_ts = |ts: u64| -> String { - ts.to_string() - }; + let format_ts = |ts: u64| -> String { ts.to_string() }; let duration = if start != 0 && finish != 0 { finish.saturating_sub(start).to_string() diff --git a/awkernel_async_lib/src/time_interval.rs b/awkernel_async_lib/src/time_interval.rs index ed188056b..ec5bc6248 100644 --- a/awkernel_async_lib/src/time_interval.rs +++ b/awkernel_async_lib/src/time_interval.rs @@ -29,11 +29,7 @@ //! SOFTWARE. use crate::sleep_task::Sleep; -use crate::{ - task::{ - perf::{update_pre_send_outer_timestamp_at, get_period_count}, - }, -}; +use crate::task::perf::{get_period_count, update_pre_send_outer_timestamp_at}; use alloc::boxed::Box; use awkernel_lib::time::Time; use core::{ diff --git a/kernel/Cargo.toml b/kernel/Cargo.toml index 9368f5904..02f8b3fec 100644 --- a/kernel/Cargo.toml +++ b/kernel/Cargo.toml @@ -82,6 +82,7 @@ no_std_unwinding = ["dep:unwinding"] debug = ["dep:gimli", "dep:addr2line"] x86 = [ "perf", + "awkernel_async_lib/x86", "no_std_unwinding", "awkernel_lib/x86", "dep:x86_64", diff --git a/userland/src/lib.rs b/userland/src/lib.rs index 01a66fe18..695f13b79 100644 --- a/userland/src/lib.rs +++ b/userland/src/lib.rs @@ -46,6 +46,9 @@ pub async fn main() -> Result<(), Cow<'static, str>> { #[cfg(feature = "test_dag")] test_dag::run().await; // test for DAG + #[cfg(feature = "test_autoware")] + test_autoware::run().await; // test for autoware + #[cfg(feature = "test_dvfs")] test_dvfs::run().await; // test for DVFS diff --git a/x86bootdisk/src/main.rs b/x86bootdisk/src/main.rs index 03d87bc4f..d03aecedf 100644 --- a/x86bootdisk/src/main.rs +++ b/x86bootdisk/src/main.rs @@ -91,4 +91,4 @@ fn main() { ) } } -} \ No newline at end of file +} From 9cabca942dab2b921ff2481ee03125d0e8f9016b Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Tue, 24 Mar 2026 07:40:39 +0900 Subject: [PATCH 04/60] fix: comment alignment 1 Signed-off-by: nokosaaan --- applications/tests/test_autoware/src/lib.rs | 426 +++----------------- 1 file changed, 45 insertions(+), 381 deletions(-) diff --git a/applications/tests/test_autoware/src/lib.rs b/applications/tests/test_autoware/src/lib.rs index 0ac57c330..487e8ccd6 100644 --- a/applications/tests/test_autoware/src/lib.rs +++ b/applications/tests/test_autoware/src/lib.rs @@ -18,23 +18,17 @@ use core::sync::atomic::{AtomicBool, AtomicU64, AtomicUsize, Ordering}; use core::ptr::null_mut; use core::sync::atomic::{AtomicPtr, Ordering as AtomicOrdering}; -// IMU ドライバーライブラリをインポート use imu_corrector::{ImuCorrector, ImuWithCovariance, Transform}; use imu_driver::{Header, ImuMsg, TamagawaImuParser, Vector3}; -// Vehicle Velocity Converter ライブラリをインポート(C++のpubsub機能に対応) use vehicle_velocity_converter::{ reactor_helpers, Twist, TwistWithCovariance, TwistWithCovarianceStamped, VehicleVelocityConverter, VelocityReport, }; -// Gyro Odometer ライブラリをインポート use gyro_odometer::{GyroOdometerConfig, GyroOdometerCore}; -// EKF Localizer ライブラリをインポート use ekf_localizer::{EKFModule, EKFParameters, Point3D, Pose, PoseWithCovariance, Quaternion}; -// COMMENTED OUT: 手動積分用の関数をコメントアウトしたためlibmは不要 -// use libm::{atan2, cos, sin}; /// EKF Odometry structure for publishing (equivalent to C++ nav_msgs::msg::Odometry) #[derive(Debug, Clone)] @@ -77,33 +71,25 @@ const EKF_TWIST_COVARIANCE: [f64; 36] = [ static LAST_DR_TIMESTAMP: AtomicU64 = AtomicU64::new(0); -// ネットワーク状態管理 const INTERFACE_ID: u64 = 0; // 10.0.2.0/24 is the IP address range of the Qemu's network. const INTERFACE_ADDR: Ipv4Addr = Ipv4Addr::new(10, 0, 2, 64); -// const INTERFACE_ADDR: Ipv4Addr = Ipv4Addr::new(192, 168, 100, 52); // For experiment. - // 10.0.2.2 is the IP address of the Qemu's host. const UDP_TCP_DST_ADDR: Ipv4Addr = Ipv4Addr::new(10, 0, 2, 2); -// const UDP_TCP_DST_ADDR: Ipv4Addr = Ipv4Addr::new(192, 168, 100, 1); // For experiment. - const UDP_DST_PORT: u16 = 26099; const TCP_DST_PORT: u16 = 26099; const TCP_LISTEN_PORT: u16 = 26100; -// JSONデータ保存用のグローバル変数 static mut LATEST_JSON_DATA: Option = None; static JSON_DATA_READY: AtomicBool = AtomicBool::new(false); static JSON_DATA_LENGTH: AtomicUsize = AtomicUsize::new(0); -// CSVデータ埋め込み const IMU_CSV_DATA_STR: &str = include_str!("../imu_raw.csv"); const VELOCITY_CSV_DATA_STR: &str = include_str!("../velocity_status.csv"); -// CSVパース結果の保存 #[derive(Clone, Debug)] struct ImuCsvRow { timestamp: u64, @@ -163,27 +149,18 @@ fn current_period_id(_dag_id: u32) -> u32 { 0 } -// COMMENTED OUT: 手動積分用のDR_POSEはEKF内部状態からポーズを取得するようになったため不要 -// static mut DR_POSE: Option = None; - pub async fn run() { wait_microsec(1000000); if let Err(e) = initialize_csv_data() { - log::warn!("CSVデータの初期化に失敗しました: {}", e); + log::warn!("Failed to initialize CSV data: {}", e); } log::info!("Starting Autoware test application with simplified TCP networking"); - // 初期ネットワークインターフェース情報を表示 - //print_network_interfaces(); - let dag = create_dag(); let dag_id = dag.get_id(); - // ダミーデータ送信用リアクター - // MODIFIED: 周期を10msから50msに変更(Autowareのekf_data_publisher.pyと同じ周期) - // これにより、CSVデータの消費速度が両システムで一致する dag.register_periodic_reactor::<_, (DagMsg, DagMsg, DagMsg)>( "start_dummy_data".into(), move || -> (DagMsg, DagMsg, DagMsg) { @@ -200,11 +177,10 @@ pub async fn run() { Cow::from("start_pose"), ], SchedulerType::GEDF(5), - Duration::from_millis(50), // CHANGED: 10ms -> 50ms (Autowareと同じ) + Duration::from_millis(50), ) .await; - // IMU driver node (periodic_reactor) - Dummy data generator dag.register_reactor::<_, (DagMsg,), (DagMsg,)>( "imu_driver".into(), move |(start_msg,): (DagMsg,)| -> (DagMsg,) { @@ -268,7 +244,6 @@ pub async fn run() { ) .await; - // Vehicle Velocity Converter node - VelocityReport to TwistWithCovarianceStamped converter dag.register_reactor::<_, (DagMsg,), (DagMsg,)>( "vehicle_velocity_converter".into(), move |(start_msg,): (DagMsg,)| -> (DagMsg,) { @@ -313,23 +288,18 @@ pub async fn run() { (pack_dag_msg(twist_msg, period_id),) }, - vec![Cow::from("start_vel")], // Subscribe to start_vel topic - vec![Cow::from("velocity_twist")], // Publish to twist_with_covariance topic + vec![Cow::from("start_vel")], + vec![Cow::from("velocity_twist")], SchedulerType::GEDF(5), ) .await; - //Imu Corrector dag.register_reactor::<_, (DagMsg,), (DagMsg,)>( "imu_corrector".into(), |(imu_msg,): (DagMsg,)| -> (DagMsg,) { let (imu_msg, period_id) = unpack_dag_msg(imu_msg); let corrector = ImuCorrector::new(); - // Use the enhanced corrector that outputs ImuWithCovariance let corrected = corrector.correct_imu_with_covariance(&imu_msg, None); - // if LOG_ENABLE { - // log::debug!("IMU corrected in imu_corrector node with covariance"); - // } (pack_dag_msg(corrected, period_id),) }, vec![Cow::from("imu_data")], @@ -338,7 +308,6 @@ pub async fn run() { ) .await; - // Gyro Odometer node - Simplified single processing step dag.register_reactor::<_, (DagMsg, DagMsg), (DagMsg,)>( "gyro_odometer".into(), |(imu_msg, vehicle_msg): (DagMsg, DagMsg)| -> (DagMsg,) { @@ -347,7 +316,6 @@ pub async fn run() { let current_timestamp = imu_with_cov.header.timestamp; let current_time = get_awkernel_uptime_timestamp(); - // Get or initialize gyro odometer core let gyro_odometer = match gyro_odometer::get_or_initialize() { Ok(core) => core, Err(_) => { @@ -355,11 +323,9 @@ pub async fn run() { } }; - // Add both messages to queues (both arrive together in test_autoware) gyro_odometer.add_vehicle_twist(vehicle_twist); gyro_odometer.add_imu(imu_with_cov); - - // Process once with current time and return result + match gyro_odometer.process_and_get_result(current_time) { Some(result) => (pack_dag_msg(gyro_odometer.process_result(result), period_imu),), None => (pack_dag_msg(reactor_helpers::create_empty_twist(current_timestamp), period_imu),) @@ -371,23 +337,10 @@ pub async fn run() { ) .await; - // Pose dummy data generator reactor dag.register_reactor::<_, (DagMsg,), (DagMsg,)>( "pose_dummy_generator".into(), move |(start_msg,): (DagMsg,)| -> (DagMsg,) { let (_counter, period_id) = unpack_dag_msg(start_msg); - // Generate dummy pose data that moves in a circle - // let time = counter as f64 * 0.1; // Time progression - // let radius = 10.0; // Circle radius - // let angular_velocity = 0.5; // rad/s - - // aip_x1_description/config/sensors_calibration.yaml - // if needed, comment out and use fixed values below - // let x = 0.86419; - // let y = 0.0; - // let z = 2.18096; - // let yaw = angular_velocity * time; - // for initial pose let x = 0.0; let y = 0.0; let z = 0.0; @@ -402,11 +355,6 @@ pub async fn run() { }, }; - // if LOG_ENABLE { - // log::debug!("Generated dummy pose: x={:.3}, y={:.3}, yaw={:.3}, counter={}", - // pose.position.x, pose.position.y, yaw, counter); - // } - (pack_dag_msg(pose, period_id),) }, vec![Cow::from("start_pose")], @@ -415,19 +363,13 @@ pub async fn run() { ) .await; - // EKF Localizer reactor - combines pose and twist data - // MODIFIED: 手動積分(integrated_pose)を廃止し、EKFの内部状態から直接ポーズを取得するように変更 dag.register_reactor::<_, (DagMsg, DagMsg), (DagMsg, DagMsg)>( "ekf_localizer".into(), |(pose_msg, twist_msg): (DagMsg, DagMsg)| -> (DagMsg, DagMsg) { let (pose, period_pose) = unpack_dag_msg(pose_msg); let (twist, _period_twist) = unpack_dag_msg(twist_msg); - // Initialize EKF Localizer if not already done if get_ekf_localizer().is_none() { - if let Err(e) = initialize_ekf_localizer() { - // if LOG_ENABLE { - // log::error!("Failed to initialize EKF Localizer: {}", e); - // } + if let Err(_e) = initialize_ekf_localizer() { return (pack_dag_msg(pose, period_pose), pack_dag_msg(EKFOdometry { header: imu_driver::Header { frame_id: "map", @@ -450,91 +392,35 @@ pub async fn run() { } let ekf = get_ekf_localizer().unwrap(); - - // Initialize EKF with first pose if not already initialized + static mut INITIALIZED: bool = false; unsafe { if !INITIALIZED { ekf.initialize(pose.clone()); - // COMMENTED OUT: 手動積分用の変数は使用しない - // DR_POSE = Some(pose.clone()); LAST_DR_TIMESTAMP.store(twist.header.timestamp, Ordering::Relaxed); INITIALIZED = true; - // if LOG_ENABLE { - // log::info!("EKF Localizer initialized with initial pose"); - // } } } - - // Predict step using measured time gap - // MODIFIED: CSVタイムスタンプ差ではなく、固定dtを使用 - // Autowareのekf_data_publisher.pyは50ms固定周期でデータをpublishする - // EKFは実際の経過時間(システムクロック)を使用するため、 - // Awkernelも同様に固定dtを使用することで挙動を一致させる - // - // OLD CODE (CSVタイムスタンプ差を使用): - // let current_ts = twist.header.timestamp; - // let last_ts = LAST_DR_TIMESTAMP.swap(current_ts, Ordering::Relaxed); - // let dt = if last_ts == 0 { - // 0.0 - // } else { - // (current_ts.saturating_sub(last_ts)) as f64 / 1_000_000_000.0 - // }; - // - // NEW CODE: 固定dt = 50ms (0.05秒) - Autowareと同じ周期 - const FIXED_DT: f64 = 0.05; // 50ms in seconds + + // Use a fixed 50ms timestep to match the Autoware publisher cadence. + const FIXED_DT: f64 = 0.05; let dt = FIXED_DT; if dt > 0.0 { ekf.predict(dt); } - // ADDED: EKFに速度観測値を更新(カルマンフィルタの観測更新ステップ) let vx = twist.twist.twist.linear.x; let wz = twist.twist.twist.angular.z; ekf.update_velocity(vx, wz); - // COMMENTED OUT: 手動積分(Dead Reckoning)処理 - // Autowareとの精度向上のため、EKF内部状態から直接ポーズを取得するように変更 - // let mut integrated_pose = unsafe { DR_POSE.clone().unwrap_or_else(|| pose.clone()) }; - // let yaw = quaternion_to_yaw(&integrated_pose.orientation); - // let vx = twist.twist.twist.linear.x; - // let vy = twist.twist.twist.linear.y; - // let vz = twist.twist.twist.linear.z; - // let wz = twist.twist.twist.angular.z; - // - // if dt > 0.0 { - // let cos_yaw = cos(yaw); - // let sin_yaw = sin(yaw); - // let new_yaw = yaw + wz * dt; - // - // integrated_pose.position.x += (vx * cos_yaw - vy * sin_yaw) * dt; - // integrated_pose.position.y += (vx * sin_yaw + vy * cos_yaw) * dt; - // integrated_pose.position.z += vz * dt; - // integrated_pose.orientation = yaw_to_quaternion(new_yaw); - // } - // - // unsafe { - // DR_POSE = Some(integrated_pose.clone()); - // } - - // MODIFIED: EKFの内部状態から直接ポーズを取得 - // get_biased_yaw=false でyaw_biasを考慮したポーズを取得 let ekf_pose = ekf.get_current_pose(false); - - // MODIFIED: EKFから動的な共分散を取得(固定値ではなく) - // これにより、走行距離や時間の経過に伴う不確かさの変化を反映 + let pose_covariance = ekf.get_current_pose_covariance(); let twist_covariance = ekf.get_current_twist_covariance(); - - // COMMENTED OUT: 固定共分散の使用 - // let pose_covariance = EKF_POSE_COVARIANCE; - // let twist_covariance = EKF_TWIST_COVARIANCE; - - // Get EKF's estimated twist + let ekf_twist = ekf.get_current_twist(); - - // Create odometry message using EKF's estimated pose and twist + let odometry = EKFOdometry { header: imu_driver::Header { frame_id: "map", @@ -546,7 +432,6 @@ pub async fn run() { covariance: pose_covariance, }, twist: TwistWithCovariance { - // Use EKF's estimated twist instead of input twist twist: Twist { linear: imu_driver::Vector3::new(ekf_twist.linear.x, ekf_twist.linear.y, ekf_twist.linear.z), angular: imu_driver::Vector3::new(ekf_twist.angular.x, ekf_twist.angular.y, ekf_twist.angular.z), @@ -554,18 +439,7 @@ pub async fn run() { covariance: twist_covariance, }, }; - - // if LOG_ENABLE { - // log::debug!("EKF Localizer: ekf_pose=({:.3}, {:.3}, {:.3}), dt={:.3}, awkernel_timestamp={}", - // ekf_pose.position.x, ekf_pose.position.y, ekf_pose.position.z, dt, odometry.header.timestamp); - // log::debug!("EKF Localizer: ekf_twist=({:.3}, {:.3}, {:.3}), angular=({:.3}, {:.3}, {:.3})", - // ekf_twist.linear.x, ekf_twist.linear.y, ekf_twist.linear.z, - // ekf_twist.angular.x, ekf_twist.angular.y, ekf_twist.angular.z); - // } - - // COMMENTED OUT: 手動積分のポーズを返していた - // (integrated_pose, odometry) - // MODIFIED: EKFの推定ポーズを返す + (pack_dag_msg(ekf_pose, period_pose), pack_dag_msg(odometry, period_pose)) }, vec![Cow::from("dummy_pose"), Cow::from("twist_with_covariance")], @@ -574,37 +448,12 @@ pub async fn run() { ) .await; - // Sink reactor for EKF Localizer output with TCP sending dag.register_sink_reactor::<_, (DagMsg, DagMsg)>( "ekf_sink".into(), move |(pose_msg, odom_msg): (DagMsg, DagMsg)| { let (_pose, _period_pose) = unpack_dag_msg(pose_msg); let (ekf_odom, _period_odom) = unpack_dag_msg(odom_msg); - // log::info!("=== EKF Sink Reactor 実行 ==="); - - // if LOG_ENABLE { - // log::info!("Estimated Pose:"); - // log::info!(" Position: x={:.3}, y={:.3}, z={:.3}", - // pose.position.x, pose.position.y, pose.position.z); - // log::info!(" Orientation: x={:.3}, y={:.3}, z={:.3}, w={:.3}", - // pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w); - - // log::info!("EKF Odometry (ekf_odom):"); - // log::info!(" Frame: {} -> {}", ekf_odom.header.frame_id, ekf_odom.child_frame_id); - // log::info!(" Timestamp: {}", ekf_odom.header.timestamp); - // log::info!(" Position: x={:.3}, y={:.3}, z={:.3}", - // ekf_odom.pose.pose.position.x, ekf_odom.pose.pose.position.y, ekf_odom.pose.pose.position.z); - // log::info!(" Orientation: x={:.3}, y={:.3}, z={:.3}, w={:.3}", - // ekf_odom.pose.pose.orientation.x, ekf_odom.pose.pose.orientation.y, - // ekf_odom.pose.pose.orientation.z, ekf_odom.pose.pose.orientation.w); - // log::info!(" Linear Velocity: x={:.3}, y={:.3}, z={:.3}", - // ekf_odom.twist.twist.linear.x, ekf_odom.twist.twist.linear.y, ekf_odom.twist.twist.linear.z); - // log::info!(" Angular Velocity: x={:.3}, y={:.3}, z={:.3}", - // ekf_odom.twist.twist.angular.x, ekf_odom.twist.twist.angular.y, ekf_odom.twist.twist.angular.z); - // log::info!("============================="); - // } - - // JSONデータを作成してグローバル変数に保存 + let json_data = format!( r#"{{"header":{{"frame_id":"{}","timestamp":{}}},"child_frame_id":"{}","pose":{{"pose":{{"position":{{"x":{:.6},"y":{:.6},"z":{:.6}}},"orientation":{{"x":{:.6},"y":{:.6},"z":{:.6},"w":{:.6}}}}},"covariance":[{}]}},"twist":{{"twist":{{"linear":{{"x":{:.6},"y":{:.6},"z":{:.6}}},"angular":{{"x":{:.6},"y":{:.6},"z":{:.6}}}}},"covariance":[{}]}}}}"#, ekf_odom.header.frame_id, @@ -626,20 +475,15 @@ pub async fn run() { ekf_odom.twist.twist.angular.z, ekf_odom.twist.covariance.iter().map(|&x| format!("{:.6}", x)).collect::>().join(",") ); - - let awkernel_timestamp = get_awkernel_uptime_timestamp(); - // log::info!("JSONデータ作成完了: {} bytes, awkernel_timestamp={}", json_data.len(), awkernel_timestamp); - - // グローバル変数にJSONデータを保存 + save_json_data_to_global(json_data); }, vec![Cow::from("estimated_pose"), Cow::from("ekf_odometry")], SchedulerType::GEDF(5), - Duration::from_millis(50), // CHANGED: 10ms -> 50ms (Autowareと同じ) + Duration::from_millis(50), ) .await; - // DAG の作成を完了 let result = finish_create_dags(&[dag.clone()]).await; match result { @@ -654,51 +498,37 @@ pub async fn run() { } } - // ノード数の確認 - // assert_eq!(dag.node_count(), 9); // 1つの periodic reactor + 8つの reactor(network_info_display追加) - // assert_eq!(dag.edge_count(), 10); // トピックエッジの数 - log::info!("Autoware test application DAG completed"); - log::info!("=== ネットワークテスト開始 ==="); - log::info!("インターフェースID: {}", INTERFACE_ID); - log::info!("インターフェースIP: {}", INTERFACE_ADDR); - log::info!("宛先IP: {}", UDP_TCP_DST_ADDR); - // + log::info!("=== Network test start ==="); + log::info!("Interface ID: {}", INTERFACE_ID); + log::info!("Interface IP: {}", INTERFACE_ADDR); + log::info!("Destination IP: {}", UDP_TCP_DST_ADDR); awkernel_lib::net::add_ipv4_addr(INTERFACE_ID, INTERFACE_ADDR, 24); log::info!( - "IPv4アドレス設定完了: {} をインターフェース {} に追加", + "Configured IPv4 address {} on interface {}", INTERFACE_ADDR, INTERFACE_ID ); - // ネットワークスタックの初期化を待つ - log::info!("ネットワークスタック初期化のため待機中..."); + log::info!("Waiting for network stack initialization..."); awkernel_async_lib::sleep(Duration::from_secs(2)).await; - // リアクターAPIに干渉しない周期UDP送信タスクを開始 - log::info!("周期UDP送信タスクを開始します"); + log::info!("Starting periodic UDP sender task"); start_periodic_udp_sender().await; - // または、設定可能な周期で開始する場合 - // start_configurable_udp_sender(2).await; // 2秒間隔 - - // JSONデータが準備されるまで待機(最大3秒) - log::info!("JSONデータの準備を待機中..."); + log::info!("Waiting for JSON data to become ready..."); let mut wait_count = 0; const MAX_WAIT_COUNT: u32 = 3; while !JSON_DATA_READY.load(Ordering::Relaxed) && wait_count < MAX_WAIT_COUNT { - // log::info!("JSONデータ待機中... ({}/{})", wait_count + 1, MAX_WAIT_COUNT); awkernel_async_lib::sleep(Duration::from_secs(1)).await; wait_count += 1; } if JSON_DATA_READY.load(Ordering::Relaxed) { - // log::info!("JSONデータが準備されました。周期UDP送信タスクが動作中です"); - // 周期UDP送信タスクは既に動作中なので、ここでは何もしない } else { - log::warn!("JSONデータが準備されませんでした。周期UDP送信タスクは待機中です"); + log::warn!("JSON data was not ready. Periodic UDP sender task remains waiting"); } log::info!("Autoware test application completed"); @@ -709,32 +539,22 @@ fn initialize_csv_data() -> Result<(), &'static str> { if IMU_CSV_DATA.is_none() { let imu_data = parse_imu_csv(IMU_CSV_DATA_STR)?; if imu_data.is_empty() { - return Err("IMU CSVが空です"); + return Err("IMU CSV is empty"); } - log::info!("IMU CSVデータをロード: {} rows", imu_data.len()); + log::info!("Loaded IMU CSV data: {} rows", imu_data.len()); IMU_CSV_DATA = Some(imu_data); } if VELOCITY_CSV_DATA.is_none() { let velocity_data = parse_velocity_csv(VELOCITY_CSV_DATA_STR)?; if velocity_data.is_empty() { - return Err("Velocity CSVが空です"); + return Err("Velocity CSV is empty"); } - log::info!("Velocity CSVデータをロード: {} rows", velocity_data.len()); + log::info!("Loaded velocity CSV data: {} rows", velocity_data.len()); VELOCITY_CSV_DATA = Some(velocity_data); } } - // let imu_start = find_first_active_imu_index(); - // IMU_CSV_INDEX.store(imu_start, Ordering::Relaxed); - // let velocity_start = find_first_moving_velocity_index(); - // VELOCITY_CSV_INDEX.store(velocity_start, Ordering::Relaxed); - // log::info!( - // "CSV開始インデックス: IMU={}, Velocity={}", - // imu_start, - // velocity_start - // ); - Ok(()) } @@ -743,7 +563,7 @@ fn parse_imu_csv(csv: &str) -> Result, &'static str> { parse_csv_records(csv, |fields| { if fields.len() < 12 { - return Err("IMU CSVの列数が不足しています"); + return Err("IMU CSV has insufficient columns"); } let timestamp = parse_timestamp(fields[0], fields[1])?; @@ -781,7 +601,7 @@ fn parse_velocity_csv(csv: &str) -> Result, &'static str> { parse_csv_records(csv, |fields| { if fields.len() < 5 { - return Err("Velocity CSVの列数が不足しています"); + return Err("Velocity CSV has insufficient columns"); } let timestamp = parse_timestamp(fields[0], fields[1])?; @@ -817,7 +637,7 @@ where input = &input[in_read..]; if matches!(result, ReadRecordResult::OutputFull) { - return Err("CSV出力バッファが不足しています"); + return Err("CSV output buffer is too small"); } if num_fields == 0 { @@ -832,7 +652,7 @@ where for i in 0..num_fields { let end = ends[i]; let slice = &output[start..end]; - let field = core::str::from_utf8(slice).map_err(|_| "CSV UTF-8変換に失敗しました")?; + let field = core::str::from_utf8(slice).map_err(|_| "Failed to decode CSV UTF-8")?; fields.push(field); start = end; } @@ -857,7 +677,7 @@ fn parse_timestamp(sec: &str, nsec: &str) -> Result { let ts = sec_val .checked_mul(1_000_000_000) .and_then(|v| v.checked_add(nsec_val)) - .ok_or("timestamp計算でオーバーフローしました")?; + .ok_or("Timestamp calculation overflowed")?; Ok(ts) } @@ -868,7 +688,7 @@ fn parse_u64(field: &str) -> Result { } trimmed .parse::() - .map_err(|_| "u64パースに失敗しました") + .map_err(|_| "Failed to parse u64") } fn parse_f64(field: &str) -> Result { @@ -878,47 +698,12 @@ fn parse_f64(field: &str) -> Result { } trimmed .parse::() - .map_err(|_| "f64パースに失敗しました") + .map_err(|_| "Failed to parse f64") } -// fn find_first_moving_velocity_index() -> usize { -// const EPS: f64 = 1.0e-6; -// let data = unsafe { VELOCITY_CSV_DATA.as_ref() }; -// if let Some(rows) = data { -// for (idx, row) in rows.iter().enumerate() { -// if row.longitudinal_velocity.abs() > EPS || row.lateral_velocity.abs() > EPS { -// return idx; -// } -// } -// } -// 0 -// } -// -// fn find_first_active_imu_index() -> usize { -// const EPS: f64 = 1.0e-6; -// let data = unsafe { IMU_CSV_DATA.as_ref() }; -// if let Some(rows) = data { -// for (idx, row) in rows.iter().enumerate() { -// if row.angular_velocity.x.abs() > EPS -// || row.angular_velocity.y.abs() > EPS -// || row.angular_velocity.z.abs() > EPS -// || row.linear_acceleration.x.abs() > EPS -// || row.linear_acceleration.y.abs() > EPS -// || row.linear_acceleration.z.abs() > EPS -// { -// return idx; -// } -// } -// } -// 0 -// } - -// Awkernel起動時間からのタイムスタンプを取得する関数 +// Returns monotonic uptime in nanoseconds clamped to u64. fn get_awkernel_uptime_timestamp() -> u64 { - // awkernel_lib::delay::uptime_nano()はu128を返すが、JSONではu64を使用 - // ナノ秒単位のタイムスタンプを取得 let uptime_nanos = awkernel_lib::delay::uptime_nano(); - // u128からu64に変換(オーバーフローを防ぐため、適切な範囲に制限) if uptime_nanos > u64::MAX as u128 { u64::MAX } else { @@ -926,38 +711,25 @@ fn get_awkernel_uptime_timestamp() -> u64 { } } -// リアクターAPIに干渉しないUDP送信タスク(一定周期実行) pub async fn start_periodic_udp_sender() { - // log::info!("=== 周期UDP送信タスク開始 ==="); - - // 独立したタスクとして実行 awkernel_async_lib::spawn( "periodic_udp_sender".into(), periodic_udp_sender_task(), awkernel_async_lib::scheduler::SchedulerType::PrioritizedFIFO(0), ) .await; - - // log::info!("周期UDP送信タスクを開始しました"); } -// 周期UDP送信タスクの実装 async fn periodic_udp_sender_task() { - // log::info!("周期UDP送信タスク: 開始"); - - // UDPソケットを作成(一度だけ) let socket_result = awkernel_async_lib::net::udp::UdpSocket::bind_on_interface( INTERFACE_ID, &Default::default(), ); let mut socket = match socket_result { - Ok(socket) => { - // log::info!("周期UDP送信タスク: UDPソケット作成成功"); - socket - } + Ok(socket) => socket, Err(e) => { - log::error!("周期UDP送信タスク: UDPソケット作成失敗: {:?}", e); + log::error!("Periodic UDP sender task: failed to create UDP socket: {:?}", e); return; } }; @@ -965,40 +737,34 @@ async fn periodic_udp_sender_task() { let dst_addr = IpAddr::new_v4(UDP_TCP_DST_ADDR); let mut counter = 0; - // 無限ループで一定周期実行 loop { - // JSONデータの準備チェック if !JSON_DATA_READY.load(Ordering::Relaxed) { - // log::debug!("周期UDP送信タスク: JSONデータ未準備、待機中..."); awkernel_async_lib::sleep(Duration::from_secs(1)).await; continue; } - // 安全にJSONデータを取得 let json_data = unsafe { LATEST_JSON_DATA.as_ref().map(|s| s.clone()) }; if let Some(data) = json_data { - // UDP送信を実行 match socket.send(data.as_bytes(), &dst_addr, UDP_DST_PORT).await { Ok(_) => { counter += 1; log::info!( - "周期UDP送信タスク: 送信成功 #{} ({} bytes)", + "Periodic UDP sender task: send success #{} ({} bytes)", counter, data.len() ); - // レスポンス受信(オプション、タイムアウト付き) let mut buf = [0u8; 1024]; if let Some(Ok((n, src_addr, src_port))) = awkernel_async_lib::timeout( - Duration::from_millis(100), // 短いタイムアウト + Duration::from_millis(100), socket.recv(&mut buf), ) .await { if let Ok(response) = core::str::from_utf8(&buf[..n]) { log::debug!( - "周期UDP送信タスク: レスポンス受信: {}:{} - {}", + "Periodic UDP sender task: response received: {}:{} - {}", src_addr.get_addr(), src_port, response @@ -1007,106 +773,23 @@ async fn periodic_udp_sender_task() { } } Err(e) => { - log::warn!("周期UDP送信タスク: 送信失敗: {:?}", e); + log::warn!("Periodic UDP sender task: send failed: {:?}", e); } } } else { - log::warn!("周期UDP送信タスク: JSONデータが取得できませんでした"); + log::warn!("Periodic UDP sender task: failed to get JSON data"); } - // 一定周期で待機(例: 2秒間隔 - DAGの実行周期と衝突を避けるため) awkernel_async_lib::sleep(Duration::from_millis(5)).await; } } -// リアクターAPIに干渉しないUDP送信タスク(設定可能な周期) -// pub async fn start_configurable_udp_sender(interval_sec: u64) { -// log::info!("=== 設定可能周期UDP送信タスク開始 (間隔: {}秒) ===", interval_sec); - -// // 独立したタスクとして実行 -// awkernel_async_lib::spawn( -// "configurable_udp_sender".into(), -// configurable_udp_sender_task(interval_sec), -// awkernel_async_lib::scheduler::SchedulerType::GEDF(5), -// ) -// .await; - -// log::info!("設定可能周期UDP送信タスクを開始しました"); -// } - -// 設定可能な周期UDP送信タスクの実装 -// async fn configurable_udp_sender_task(interval_sec: u64) { -// log::info!("設定可能周期UDP送信タスク: 開始 (間隔: {}秒)", interval_sec); - -// // UDPソケットを作成 -// let socket_result = awkernel_async_lib::net::udp::UdpSocket::bind_on_interface( -// INTERFACE_ID, -// &Default::default(), -// ); - -// let mut socket = match socket_result { -// Ok(socket) => { -// log::info!("設定可能周期UDP送信タスク: UDPソケット作成成功"); -// socket -// } -// Err(e) => { -// log::error!("設定可能周期UDP送信タスク: UDPソケット作成失敗: {:?}", e); -// return; -// } -// }; - -// let dst_addr = IpAddr::new_v4(UDP_TCP_DST_ADDR); -// let mut counter = 0; - -// loop { -// // ネットワーク初期化チェック -// if !NETWORK_INITIALIZED.load(Ordering::Relaxed) { -// log::debug!("設定可能周期UDP送信タスク: ネットワーク未初期化、待機中..."); -// awkernel_async_lib::sleep(Duration::from_secs(1)).await; -// continue; -// } - -// // JSONデータの準備チェック -// if !JSON_DATA_READY.load(Ordering::Relaxed) { -// log::debug!("設定可能周期UDP送信タスク: JSONデータ未準備、待機中..."); -// awkernel_async_lib::sleep(Duration::from_secs(1)).await; -// continue; -// } - -// // 安全にJSONデータを取得 -// let json_data = unsafe { -// LATEST_JSON_DATA.as_ref().map(|s| s.clone()) -// }; - -// if let Some(data) = json_data { -// // UDP送信を実行 -// match socket.send(data.as_bytes(), &dst_addr, UDP_DST_PORT).await { -// Ok(_) => { -// counter += 1; -// log::info!("設定可能周期UDP送信タスク: 送信成功 #{} ({} bytes, 間隔: {}秒)", -// counter, data.len(), interval_sec); -// } -// Err(e) => { -// log::warn!("設定可能周期UDP送信タスク: 送信失敗: {:?}", e); -// } -// } -// } else { -// log::warn!("設定可能周期UDP送信タスク: JSONデータが取得できませんでした"); -// } - -// // 設定された周期で待機 -// awkernel_async_lib::sleep(Duration::from_secs(interval_sec)).await; -// } -// } - -// JSONデータをグローバル変数に保存する関数 fn save_json_data_to_global(json_data: String) { unsafe { LATEST_JSON_DATA = Some(json_data.clone()); } JSON_DATA_READY.store(true, Ordering::Relaxed); JSON_DATA_LENGTH.store(json_data.len(), Ordering::Relaxed); - // log::info!("JSONデータをグローバル変数に保存: {} bytes", json_data.len()); } // Transform error handling function @@ -1150,25 +833,6 @@ fn initialize_ekf_localizer() -> Result<(), &'static str> { } } -// COMMENTED OUT: 手動積分用の関数はEKF内部状態からポーズを取得するようになったため不要 -// EKFModule内にquaternion_to_yawとrpy_to_quaternionがあるため、そちらを使用 -// fn quaternion_to_yaw(q: &Quaternion) -> f64 { -// // Yaw extraction for dead reckoning heading propagation -// let siny_cosp = 2.0 * (q.w * q.z + q.x * q.y); -// let cosy_cosp = 1.0 - 2.0 * (q.y * q.y + q.z * q.z); -// atan2(siny_cosp, cosy_cosp) -// } -// -// fn yaw_to_quaternion(yaw: f64) -> Quaternion { -// let half = yaw * 0.5; -// Quaternion { -// x: 0.0, -// y: 0.0, -// z: sin(half), -// w: cos(half), -// } -// } - // Get EKF Localizer safely fn get_ekf_localizer() -> Option<&'static mut EKFModule> { let ptr = EKF_LOCALIZER.load(AtomicOrdering::Acquire); From 9832297a39bf52bafee8ccd55073c77979a6f968 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Tue, 24 Mar 2026 15:07:33 +0900 Subject: [PATCH 05/60] fix: module separation 1 Signed-off-by: nokosaaan --- .../test_autoware/ekf_localizer/src/lib.rs | 29 +++ .../tests/test_autoware/imu_driver/src/lib.rs | 21 +++ applications/tests/test_autoware/src/lib.rs | 167 ++---------------- .../vehicle_velocity_converter/src/lib.rs | 21 +++ 4 files changed, 83 insertions(+), 155 deletions(-) diff --git a/applications/tests/test_autoware/ekf_localizer/src/lib.rs b/applications/tests/test_autoware/ekf_localizer/src/lib.rs index 6714aea03..33db0dab9 100644 --- a/applications/tests/test_autoware/ekf_localizer/src/lib.rs +++ b/applications/tests/test_autoware/ekf_localizer/src/lib.rs @@ -5,9 +5,13 @@ extern crate alloc; use alloc::{vec, vec::Vec}; use core::f64::consts::PI; +use core::ptr::null_mut; +use core::sync::atomic::{AtomicPtr, Ordering as AtomicOrdering}; use libm::{asin, atan2, cos, sin}; use nalgebra::{Matrix6, Vector3, Vector6}; +static EKF_MODULE_INSTANCE: AtomicPtr = AtomicPtr::new(null_mut()); + /// State indices for EKF #[derive(Debug, Clone, Copy, PartialEq)] pub enum StateIndex { @@ -538,6 +542,31 @@ impl EKFModule { } } +pub fn get_or_initialize_default_module() -> &'static mut EKFModule { + let existing = EKF_MODULE_INSTANCE.load(AtomicOrdering::Acquire); + if !existing.is_null() { + return unsafe { &mut *existing }; + } + + let boxed = alloc::boxed::Box::new(EKFModule::new(EKFParameters::default())); + let ptr = alloc::boxed::Box::into_raw(boxed); + + match EKF_MODULE_INSTANCE.compare_exchange( + null_mut(), + ptr, + AtomicOrdering::AcqRel, + AtomicOrdering::Acquire, + ) { + Ok(_) => unsafe { &mut *ptr }, + Err(existing_ptr) => { + unsafe { + let _ = alloc::boxed::Box::from_raw(ptr); + &mut *existing_ptr + } + } + } +} + #[cfg(test)] mod tests { use super::*; diff --git a/applications/tests/test_autoware/imu_driver/src/lib.rs b/applications/tests/test_autoware/imu_driver/src/lib.rs index 09c2d6882..3c660c7cd 100644 --- a/applications/tests/test_autoware/imu_driver/src/lib.rs +++ b/applications/tests/test_autoware/imu_driver/src/lib.rs @@ -14,6 +14,14 @@ pub struct ImuMsg { pub linear_acceleration: Vector3, } +#[derive(Clone, Debug)] +pub struct ImuCsvRow { + pub timestamp: u64, + pub orientation: Quaternion, + pub angular_velocity: Vector3, + pub linear_acceleration: Vector3, +} + #[derive(Clone, Debug)] pub struct Header { pub frame_id: &'static str, @@ -60,6 +68,19 @@ impl Default for ImuMsg { } } +pub fn build_imu_msg_from_csv_row( + row: &ImuCsvRow, + frame_id: &'static str, + timestamp: u64, +) -> ImuMsg { + ImuMsg { + header: Header { frame_id, timestamp }, + orientation: row.orientation.clone(), + angular_velocity: row.angular_velocity.clone(), + linear_acceleration: row.linear_acceleration.clone(), + } +} + /// IMU data parser for Tamagawa IMU pub struct TamagawaImuParser { frame_id: &'static str, diff --git a/applications/tests/test_autoware/src/lib.rs b/applications/tests/test_autoware/src/lib.rs index 487e8ccd6..36df051f0 100644 --- a/applications/tests/test_autoware/src/lib.rs +++ b/applications/tests/test_autoware/src/lib.rs @@ -1,7 +1,7 @@ #![no_std] extern crate alloc; -use alloc::{borrow::Cow, collections::VecDeque, format, string::String, sync::Arc, vec, vec::Vec}; +use alloc::{borrow::Cow, format, string::String, vec, vec::Vec}; use awkernel_async_lib::dag::{create_dag, finish_create_dags}; use awkernel_async_lib::net::IpAddr; use awkernel_async_lib::scheduler::SchedulerType; @@ -13,22 +13,18 @@ use core::net::Ipv4Addr; use core::time::Duration; use csv_core::{ReadRecordResult, Reader}; // Thread-safe state management using atomic operations -use core::sync::atomic::{AtomicBool, AtomicU64, AtomicUsize, Ordering}; -// Global gyro odometer core instance with proper synchronization -use core::ptr::null_mut; -use core::sync::atomic::{AtomicPtr, Ordering as AtomicOrdering}; +use core::sync::atomic::{AtomicBool, AtomicUsize, Ordering}; -use imu_corrector::{ImuCorrector, ImuWithCovariance, Transform}; -use imu_driver::{Header, ImuMsg, TamagawaImuParser, Vector3}; +use imu_corrector::{ImuCorrector, ImuWithCovariance}; +use imu_driver::{build_imu_msg_from_csv_row, ImuCsvRow, ImuMsg, TamagawaImuParser}; use vehicle_velocity_converter::{ + build_velocity_report_from_csv_row, reactor_helpers, Twist, TwistWithCovariance, TwistWithCovarianceStamped, - VehicleVelocityConverter, VelocityReport, + VehicleVelocityConverter, VelocityCsvRow, }; -use gyro_odometer::{GyroOdometerConfig, GyroOdometerCore}; - -use ekf_localizer::{EKFModule, EKFParameters, Point3D, Pose, PoseWithCovariance, Quaternion}; +use ekf_localizer::{get_or_initialize_default_module, Point3D, Pose, PoseWithCovariance, Quaternion}; /// EKF Odometry structure for publishing (equivalent to C++ nav_msgs::msg::Odometry) #[derive(Debug, Clone)] @@ -39,37 +35,7 @@ pub struct EKFOdometry { pub twist: TwistWithCovariance, } -const LOG_ENABLE: bool = true; - -// EKF pose covariance (6x6 matrix flattened to array) -// Layout: [x, xy, xz, xr, xp, xy_yaw, -// yx, y, yz, yr, yp, y_yaw, -// zx, zy, z, zr, zp, z_yaw, -// rx, ry, rz, r, rp, r_yaw, -// px, py, pz, pr, p, p_yaw, -// yaw_x, yaw_y, yaw_z, yaw_r, yaw_p, yaw] -const EKF_POSE_COVARIANCE: [f64; 36] = [ - 0.0225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0225, 0.0, 0.0, - 0.0, 0.0, 0.0, 0.0, 0.000625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000625, 0.0, 0.0, 0.0, 0.0, 0.0, - 0.0, 0.000625, -]; - -// EKF twist covariance (6x6 matrix flattened to array) -// For twist, we mainly care about linear.x (vx) and angular.z (wz) -// Layout: [vx_x, vx_y, vx_z, vx_rx, vx_ry, vx_wz, -// vy_x, vy_y, vy_z, vy_rx, vy_ry, vy_wz, -// vz_x, vz_y, vz_z, vz_rx, vz_ry, vz_wz, -// wx_x, wx_y, wx_z, wx_rx, wx_ry, wx_wz, -// wy_x, wy_y, wy_z, wy_rx, wy_ry, wy_wz, -// wz_x, wz_y, wz_z, wz_rx, wz_ry, wz] -// Based on Autoware's typical twist uncertainty (0.01 m/s for linear, 0.01 rad/s for angular) -const EKF_TWIST_COVARIANCE: [f64; 36] = [ - 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, - 0.0, 0.0, 0.0, 0.0001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, - 0.0001, -]; - -static LAST_DR_TIMESTAMP: AtomicU64 = AtomicU64::new(0); +const LOG_ENABLE: bool = false; const INTERFACE_ID: u64 = 0; @@ -90,30 +56,11 @@ static JSON_DATA_LENGTH: AtomicUsize = AtomicUsize::new(0); const IMU_CSV_DATA_STR: &str = include_str!("../imu_raw.csv"); const VELOCITY_CSV_DATA_STR: &str = include_str!("../velocity_status.csv"); -#[derive(Clone, Debug)] -struct ImuCsvRow { - timestamp: u64, - orientation: imu_driver::Quaternion, - angular_velocity: imu_driver::Vector3, - linear_acceleration: imu_driver::Vector3, -} - -#[derive(Clone, Debug)] -struct VelocityCsvRow { - timestamp: u64, - longitudinal_velocity: f64, - lateral_velocity: f64, - heading_rate: f64, -} - static mut IMU_CSV_DATA: Option> = None; static mut VELOCITY_CSV_DATA: Option> = None; static IMU_CSV_COUNT: Mutex = Mutex::new(0); static VELOCITY_CSV_COUNT: Mutex = Mutex::new(0); -// Global EKF Localizer instance with proper synchronization -static EKF_LOCALIZER: AtomicPtr = AtomicPtr::new(null_mut()); - #[cfg(feature = "dag-send-period")] type DagMsg = (T, u32); #[cfg(not(feature = "dag-send-period"))] @@ -202,15 +149,7 @@ pub async fn run() { let idx = count % csv_data.len(); let row = &csv_data[idx]; let awkernel_timestamp = get_awkernel_uptime_timestamp(); - ImuMsg { - header: Header { - frame_id: "imu_link", - timestamp: awkernel_timestamp, - }, - orientation: row.orientation.clone(), - angular_velocity: row.angular_velocity.clone(), - linear_acceleration: row.linear_acceleration.clone(), - } + build_imu_msg_from_csv_row(row, "imu_link", awkernel_timestamp) } } else { let mut parser = TamagawaImuParser::new("imu_link"); @@ -259,15 +198,8 @@ pub async fn run() { let idx = count % csv_data.len(); let row = &csv_data[idx]; let awkernel_timestamp = get_awkernel_uptime_timestamp(); - let velocity_report = VelocityReport { - header: Header { - frame_id: "base_link", - timestamp: awkernel_timestamp, - }, - longitudinal_velocity: row.longitudinal_velocity, - lateral_velocity: row.lateral_velocity, - heading_rate: row.heading_rate, - }; + let velocity_report = + build_velocity_report_from_csv_row(row, "base_link", awkernel_timestamp); *count_guard += 1; if *count_guard >= 5700 { @@ -368,36 +300,12 @@ pub async fn run() { |(pose_msg, twist_msg): (DagMsg, DagMsg)| -> (DagMsg, DagMsg) { let (pose, period_pose) = unpack_dag_msg(pose_msg); let (twist, _period_twist) = unpack_dag_msg(twist_msg); - if get_ekf_localizer().is_none() { - if let Err(_e) = initialize_ekf_localizer() { - return (pack_dag_msg(pose, period_pose), pack_dag_msg(EKFOdometry { - header: imu_driver::Header { - frame_id: "map", - timestamp: twist.header.timestamp, - }, - child_frame_id: "base_link", - pose: PoseWithCovariance { - pose: pose, - covariance: EKF_POSE_COVARIANCE, - }, - twist: TwistWithCovariance { - twist: Twist { - linear: imu_driver::Vector3::new(0.0, 0.0, 0.0), - angular: imu_driver::Vector3::new(0.0, 0.0, 0.0), - }, - covariance: EKF_TWIST_COVARIANCE, - }, - }, period_pose)); - } - } - - let ekf = get_ekf_localizer().unwrap(); + let ekf = get_or_initialize_default_module(); static mut INITIALIZED: bool = false; unsafe { if !INITIALIZED { ekf.initialize(pose.clone()); - LAST_DR_TIMESTAMP.store(twist.header.timestamp, Ordering::Relaxed); INITIALIZED = true; } } @@ -791,54 +699,3 @@ fn save_json_data_to_global(json_data: String) { JSON_DATA_READY.store(true, Ordering::Relaxed); JSON_DATA_LENGTH.store(json_data.len(), Ordering::Relaxed); } - -// Transform error handling function -fn get_transform_safely(from_frame: &str, to_frame: &str) -> Result { - // For now, return identity transform - // In a real implementation, this would query the transform tree - if from_frame == to_frame { - Ok(Transform::identity()) - } else { - // Simulate transform lookup - Ok(Transform::identity()) - } -} - -// Initialize EKF Localizer safely -fn initialize_ekf_localizer() -> Result<(), &'static str> { - let params = EKFParameters::default(); - let ekf = EKFModule::new(params); - - // Allocate on heap and store pointer - let boxed_ekf = alloc::boxed::Box::new(ekf); - let ptr = alloc::boxed::Box::into_raw(boxed_ekf); - - // Try to store the pointer atomically - let old_ptr = EKF_LOCALIZER.compare_exchange( - null_mut(), - ptr, - AtomicOrdering::Acquire, - AtomicOrdering::Relaxed, - ); - - match old_ptr { - Ok(_) => Ok(()), - Err(_) => { - // Another thread already initialized it, clean up our allocation - unsafe { - let _ = alloc::boxed::Box::from_raw(ptr); - } - Ok(()) - } - } -} - -// Get EKF Localizer safely -fn get_ekf_localizer() -> Option<&'static mut EKFModule> { - let ptr = EKF_LOCALIZER.load(AtomicOrdering::Acquire); - if ptr.is_null() { - None - } else { - unsafe { Some(&mut *ptr) } - } -} diff --git a/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs b/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs index 7ef0aba5b..cb2ff5e52 100644 --- a/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs +++ b/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs @@ -25,6 +25,27 @@ pub struct VelocityReport { pub heading_rate: f64, } +#[derive(Debug, Clone)] +pub struct VelocityCsvRow { + pub timestamp: u64, + pub longitudinal_velocity: f64, + pub lateral_velocity: f64, + pub heading_rate: f64, +} + +pub fn build_velocity_report_from_csv_row( + row: &VelocityCsvRow, + frame_id: &'static str, + timestamp: u64, +) -> VelocityReport { + VelocityReport { + header: Header { frame_id, timestamp }, + longitudinal_velocity: row.longitudinal_velocity, + lateral_velocity: row.lateral_velocity, + heading_rate: row.heading_rate, + } +} + /// TwistWithCovarianceStampedメッセージの構造体 #[derive(Debug, Clone)] pub struct TwistWithCovarianceStamped { From 9bac5301211f68644fe45c6f6e80de9fb85e7de9 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Tue, 24 Mar 2026 15:43:20 +0900 Subject: [PATCH 06/60] fix: revert schedtype and toml Signed-off-by: nokosaaan --- applications/tests/test_autoware/src/lib.rs | 2 +- mdbook/book.toml | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/applications/tests/test_autoware/src/lib.rs b/applications/tests/test_autoware/src/lib.rs index 36df051f0..621e7bd9c 100644 --- a/applications/tests/test_autoware/src/lib.rs +++ b/applications/tests/test_autoware/src/lib.rs @@ -623,7 +623,7 @@ pub async fn start_periodic_udp_sender() { awkernel_async_lib::spawn( "periodic_udp_sender".into(), periodic_udp_sender_task(), - awkernel_async_lib::scheduler::SchedulerType::PrioritizedFIFO(0), + awkernel_async_lib::scheduler::SchedulerType::GEDF(5), ) .await; } diff --git a/mdbook/book.toml b/mdbook/book.toml index 4bf31f613..8f5c1c4a3 100644 --- a/mdbook/book.toml +++ b/mdbook/book.toml @@ -1,6 +1,7 @@ [book] authors = ["Yuuki Takano"] language = "en" +multilingual = false src = "src" title = "Awkernel" From 47de021827b9ff9ae5268e4eb994cde2c9ef5376 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Thu, 26 Mar 2026 09:15:02 +0900 Subject: [PATCH 07/60] add: saveing implementation msg with period Signed-off-by: nokosaaan --- .../test_autoware/ekf_localizer/src/lib.rs | 10 +- .../tests/test_autoware/imu_driver/src/lib.rs | 5 +- applications/tests/test_autoware/src/lib.rs | 64 ++++++---- .../vehicle_velocity_converter/src/lib.rs | 5 +- applications/tests/test_dag/Cargo.toml | 4 + applications/tests/test_dag/src/lib.rs | 112 ++++++++++++------ awkernel_async_lib/src/dag.rs | 57 +++------ awkernel_async_lib/src/task.rs | 7 +- userland/Cargo.toml | 2 +- 9 files changed, 156 insertions(+), 110 deletions(-) diff --git a/applications/tests/test_autoware/ekf_localizer/src/lib.rs b/applications/tests/test_autoware/ekf_localizer/src/lib.rs index 33db0dab9..f7a9396ed 100644 --- a/applications/tests/test_autoware/ekf_localizer/src/lib.rs +++ b/applications/tests/test_autoware/ekf_localizer/src/lib.rs @@ -558,12 +558,10 @@ pub fn get_or_initialize_default_module() -> &'static mut EKFModule { AtomicOrdering::Acquire, ) { Ok(_) => unsafe { &mut *ptr }, - Err(existing_ptr) => { - unsafe { - let _ = alloc::boxed::Box::from_raw(ptr); - &mut *existing_ptr - } - } + Err(existing_ptr) => unsafe { + let _ = alloc::boxed::Box::from_raw(ptr); + &mut *existing_ptr + }, } } diff --git a/applications/tests/test_autoware/imu_driver/src/lib.rs b/applications/tests/test_autoware/imu_driver/src/lib.rs index 3c660c7cd..fa36930eb 100644 --- a/applications/tests/test_autoware/imu_driver/src/lib.rs +++ b/applications/tests/test_autoware/imu_driver/src/lib.rs @@ -74,7 +74,10 @@ pub fn build_imu_msg_from_csv_row( timestamp: u64, ) -> ImuMsg { ImuMsg { - header: Header { frame_id, timestamp }, + header: Header { + frame_id, + timestamp, + }, orientation: row.orientation.clone(), angular_velocity: row.angular_velocity.clone(), linear_acceleration: row.linear_acceleration.clone(), diff --git a/applications/tests/test_autoware/src/lib.rs b/applications/tests/test_autoware/src/lib.rs index 621e7bd9c..e0df1e920 100644 --- a/applications/tests/test_autoware/src/lib.rs +++ b/applications/tests/test_autoware/src/lib.rs @@ -19,12 +19,13 @@ use imu_corrector::{ImuCorrector, ImuWithCovariance}; use imu_driver::{build_imu_msg_from_csv_row, ImuCsvRow, ImuMsg, TamagawaImuParser}; use vehicle_velocity_converter::{ - build_velocity_report_from_csv_row, - reactor_helpers, Twist, TwistWithCovariance, TwistWithCovarianceStamped, - VehicleVelocityConverter, VelocityCsvRow, + build_velocity_report_from_csv_row, reactor_helpers, Twist, TwistWithCovariance, + TwistWithCovarianceStamped, VehicleVelocityConverter, VelocityCsvRow, }; -use ekf_localizer::{get_or_initialize_default_module, Point3D, Pose, PoseWithCovariance, Quaternion}; +use ekf_localizer::{ + get_or_initialize_default_module, Point3D, Pose, PoseWithCovariance, Quaternion, +}; /// EKF Odometry structure for publishing (equivalent to C++ nav_msgs::msg::Odometry) #[derive(Debug, Clone)] @@ -188,28 +189,28 @@ pub async fn run() { move |(start_msg,): (DagMsg,)| -> (DagMsg,) { let (_b, period_id) = unpack_dag_msg(start_msg); let converter = VehicleVelocityConverter::default(); - + let mut node = MCSNode::new(); let mut count_guard = VELOCITY_CSV_COUNT.lock(&mut node); let count = *count_guard; let data = unsafe { VELOCITY_CSV_DATA.as_ref() }; - + let csv_data = data.expect("VELOCITY_CSV_DATA must be initialized"); let idx = count % csv_data.len(); let row = &csv_data[idx]; let awkernel_timestamp = get_awkernel_uptime_timestamp(); let velocity_report = build_velocity_report_from_csv_row(row, "base_link", awkernel_timestamp); - + *count_guard += 1; if *count_guard >= 5700 { *count_guard = 0; log::info!("rust_e2e_app: finish csv for Velocity"); loop {} } - + let twist_msg = converter.convert_velocity_report(&velocity_report); - + if LOG_ENABLE { log::debug!("Vehicle velocity converter: Converted velocity report to twist - linear.x={:.3}, angular.z={:.3}, awkernel_timestamp={}", twist_msg.twist.twist.linear.x, @@ -217,7 +218,7 @@ pub async fn run() { twist_msg.header.timestamp ); } - + (pack_dag_msg(twist_msg, period_id),) }, vec![Cow::from("start_vel")], @@ -240,18 +241,28 @@ pub async fn run() { ) .await; - dag.register_reactor::<_, (DagMsg, DagMsg), (DagMsg,)>( + dag.register_reactor::<_, ( + DagMsg, + DagMsg, + ), (DagMsg,)>( "gyro_odometer".into(), - |(imu_msg, vehicle_msg): (DagMsg, DagMsg)| -> (DagMsg,) { + |(imu_msg, vehicle_msg): ( + DagMsg, + DagMsg, + )| + -> (DagMsg,) { let (imu_with_cov, period_imu) = unpack_dag_msg(imu_msg); let (vehicle_twist, _period_twist) = unpack_dag_msg(vehicle_msg); let current_timestamp = imu_with_cov.header.timestamp; let current_time = get_awkernel_uptime_timestamp(); - + let gyro_odometer = match gyro_odometer::get_or_initialize() { Ok(core) => core, Err(_) => { - return (pack_dag_msg(reactor_helpers::create_empty_twist(current_timestamp), period_imu),); + return (pack_dag_msg( + reactor_helpers::create_empty_twist(current_timestamp), + period_imu, + ),); } }; @@ -259,11 +270,17 @@ pub async fn run() { gyro_odometer.add_imu(imu_with_cov); match gyro_odometer.process_and_get_result(current_time) { - Some(result) => (pack_dag_msg(gyro_odometer.process_result(result), period_imu),), - None => (pack_dag_msg(reactor_helpers::create_empty_twist(current_timestamp), period_imu),) + Some(result) => (pack_dag_msg( + gyro_odometer.process_result(result), + period_imu, + ),), + None => (pack_dag_msg( + reactor_helpers::create_empty_twist(current_timestamp), + period_imu, + ),), } }, - vec![Cow::from("corrected_imu_data"),Cow::from("velocity_twist")], + vec![Cow::from("corrected_imu_data"), Cow::from("velocity_twist")], vec![Cow::from("twist_with_covariance")], SchedulerType::GEDF(5), ) @@ -594,9 +611,7 @@ fn parse_u64(field: &str) -> Result { if trimmed.is_empty() { return Ok(0); } - trimmed - .parse::() - .map_err(|_| "Failed to parse u64") + trimmed.parse::().map_err(|_| "Failed to parse u64") } fn parse_f64(field: &str) -> Result { @@ -604,9 +619,7 @@ fn parse_f64(field: &str) -> Result { if trimmed.is_empty() { return Ok(0.0); } - trimmed - .parse::() - .map_err(|_| "Failed to parse f64") + trimmed.parse::().map_err(|_| "Failed to parse f64") } // Returns monotonic uptime in nanoseconds clamped to u64. @@ -637,7 +650,10 @@ async fn periodic_udp_sender_task() { let mut socket = match socket_result { Ok(socket) => socket, Err(e) => { - log::error!("Periodic UDP sender task: failed to create UDP socket: {:?}", e); + log::error!( + "Periodic UDP sender task: failed to create UDP socket: {:?}", + e + ); return; } }; diff --git a/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs b/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs index cb2ff5e52..e94e39e6e 100644 --- a/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs +++ b/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs @@ -39,7 +39,10 @@ pub fn build_velocity_report_from_csv_row( timestamp: u64, ) -> VelocityReport { VelocityReport { - header: Header { frame_id, timestamp }, + header: Header { + frame_id, + timestamp, + }, longitudinal_velocity: row.longitudinal_velocity, lateral_velocity: row.lateral_velocity, heading_rate: row.heading_rate, diff --git a/applications/tests/test_dag/Cargo.toml b/applications/tests/test_dag/Cargo.toml index 739914e9d..afa70e28b 100644 --- a/applications/tests/test_dag/Cargo.toml +++ b/applications/tests/test_dag/Cargo.toml @@ -13,3 +13,7 @@ default-features = false [dependencies.awkernel_lib] path = "../../../awkernel_lib" default-features = false + +[features] +default = ["relax-get-period"] +relax-get-period = ["awkernel_async_lib/relax-get-period"] diff --git a/applications/tests/test_dag/src/lib.rs b/applications/tests/test_dag/src/lib.rs index f36b830d6..284f18a57 100644 --- a/applications/tests/test_dag/src/lib.rs +++ b/applications/tests/test_dag/src/lib.rs @@ -1,16 +1,55 @@ #![no_std] extern crate alloc; -use alloc::{borrow::Cow, sync::Arc, vec}; +use alloc::{borrow::Cow, vec}; use awkernel_async_lib::dag::{create_dag, finish_create_dags}; use awkernel_async_lib::scheduler::SchedulerType; +#[cfg(not(feature = "dag-no-period"))] use awkernel_async_lib::task::perf::get_period_count; use awkernel_lib::delay::wait_microsec; use core::time::Duration; -const LOG_ENABLE: bool = false; +const LOG_ENABLE: bool = true; const DATA_SIZE: usize = 128; +// Conditional message type based on features +#[cfg(not(feature = "dag-no-period"))] +type DagMsg = (T, u32); +#[cfg(feature = "dag-no-period")] +type DagMsg = T; + +// Conditional message packing/unpacking - dag-no-period フィーチャー有効時 +#[cfg(not(feature = "dag-no-period"))] +fn pack_dag_msg(value: T, period_id: u32) -> DagMsg { + (value, period_id) +} + +#[cfg(not(feature = "dag-no-period"))] +fn unpack_dag_msg(msg: DagMsg) -> (T, u32) { + msg +} + +#[cfg(not(feature = "dag-no-period"))] +fn current_period_id(dag_id: u32) -> u32 { + get_period_count(dag_id as usize) as u32 +} + +// dag-no-period フィーチャー無効時 (period_id は使わない) +#[cfg(feature = "dag-no-period")] +fn pack_dag_msg(value: T, _period_id: u32) -> DagMsg { + value +} + +#[cfg(feature = "dag-no-period")] +fn unpack_dag_msg(msg: DagMsg) -> (T, u32) { + (msg, 0) +} + +#[cfg(feature = "dag-no-period")] +fn current_period_id(_dag_id: u32) -> u32 { + 5 +} + pub async fn run() { wait_microsec(1000000); @@ -22,21 +61,16 @@ pub async fn run() { let dag = create_dag(); let dag_id = dag.get_id(); - dag.register_periodic_reactor::<_, ((Arc<[u8; DATA_SIZE]>, u32),)>( + dag.register_periodic_reactor::<_, (DagMsg,)>( "reactor_source_node".into(), - move || -> ((Arc<[u8; DATA_SIZE]>, u32),) { + move || -> (DagMsg,) { wait_microsec(exe_time); - let data: Arc<[u8; DATA_SIZE]> = Arc::new([0; DATA_SIZE]); - let period_id = get_period_count(dag_id as usize) as u32; + let number: i32 = 1; + let period_id = current_period_id(dag_id); if LOG_ENABLE { - log::debug!( - "Sending data[0]={}, period_id={}, size={} in reactor_source_node", - data[0], - period_id, - DATA_SIZE - ); + log::debug!("value={number} period={period_id} in reactor_source_node"); } - ((data, period_id),) + (pack_dag_msg(number, period_id),) }, vec![Cow::from("topic0")], SchedulerType::GEDF(5), @@ -44,14 +78,19 @@ pub async fn run() { ) .await; - dag.register_reactor::<_, ((Arc<[u8; DATA_SIZE]>, u32),), ((Arc<[u8; DATA_SIZE]>, u32), (Arc<[u8; DATA_SIZE]>, u32))>( + dag.register_reactor::<_, (DagMsg,), (DagMsg, DagMsg)>( "reactor_node1".into(), - move |((data, period),): ((Arc<[u8; DATA_SIZE]>, u32),)| -> ((Arc<[u8; DATA_SIZE]>, u32), (Arc<[u8; DATA_SIZE]>, u32)) { + move |(msg,): (DagMsg,)| -> (DagMsg, DagMsg) { + let (value, period) = unpack_dag_msg(msg); + let result = value + 1; if LOG_ENABLE { - log::debug!("Processing data[0]={}, period={}, size={} in reactor_node1", data[0], period, DATA_SIZE); + log::debug!("value={result} in reactor_node1"); } - ((data.clone(), period), (data, period)) + ( + pack_dag_msg(result, period), + pack_dag_msg(result + 1, period), + ) }, vec![Cow::from("topic0")], vec![Cow::from("topic1"), Cow::from("topic2")], @@ -59,18 +98,15 @@ pub async fn run() { ) .await; - dag.register_reactor::<_, ((Arc<[u8; DATA_SIZE]>, u32),), ((Arc<[u8; DATA_SIZE]>, u32),)>( + dag.register_reactor::<_, (DagMsg,), (DagMsg,)>( "reactor_node2".into(), - |((data, period),): ((Arc<[u8; DATA_SIZE]>, u32),)| -> ((Arc<[u8; DATA_SIZE]>, u32),) { + |(msg,): (DagMsg,)| -> (DagMsg,) { + let (value, period) = unpack_dag_msg(msg); + let result = value * 2; if LOG_ENABLE { - log::debug!( - "Processing data[0]={}, period={}, size={} in reactor_node2", - data[0], - period, - DATA_SIZE - ); + log::debug!("value={result} in reactor_node2"); } - ((data, period),) + (pack_dag_msg(result, period),) }, vec![Cow::from("topic1")], vec![Cow::from("topic3")], @@ -78,18 +114,15 @@ pub async fn run() { ) .await; - dag.register_reactor::<_, ((Arc<[u8; DATA_SIZE]>, u32),), ((Arc<[u8; DATA_SIZE]>, u32),)>( + dag.register_reactor::<_, (DagMsg,), (DagMsg,)>( "reactor_node3".into(), - |((data, period),): ((Arc<[u8; DATA_SIZE]>, u32),)| -> ((Arc<[u8; DATA_SIZE]>, u32),) { + |(msg,): (DagMsg,)| -> (DagMsg,) { + let (value, period) = unpack_dag_msg(msg); + let result = value * 3; if LOG_ENABLE { - log::debug!( - "Processing data[0]={}, period={}, size={} in reactor_node3", - data[0], - period, - DATA_SIZE - ); + log::debug!("value={result} in reactor_node3"); } - ((data, period),) + (pack_dag_msg(result, period),) }, vec![Cow::from("topic2")], vec![Cow::from("topic4")], @@ -97,11 +130,14 @@ pub async fn run() { ) .await; - dag.register_sink_reactor::<_, ((Arc<[u8; DATA_SIZE]>, u32), (Arc<[u8; DATA_SIZE]>, u32))>( + dag.register_sink_reactor::<_, (DagMsg, DagMsg)>( "reactor_node4".into(), - |((data1, period1), (data2, period2)): ((Arc<[u8; DATA_SIZE]>, u32), (Arc<[u8; DATA_SIZE]>, u32))| { + |(msg1, msg2): (DagMsg, DagMsg)| { + let (value1, _period1) = unpack_dag_msg(msg1); + let (value2, _period2) = unpack_dag_msg(msg2); + let result = value1 + value2; if LOG_ENABLE { - log::debug!("Received data1[0]={}, data2[0]={}, period1={}, period2={}, size={} in reactor_node4", data1[0], data2[0], period1, period2, DATA_SIZE); + log::debug!("value={result} in reactor_node4"); } }, vec![Cow::from("topic3"), Cow::from("topic4")], diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index 47a6bf2f3..3103c0e7f 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -136,18 +136,13 @@ pub trait GetPeriod { fn get_period(&self) -> u32; } +// When relax-get-period is NOT enabled, enforce period_id presence via GetPeriod #[cfg(not(feature = "relax-get-period"))] pub trait DagSubscriberItem: TupleSize + GetPeriod + Send {} #[cfg(not(feature = "relax-get-period"))] impl DagSubscriberItem for T where T: TupleSize + GetPeriod + Send {} -#[cfg(feature = "relax-get-period")] -pub trait DagSubscriberItem: TupleSize + Send {} - -#[cfg(feature = "relax-get-period")] -impl DagSubscriberItem for T where T: TupleSize + Send {} - #[cfg(not(feature = "relax-get-period"))] impl GetPeriod for ((V, u32),) { fn get_period(&self) -> u32 { @@ -234,6 +229,7 @@ impl GetPeriod } } +// When relax-get-period feature is enabled, provide a default implementation #[cfg(feature = "relax-get-period")] impl GetPeriod for T { fn get_period(&self) -> u32 { @@ -241,6 +237,18 @@ impl GetPeriod for T { } } +// When relax-get-period is enabled, DagSubscriberItem does not require GetPeriod +#[cfg(feature = "relax-get-period")] +pub trait DagSubscriberItem: TupleSize + Send {} + +#[cfg(feature = "relax-get-period")] +impl DagSubscriberItem for T where T: TupleSize + Send {} + +// #[cfg(feature = "relax-get-period")] +// impl DagSubscriberItem for T where T: TupleSize + Send {} + + + /// Convenience helper to extract period from a subscriber tuple by reference. pub fn get_period(args: &T) -> u32 { args.get_period() @@ -1110,8 +1118,7 @@ where let args: <::Subscribers as MultipleReceiver>::Item = subscribers.recv_all().await; - #[cfg(not(feature = "relax-get-period"))] - { + if crate::task::perf::ENABLE_PERIOD_TRACKING.load(core::sync::atomic::Ordering::Relaxed) { // [end] pubsub communication latency let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; let count_st = get_period(&args); @@ -1122,13 +1129,6 @@ where if let Some(task_id) = crate::task::get_current_task(cpu_id) { crate::task::set_task_period(task_id, Some(count_st)); } - // let noderecord = NodeRecord { - // period_count: count_st, - // dag_info: DagInfo { dag_id: dag_info.dag_id.clone(), node_id: dag_info.node_id.clone() }, - // }; - // node_period_count(noderecord.clone()); - // let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - // node_start(noderecord.clone(), start); let results = f(args); // [start] pubsub communication latency let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; @@ -1136,10 +1136,7 @@ where publishers .send_all_with_meta(results, 1, count_st as usize, dag_info.node_id) .await; - } - - #[cfg(feature = "relax-get-period")] - { + } else { let results = f(args); publishers.send_all(results).await; } @@ -1184,21 +1181,12 @@ where interval.tick().await; loop { - #[cfg(not(feature = "relax-get-period"))] - { + if crate::task::perf::ENABLE_PERIOD_TRACKING.load(core::sync::atomic::Ordering::Relaxed) { let index = get_period_count(dag_info.dag_id.clone() as usize) as usize; let cpu_id = awkernel_lib::cpu::cpu_id(); if let Some(task_id) = crate::task::get_current_task(cpu_id) { crate::task::set_task_period(task_id, Some(index as u32)); } - // [node] per node - // let noderecord = NodeRecord { - // period_count: index as u32, - // dag_info: DagInfo { dag_id: dag_info.dag_id.clone(), node_id: dag_info.node_id.clone() }, - // }; - // node_period_count(noderecord.clone()); - // let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - // node_start(noderecord.clone(), start); if index != 0 { let release_time = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; update_pre_send_outer_timestamp_at( @@ -1217,10 +1205,7 @@ where increment_period_count(dag_info.dag_id.clone() as usize); increment_pub_count(0); - } - - #[cfg(feature = "relax-get-period")] - { + } else { let results = f(); publishers.send_all(results).await; } @@ -1260,8 +1245,7 @@ where loop { let args: ::Item = subscribers.recv_all().await; - #[cfg(not(feature = "relax-get-period"))] - { + if crate::task::perf::ENABLE_PERIOD_TRACKING.load(core::sync::atomic::Ordering::Relaxed) { // [end] pubsub communication latency let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; let count_st = get_period(&args); @@ -1275,11 +1259,8 @@ where if let Some(task_id) = crate::task::get_current_task(cpu_id) { crate::task::set_task_period(task_id, Some(count_st)); } - // f(args); let timenow = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - let counter = get_sink_count(dag_info.dag_id.clone() as usize) as usize; if count_st != 0 { - // update_fin_recv_outer_timestamp_at(counter, timenow, dag_info.dag_id.clone()); update_fin_recv_outer_timestamp_at(count_st as usize, timenow, dag_info.dag_id); } increment_sink_count(dag_info.dag_id.clone() as usize); diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index 6eefb8118..db982e06e 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -471,7 +471,12 @@ pub mod perf { use array_macro::array; use awkernel_lib::{cpu::NUM_MAX_CPU, device_tree::node}; use core::ptr::{read_volatile, write_volatile}; - use core::sync::atomic::{AtomicU32, Ordering}; + use core::sync::atomic::{AtomicBool, AtomicU32, Ordering}; + + /// Flag to control whether period tracking is enabled + /// When false (with relax-get-period feature), period tracking is disabled to reduce BSS memory + /// When true (without relax-get-period feature), period tracking is enabled + pub static ENABLE_PERIOD_TRACKING: AtomicBool = AtomicBool::new(false); #[derive(Debug, Clone, PartialEq, Eq)] #[repr(u8)] diff --git a/userland/Cargo.toml b/userland/Cargo.toml index c6fac4eaa..95e969185 100644 --- a/userland/Cargo.toml +++ b/userland/Cargo.toml @@ -79,7 +79,7 @@ path = "../applications/tests/test_voluntary_preemption" optional = true [features] -default = ["test_autoware"] +default = ["test_dag"] perf = ["awkernel_services/perf"] # Evaluation applications From efb1f02361580abfa010a90b79785e64bbed9641 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Thu, 26 Mar 2026 09:43:11 +0900 Subject: [PATCH 08/60] fix: delete kernel dependics Signed-off-by: nokosaaan --- applications/tests/test_dag/Cargo.toml | 2 +- awkernel_async_lib/Cargo.toml | 1 - kernel/Cargo.toml | 1 - 3 files changed, 1 insertion(+), 3 deletions(-) diff --git a/applications/tests/test_dag/Cargo.toml b/applications/tests/test_dag/Cargo.toml index afa70e28b..c379ab109 100644 --- a/applications/tests/test_dag/Cargo.toml +++ b/applications/tests/test_dag/Cargo.toml @@ -15,5 +15,5 @@ path = "../../../awkernel_lib" default-features = false [features] -default = ["relax-get-period"] +default = [] relax-get-period = ["awkernel_async_lib/relax-get-period"] diff --git a/awkernel_async_lib/Cargo.toml b/awkernel_async_lib/Cargo.toml index 61fe6104d..209cd59b9 100644 --- a/awkernel_async_lib/Cargo.toml +++ b/awkernel_async_lib/Cargo.toml @@ -40,7 +40,6 @@ features = ["awkernel"] [features] default = [] -x86 = [] std = ["awkernel_lib/std", "no_preempt"] no_preempt = [] spinlock = ["awkernel_lib/spinlock"] diff --git a/kernel/Cargo.toml b/kernel/Cargo.toml index 02f8b3fec..9368f5904 100644 --- a/kernel/Cargo.toml +++ b/kernel/Cargo.toml @@ -82,7 +82,6 @@ no_std_unwinding = ["dep:unwinding"] debug = ["dep:gimli", "dep:addr2line"] x86 = [ "perf", - "awkernel_async_lib/x86", "no_std_unwinding", "awkernel_lib/x86", "dep:x86_64", From b1b921b179d492411c3cfda7b1a8f01dab2624f9 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Thu, 26 Mar 2026 10:00:03 +0900 Subject: [PATCH 09/60] fix: no period with test_autoware Signed-off-by: nokosaaan --- applications/tests/test_autoware/Cargo.toml | 7 +- applications/tests/test_autoware/src/lib.rs | 121 +++++--------------- userland/Cargo.toml | 2 +- 3 files changed, 32 insertions(+), 98 deletions(-) diff --git a/applications/tests/test_autoware/Cargo.toml b/applications/tests/test_autoware/Cargo.toml index e625a69fb..5e7075844 100644 --- a/applications/tests/test_autoware/Cargo.toml +++ b/applications/tests/test_autoware/Cargo.toml @@ -7,16 +7,11 @@ edition = "2021" path = "src/lib.rs" crate-type = ["rlib"] -[features] -default = ["dag-no-period"] -dag-send-period = [] -dag-no-period = ["awkernel_async_lib/relax-get-period"] - [dependencies] log = "0.4" libm = "0.2" csv-core = "0.1" -awkernel_async_lib = { path = "../../../awkernel_async_lib", default-features = false } +awkernel_async_lib = { path = "../../../awkernel_async_lib", default-features = false, features = ["relax-get-period"] } awkernel_lib = { path = "../../../awkernel_lib", default-features = false } imu_driver = { path = "./imu_driver", default-features = false } imu_corrector = { path = "./imu_corrector", default-features = false } diff --git a/applications/tests/test_autoware/src/lib.rs b/applications/tests/test_autoware/src/lib.rs index e0df1e920..b0f5a2f9e 100644 --- a/applications/tests/test_autoware/src/lib.rs +++ b/applications/tests/test_autoware/src/lib.rs @@ -5,8 +5,6 @@ use alloc::{borrow::Cow, format, string::String, vec, vec::Vec}; use awkernel_async_lib::dag::{create_dag, finish_create_dags}; use awkernel_async_lib::net::IpAddr; use awkernel_async_lib::scheduler::SchedulerType; -#[cfg(feature = "dag-send-period")] -use awkernel_async_lib::task::perf::get_period_count; use awkernel_lib::delay::wait_microsec; use awkernel_lib::sync::mutex::{MCSNode, Mutex}; use core::net::Ipv4Addr; @@ -62,41 +60,6 @@ static mut VELOCITY_CSV_DATA: Option> = None; static IMU_CSV_COUNT: Mutex = Mutex::new(0); static VELOCITY_CSV_COUNT: Mutex = Mutex::new(0); -#[cfg(feature = "dag-send-period")] -type DagMsg = (T, u32); -#[cfg(not(feature = "dag-send-period"))] -type DagMsg = T; - -#[cfg(feature = "dag-send-period")] -fn pack_dag_msg(value: T, period_id: u32) -> DagMsg { - (value, period_id) -} - -#[cfg(not(feature = "dag-send-period"))] -fn pack_dag_msg(value: T, _period_id: u32) -> DagMsg { - value -} - -#[cfg(feature = "dag-send-period")] -fn unpack_dag_msg(msg: DagMsg) -> (T, u32) { - msg -} - -#[cfg(not(feature = "dag-send-period"))] -fn unpack_dag_msg(msg: DagMsg) -> (T, u32) { - (msg, 0) -} - -#[cfg(feature = "dag-send-period")] -fn current_period_id(dag_id: u32) -> u32 { - get_period_count(dag_id as usize) as u32 -} - -#[cfg(not(feature = "dag-send-period"))] -fn current_period_id(_dag_id: u32) -> u32 { - 0 -} - pub async fn run() { wait_microsec(1000000); @@ -109,15 +72,10 @@ pub async fn run() { let dag = create_dag(); let dag_id = dag.get_id(); - dag.register_periodic_reactor::<_, (DagMsg, DagMsg, DagMsg)>( + dag.register_periodic_reactor::<_, (i32, i32, i32)>( "start_dummy_data".into(), - move || -> (DagMsg, DagMsg, DagMsg) { - let period_id = current_period_id(dag_id); - ( - pack_dag_msg(1, period_id), - pack_dag_msg(2, period_id), - pack_dag_msg(3, period_id), - ) + move || -> (i32, i32, i32) { + (1, 2, 3) }, vec![ Cow::from("start_imu"), @@ -129,10 +87,9 @@ pub async fn run() { ) .await; - dag.register_reactor::<_, (DagMsg,), (DagMsg,)>( + dag.register_reactor::<_, (i32,), (ImuMsg,)>( "imu_driver".into(), - move |(start_msg,): (DagMsg,)| -> (DagMsg,) { - let (_a, period_id) = unpack_dag_msg(start_msg); + move |(_start_msg,): (i32,)| -> (ImuMsg,) { let mut node = MCSNode::new(); let mut count_guard = IMU_CSV_COUNT.lock(&mut node); let count = *count_guard; @@ -176,7 +133,7 @@ pub async fn run() { ); } - (pack_dag_msg(imu_msg, period_id),) + (imu_msg,) }, vec![Cow::from("start_imu")], vec![Cow::from("imu_data")], @@ -184,10 +141,9 @@ pub async fn run() { ) .await; - dag.register_reactor::<_, (DagMsg,), (DagMsg,)>( + dag.register_reactor::<_, (i32,), (TwistWithCovarianceStamped,)>( "vehicle_velocity_converter".into(), - move |(start_msg,): (DagMsg,)| -> (DagMsg,) { - let (_b, period_id) = unpack_dag_msg(start_msg); + move |(_start_msg,): (i32,)| -> (TwistWithCovarianceStamped,) { let converter = VehicleVelocityConverter::default(); let mut node = MCSNode::new(); @@ -219,7 +175,7 @@ pub async fn run() { ); } - (pack_dag_msg(twist_msg, period_id),) + (twist_msg,) }, vec![Cow::from("start_vel")], vec![Cow::from("velocity_twist")], @@ -227,13 +183,12 @@ pub async fn run() { ) .await; - dag.register_reactor::<_, (DagMsg,), (DagMsg,)>( + dag.register_reactor::<_, (ImuMsg,), (ImuWithCovariance,)>( "imu_corrector".into(), - |(imu_msg,): (DagMsg,)| -> (DagMsg,) { - let (imu_msg, period_id) = unpack_dag_msg(imu_msg); + |(imu_msg,): (ImuMsg,)| -> (ImuWithCovariance,) { let corrector = ImuCorrector::new(); let corrected = corrector.correct_imu_with_covariance(&imu_msg, None); - (pack_dag_msg(corrected, period_id),) + (corrected,) }, vec![Cow::from("imu_data")], vec![Cow::from("corrected_imu_data")], @@ -242,27 +197,22 @@ pub async fn run() { .await; dag.register_reactor::<_, ( - DagMsg, - DagMsg, - ), (DagMsg,)>( + ImuWithCovariance, + TwistWithCovarianceStamped, + ), (TwistWithCovarianceStamped,)>( "gyro_odometer".into(), - |(imu_msg, vehicle_msg): ( - DagMsg, - DagMsg, + |(imu_with_cov, vehicle_twist): ( + ImuWithCovariance, + TwistWithCovarianceStamped, )| - -> (DagMsg,) { - let (imu_with_cov, period_imu) = unpack_dag_msg(imu_msg); - let (vehicle_twist, _period_twist) = unpack_dag_msg(vehicle_msg); + -> (TwistWithCovarianceStamped,) { let current_timestamp = imu_with_cov.header.timestamp; let current_time = get_awkernel_uptime_timestamp(); let gyro_odometer = match gyro_odometer::get_or_initialize() { Ok(core) => core, Err(_) => { - return (pack_dag_msg( - reactor_helpers::create_empty_twist(current_timestamp), - period_imu, - ),); + return (reactor_helpers::create_empty_twist(current_timestamp),); } }; @@ -270,14 +220,8 @@ pub async fn run() { gyro_odometer.add_imu(imu_with_cov); match gyro_odometer.process_and_get_result(current_time) { - Some(result) => (pack_dag_msg( - gyro_odometer.process_result(result), - period_imu, - ),), - None => (pack_dag_msg( - reactor_helpers::create_empty_twist(current_timestamp), - period_imu, - ),), + Some(result) => (gyro_odometer.process_result(result),), + None => (reactor_helpers::create_empty_twist(current_timestamp),), } }, vec![Cow::from("corrected_imu_data"), Cow::from("velocity_twist")], @@ -286,10 +230,9 @@ pub async fn run() { ) .await; - dag.register_reactor::<_, (DagMsg,), (DagMsg,)>( + dag.register_reactor::<_, (i32,), (Pose,)>( "pose_dummy_generator".into(), - move |(start_msg,): (DagMsg,)| -> (DagMsg,) { - let (_counter, period_id) = unpack_dag_msg(start_msg); + move |(_start_msg,): (i32,)| -> (Pose,) { let x = 0.0; let y = 0.0; let z = 0.0; @@ -304,7 +247,7 @@ pub async fn run() { }, }; - (pack_dag_msg(pose, period_id),) + (pose,) }, vec![Cow::from("start_pose")], vec![Cow::from("dummy_pose")], @@ -312,11 +255,9 @@ pub async fn run() { ) .await; - dag.register_reactor::<_, (DagMsg, DagMsg), (DagMsg, DagMsg)>( + dag.register_reactor::<_, (Pose, TwistWithCovarianceStamped), (Pose, EKFOdometry)>( "ekf_localizer".into(), - |(pose_msg, twist_msg): (DagMsg, DagMsg)| -> (DagMsg, DagMsg) { - let (pose, period_pose) = unpack_dag_msg(pose_msg); - let (twist, _period_twist) = unpack_dag_msg(twist_msg); + |(pose, twist): (Pose, TwistWithCovarianceStamped)| -> (Pose, EKFOdometry) { let ekf = get_or_initialize_default_module(); static mut INITIALIZED: bool = false; @@ -365,7 +306,7 @@ pub async fn run() { }, }; - (pack_dag_msg(ekf_pose, period_pose), pack_dag_msg(odometry, period_pose)) + (ekf_pose, odometry) }, vec![Cow::from("dummy_pose"), Cow::from("twist_with_covariance")], vec![Cow::from("estimated_pose"), Cow::from("ekf_odometry")], @@ -373,11 +314,9 @@ pub async fn run() { ) .await; - dag.register_sink_reactor::<_, (DagMsg, DagMsg)>( + dag.register_sink_reactor::<_, (Pose, EKFOdometry)>( "ekf_sink".into(), - move |(pose_msg, odom_msg): (DagMsg, DagMsg)| { - let (_pose, _period_pose) = unpack_dag_msg(pose_msg); - let (ekf_odom, _period_odom) = unpack_dag_msg(odom_msg); + move |(_pose, ekf_odom): (Pose, EKFOdometry)| { let json_data = format!( r#"{{"header":{{"frame_id":"{}","timestamp":{}}},"child_frame_id":"{}","pose":{{"pose":{{"position":{{"x":{:.6},"y":{:.6},"z":{:.6}}},"orientation":{{"x":{:.6},"y":{:.6},"z":{:.6},"w":{:.6}}}}},"covariance":[{}]}},"twist":{{"twist":{{"linear":{{"x":{:.6},"y":{:.6},"z":{:.6}}},"angular":{{"x":{:.6},"y":{:.6},"z":{:.6}}}}},"covariance":[{}]}}}}"#, diff --git a/userland/Cargo.toml b/userland/Cargo.toml index 95e969185..c6fac4eaa 100644 --- a/userland/Cargo.toml +++ b/userland/Cargo.toml @@ -79,7 +79,7 @@ path = "../applications/tests/test_voluntary_preemption" optional = true [features] -default = ["test_dag"] +default = ["test_autoware"] perf = ["awkernel_services/perf"] # Evaluation applications From 1b18749b26c1ca3890d1ab9376d59b492d26b543 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 27 Mar 2026 18:44:26 +0900 Subject: [PATCH 10/60] fix: reduce impl for get_period with macro Signed-off-by: nokosaaan --- awkernel_async_lib/src/dag.rs | 276 ++++++++++++---------------------- 1 file changed, 94 insertions(+), 182 deletions(-) diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index 3103c0e7f..da12e208d 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -84,7 +84,6 @@ use alloc::{ vec::Vec, }; use awkernel_lib::sync::mutex::{MCSNode, Mutex}; -use core::sync::atomic::Ordering; use core::{future::Future, pin::Pin, time::Duration}; #[cfg(feature = "perf")] @@ -106,150 +105,53 @@ pub trait TupleSize { const SIZE: usize; } -macro_rules! impl_tuple_size { - (@count) => { 0 }; - (@count $_head:ident $($tail:ident)*) => { 1 + impl_tuple_size!(@count $($tail)*) }; - - ($($T:ident),*) => { - impl<$($T),*> TupleSize for ($($T,)*) { - const SIZE: usize = impl_tuple_size!(@count $($T)*); - } - }; -} - -impl_tuple_size!(); -impl_tuple_size!(T1); -impl_tuple_size!(T1, T2); -impl_tuple_size!(T1, T2, T3); -impl_tuple_size!(T1, T2, T3, T4); -impl_tuple_size!(T1, T2, T3, T4, T5); -impl_tuple_size!(T1, T2, T3, T4, T5, T6); -impl_tuple_size!(T1, T2, T3, T4, T5, T6, T7); -impl_tuple_size!(T1, T2, T3, T4, T5, T6, T7, T8); - -// Trait to extract the period (u32) carried in the last element of -// subscriber tuples. Each subscriber tuple element is expected to be -// a `(value, u32)` pair; implementations below return the u32 from -// the last tuple element. The trait is public so `get_period` bounds -// in other functions can reference it. pub trait GetPeriod { fn get_period(&self) -> u32; } -// When relax-get-period is NOT enabled, enforce period_id presence via GetPeriod -#[cfg(not(feature = "relax-get-period"))] -pub trait DagSubscriberItem: TupleSize + GetPeriod + Send {} - -#[cfg(not(feature = "relax-get-period"))] -impl DagSubscriberItem for T where T: TupleSize + GetPeriod + Send {} - -#[cfg(not(feature = "relax-get-period"))] -impl GetPeriod for ((V, u32),) { - fn get_period(&self) -> u32 { - self.0 .1 - } -} - -#[cfg(not(feature = "relax-get-period"))] -impl GetPeriod for ((V1, u32), (V2, u32)) { - fn get_period(&self) -> u32 { - self.1 .1 - } -} - -#[cfg(not(feature = "relax-get-period"))] -impl GetPeriod for ((V1, u32), (V2, u32), (V3, u32)) { - fn get_period(&self) -> u32 { - self.2 .1 - } -} +macro_rules! impl_tuple_traits { + () => { + impl TupleSize for () { + const SIZE: usize = 0; + } + }; -#[cfg(not(feature = "relax-get-period"))] -impl GetPeriod for ((V1, u32), (V2, u32), (V3, u32), (V4, u32)) { - fn get_period(&self) -> u32 { - self.3 .1 - } -} + ($last_idx:tt => $($T:ident),+) => { + impl<$($T),+> TupleSize for ($($T,)+) { + const SIZE: usize = $last_idx + 1; + } -#[cfg(not(feature = "relax-get-period"))] -impl GetPeriod for ((V1, u32), (V2, u32), (V3, u32), (V4, u32), (V5, u32)) { - fn get_period(&self) -> u32 { - self.4 .1 - } + #[cfg(not(feature = "relax-get-period"))] + impl<$($T),+> GetPeriod for ($(($T, u32),)+) { + fn get_period(&self) -> u32 { + self.$last_idx .1 + } + } + }; } -#[cfg(not(feature = "relax-get-period"))] -impl GetPeriod - for ( - (V1, u32), - (V2, u32), - (V3, u32), - (V4, u32), - (V5, u32), - (V6, u32), - ) -{ - fn get_period(&self) -> u32 { - self.5 .1 - } -} +impl_tuple_traits!(); +impl_tuple_traits!(0 => T1); +impl_tuple_traits!(1 => T1, T2); +impl_tuple_traits!(2 => T1, T2, T3); +impl_tuple_traits!(3 => T1, T2, T3, T4); +impl_tuple_traits!(4 => T1, T2, T3, T4, T5); +impl_tuple_traits!(5 => T1, T2, T3, T4, T5, T6); +impl_tuple_traits!(6 => T1, T2, T3, T4, T5, T6, T7); +impl_tuple_traits!(7 => T1, T2, T3, T4, T5, T6, T7, T8); #[cfg(not(feature = "relax-get-period"))] -impl GetPeriod - for ( - (V1, u32), - (V2, u32), - (V3, u32), - (V4, u32), - (V5, u32), - (V6, u32), - (V7, u32), - ) -{ - fn get_period(&self) -> u32 { - self.6 .1 - } -} +pub trait DagSubscriberItem: TupleSize + GetPeriod + Send {} #[cfg(not(feature = "relax-get-period"))] -impl GetPeriod - for ( - (V1, u32), - (V2, u32), - (V3, u32), - (V4, u32), - (V5, u32), - (V6, u32), - (V7, u32), - (V8, u32), - ) -{ - fn get_period(&self) -> u32 { - self.7 .1 - } -} - -// When relax-get-period feature is enabled, provide a default implementation -#[cfg(feature = "relax-get-period")] -impl GetPeriod for T { - fn get_period(&self) -> u32 { - 0 - } -} +impl DagSubscriberItem for T where T: TupleSize + GetPeriod + Send {} -// When relax-get-period is enabled, DagSubscriberItem does not require GetPeriod #[cfg(feature = "relax-get-period")] pub trait DagSubscriberItem: TupleSize + Send {} #[cfg(feature = "relax-get-period")] impl DagSubscriberItem for T where T: TupleSize + Send {} - -// #[cfg(feature = "relax-get-period")] -// impl DagSubscriberItem for T where T: TupleSize + Send {} - - - -/// Convenience helper to extract period from a subscriber tuple by reference. +#[cfg(not(feature = "relax-get-period"))] pub fn get_period(args: &T) -> u32 { args.get_period() } @@ -1119,23 +1021,26 @@ where subscribers.recv_all().await; if crate::task::perf::ENABLE_PERIOD_TRACKING.load(core::sync::atomic::Ordering::Relaxed) { - // [end] pubsub communication latency - let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - let count_st = get_period(&args); - subscribe_timestamp_at(count_st as usize, end, 1, dag_info.node_id.clone()); - - // period count from message to TaskInfo - let cpu_id = awkernel_lib::cpu::cpu_id(); - if let Some(task_id) = crate::task::get_current_task(cpu_id) { - crate::task::set_task_period(task_id, Some(count_st)); + #[cfg(not(feature = "relax-get-period"))] + { + // [end] pubsub communication latency + let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + let count_st = get_period(&args); + subscribe_timestamp_at(count_st as usize, end, 1, dag_info.node_id.clone()); + + // period count from message to TaskInfo + let cpu_id = awkernel_lib::cpu::cpu_id(); + if let Some(task_id) = crate::task::get_current_task(cpu_id) { + crate::task::set_task_period(task_id, Some(count_st)); + } + let results = f(args); + // [start] pubsub communication latency + let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + publish_timestamp_at(count_st as usize, end, 1, dag_info.node_id.clone()); + publishers + .send_all_with_meta(results, 1, count_st as usize, dag_info.node_id) + .await; } - let results = f(args); - // [start] pubsub communication latency - let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - publish_timestamp_at(count_st as usize, end, 1, dag_info.node_id.clone()); - publishers - .send_all_with_meta(results, 1, count_st as usize, dag_info.node_id) - .await; } else { let results = f(args); publishers.send_all(results).await; @@ -1182,29 +1087,32 @@ where loop { if crate::task::perf::ENABLE_PERIOD_TRACKING.load(core::sync::atomic::Ordering::Relaxed) { - let index = get_period_count(dag_info.dag_id.clone() as usize) as usize; - let cpu_id = awkernel_lib::cpu::cpu_id(); - if let Some(task_id) = crate::task::get_current_task(cpu_id) { - crate::task::set_task_period(task_id, Some(index as u32)); + #[cfg(not(feature = "relax-get-period"))] + { + let index = get_period_count(dag_info.dag_id.clone() as usize) as usize; + let cpu_id = awkernel_lib::cpu::cpu_id(); + if let Some(task_id) = crate::task::get_current_task(cpu_id) { + crate::task::set_task_period(task_id, Some(index as u32)); + } + if index != 0 { + let release_time = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + update_pre_send_outer_timestamp_at( + index, + release_time, + dag_info.dag_id.clone(), + ); + } + let results = f(); + // [start] pubsub communication latency + let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + publish_timestamp_at(index, end, 0, dag_info.node_id); + publishers + .send_all_with_meta(results, 0, index, dag_info.node_id) + .await; + + increment_period_count(dag_info.dag_id.clone() as usize); + increment_pub_count(0); } - if index != 0 { - let release_time = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - update_pre_send_outer_timestamp_at( - index, - release_time, - dag_info.dag_id.clone(), - ); - } - let results = f(); - // [start] pubsub communication latency - let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - publish_timestamp_at(index, end, 0, dag_info.node_id); - publishers - .send_all_with_meta(results, 0, index, dag_info.node_id) - .await; - - increment_period_count(dag_info.dag_id.clone() as usize); - increment_pub_count(0); } else { let results = f(); publishers.send_all(results).await; @@ -1246,24 +1154,28 @@ where let args: ::Item = subscribers.recv_all().await; if crate::task::perf::ENABLE_PERIOD_TRACKING.load(core::sync::atomic::Ordering::Relaxed) { - // [end] pubsub communication latency - let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - let count_st = get_period(&args); - subscribe_timestamp_at(count_st as usize, end, 2, dag_info.node_id.clone()); - increment_pub_count(1); - increment_sub_count(1); - increment_sub_count(2); - - // period count from message to TaskInfo - let cpu_id = awkernel_lib::cpu::cpu_id(); - if let Some(task_id) = crate::task::get_current_task(cpu_id) { - crate::task::set_task_period(task_id, Some(count_st)); - } - let timenow = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - if count_st != 0 { - update_fin_recv_outer_timestamp_at(count_st as usize, timenow, dag_info.dag_id); + #[cfg(not(feature = "relax-get-period"))] + { + // [end] pubsub communication latency + let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + let count_st = get_period(&args); + subscribe_timestamp_at(count_st as usize, end, 2, dag_info.node_id.clone()); + increment_pub_count(1); + increment_sub_count(1); + increment_sub_count(2); + + // period count from message to TaskInfo + let cpu_id = awkernel_lib::cpu::cpu_id(); + if let Some(task_id) = crate::task::get_current_task(cpu_id) { + crate::task::set_task_period(task_id, Some(count_st)); + } + let timenow = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + if count_st != 0 { + update_fin_recv_outer_timestamp_at(count_st as usize, timenow, dag_info.dag_id); + } + increment_sink_count(dag_info.dag_id.clone() as usize); } - increment_sink_count(dag_info.dag_id.clone() as usize); + } f(args); } From 3c112f9f3d36520cb767a7684505dcb9f81cbfe9 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 27 Mar 2026 18:46:32 +0900 Subject: [PATCH 11/60] fix: reset test_dag Signed-off-by: nokosaaan --- applications/tests/test_dag/Cargo.toml | 4 -- applications/tests/test_dag/src/lib.rs | 97 ++++++-------------------- 2 files changed, 23 insertions(+), 78 deletions(-) diff --git a/applications/tests/test_dag/Cargo.toml b/applications/tests/test_dag/Cargo.toml index c379ab109..739914e9d 100644 --- a/applications/tests/test_dag/Cargo.toml +++ b/applications/tests/test_dag/Cargo.toml @@ -13,7 +13,3 @@ default-features = false [dependencies.awkernel_lib] path = "../../../awkernel_lib" default-features = false - -[features] -default = [] -relax-get-period = ["awkernel_async_lib/relax-get-period"] diff --git a/applications/tests/test_dag/src/lib.rs b/applications/tests/test_dag/src/lib.rs index 284f18a57..a7330457f 100644 --- a/applications/tests/test_dag/src/lib.rs +++ b/applications/tests/test_dag/src/lib.rs @@ -4,51 +4,10 @@ extern crate alloc; use alloc::{borrow::Cow, vec}; use awkernel_async_lib::dag::{create_dag, finish_create_dags}; use awkernel_async_lib::scheduler::SchedulerType; -#[cfg(not(feature = "dag-no-period"))] -use awkernel_async_lib::task::perf::get_period_count; use awkernel_lib::delay::wait_microsec; use core::time::Duration; const LOG_ENABLE: bool = true; -const DATA_SIZE: usize = 128; - -// Conditional message type based on features -#[cfg(not(feature = "dag-no-period"))] -type DagMsg = (T, u32); -#[cfg(feature = "dag-no-period")] -type DagMsg = T; - -// Conditional message packing/unpacking - dag-no-period フィーチャー有効時 -#[cfg(not(feature = "dag-no-period"))] -fn pack_dag_msg(value: T, period_id: u32) -> DagMsg { - (value, period_id) -} - -#[cfg(not(feature = "dag-no-period"))] -fn unpack_dag_msg(msg: DagMsg) -> (T, u32) { - msg -} - -#[cfg(not(feature = "dag-no-period"))] -fn current_period_id(dag_id: u32) -> u32 { - get_period_count(dag_id as usize) as u32 -} - -// dag-no-period フィーチャー無効時 (period_id は使わない) -#[cfg(feature = "dag-no-period")] -fn pack_dag_msg(value: T, _period_id: u32) -> DagMsg { - value -} - -#[cfg(feature = "dag-no-period")] -fn unpack_dag_msg(msg: DagMsg) -> (T, u32) { - (msg, 0) -} - -#[cfg(feature = "dag-no-period")] -fn current_period_id(_dag_id: u32) -> u32 { - 5 -} pub async fn run() { wait_microsec(1000000); @@ -59,18 +18,16 @@ pub async fn run() { log::debug!("period is {} [ns]", period.as_nanos()); let dag = create_dag(); - let dag_id = dag.get_id(); - dag.register_periodic_reactor::<_, (DagMsg,)>( + dag.register_periodic_reactor::<_, (i32,)>( "reactor_source_node".into(), - move || -> (DagMsg,) { + move || -> (i32,) { wait_microsec(exe_time); let number: i32 = 1; - let period_id = current_period_id(dag_id); if LOG_ENABLE { - log::debug!("value={number} period={period_id} in reactor_source_node"); + log::debug!("value={number} in reactor_source_node"); } - (pack_dag_msg(number, period_id),) + (number,) }, vec![Cow::from("topic0")], SchedulerType::GEDF(5), @@ -78,19 +35,15 @@ pub async fn run() { ) .await; - dag.register_reactor::<_, (DagMsg,), (DagMsg, DagMsg)>( + dag.register_reactor::<_, (i32,), (i32, i32)>( "reactor_node1".into(), - move |(msg,): (DagMsg,)| -> (DagMsg, DagMsg) { - let (value, period) = unpack_dag_msg(msg); - let result = value + 1; + |(a,): (i32,)| -> (i32, i32) { + let value = a + 1; if LOG_ENABLE { - log::debug!("value={result} in reactor_node1"); + log::debug!("value={value} in reactor_node1"); } - ( - pack_dag_msg(result, period), - pack_dag_msg(result + 1, period), - ) + (value, value + 1) }, vec![Cow::from("topic0")], vec![Cow::from("topic1"), Cow::from("topic2")], @@ -98,15 +51,14 @@ pub async fn run() { ) .await; - dag.register_reactor::<_, (DagMsg,), (DagMsg,)>( + dag.register_reactor::<_, (i32,), (i32,)>( "reactor_node2".into(), - |(msg,): (DagMsg,)| -> (DagMsg,) { - let (value, period) = unpack_dag_msg(msg); - let result = value * 2; + |(a,): (i32,)| -> (i32,) { + let value = a * 2; if LOG_ENABLE { - log::debug!("value={result} in reactor_node2"); + log::debug!("value={value} in reactor_node2"); } - (pack_dag_msg(result, period),) + (value,) }, vec![Cow::from("topic1")], vec![Cow::from("topic3")], @@ -114,15 +66,14 @@ pub async fn run() { ) .await; - dag.register_reactor::<_, (DagMsg,), (DagMsg,)>( + dag.register_reactor::<_, (i32,), (i32,)>( "reactor_node3".into(), - |(msg,): (DagMsg,)| -> (DagMsg,) { - let (value, period) = unpack_dag_msg(msg); - let result = value * 3; + |(a,): (i32,)| -> (i32,) { + let value = a * 3; if LOG_ENABLE { - log::debug!("value={result} in reactor_node3"); + log::debug!("value={value} in reactor_node3"); } - (pack_dag_msg(result, period),) + (value,) }, vec![Cow::from("topic2")], vec![Cow::from("topic4")], @@ -130,14 +81,12 @@ pub async fn run() { ) .await; - dag.register_sink_reactor::<_, (DagMsg, DagMsg)>( + dag.register_sink_reactor::<_, (i32, i32)>( "reactor_node4".into(), - |(msg1, msg2): (DagMsg, DagMsg)| { - let (value1, _period1) = unpack_dag_msg(msg1); - let (value2, _period2) = unpack_dag_msg(msg2); - let result = value1 + value2; + |(a, b): (i32, i32)| { + let value = a + b; if LOG_ENABLE { - log::debug!("value={result} in reactor_node4"); + log::debug!("value={value} in reactor_node4"); } }, vec![Cow::from("topic3"), Cow::from("topic4")], From 1cfa9eda0a5db3517f13bd5137e7fcd5fdad8044 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 3 Apr 2026 16:52:29 +0900 Subject: [PATCH 12/60] fix: delete unnecessary comments Signed-off-by: nokosaaan --- .../test_autoware/ekf_localizer/Cargo.toml | 2 + .../test_autoware/ekf_localizer/README.md | 150 -------------- .../test_autoware/ekf_localizer/src/lib.rs | 111 ++--------- .../test_autoware/gyro_odometer/src/lib.rs | 67 +------ .../test_autoware/imu_corrector/src/lib.rs | 188 +++++------------- .../tests/test_autoware/imu_driver/src/lib.rs | 110 +--------- applications/tests/test_autoware/src/lib.rs | 20 +- .../vehicle_velocity_converter/src/lib.rs | 43 +--- 8 files changed, 83 insertions(+), 608 deletions(-) delete mode 100644 applications/tests/test_autoware/ekf_localizer/README.md diff --git a/applications/tests/test_autoware/ekf_localizer/Cargo.toml b/applications/tests/test_autoware/ekf_localizer/Cargo.toml index b81a101b1..92111e0cb 100644 --- a/applications/tests/test_autoware/ekf_localizer/Cargo.toml +++ b/applications/tests/test_autoware/ekf_localizer/Cargo.toml @@ -8,6 +8,8 @@ edition = "2021" libm = "0.2" nalgebra = { version = "0.32", default-features = false} approx = "0.5" +imu_driver = { path = "../imu_driver", default-features = false } +vehicle_velocity_converter = { path = "../vehicle_velocity_converter", default-features = false} # Optional: for better math functions micromath = "2.1" \ No newline at end of file diff --git a/applications/tests/test_autoware/ekf_localizer/README.md b/applications/tests/test_autoware/ekf_localizer/README.md deleted file mode 100644 index f84837adc..000000000 --- a/applications/tests/test_autoware/ekf_localizer/README.md +++ /dev/null @@ -1,150 +0,0 @@ -# EKF Localizer for awkernel - -This is a no_std Rust implementation of the EKF (Extended Kalman Filter) Localizer for awkernel, extracted from Autoware's EKF Localizer. - -## Features - -- **no_std compatible**: Can run in embedded environments without standard library -- **TF publishing support**: Provides transform data for ROS2 tf broadcasting -- **EKF state estimation**: Estimates vehicle pose (x, y, yaw) and velocity (vx, wz) -- **Yaw bias estimation**: Optional yaw bias estimation for improved accuracy -- **Simple 1D filters**: For z, roll, and pitch estimation - -## State Vector - -The EKF state vector contains 6 elements: -- `x`: X position [m] -- `y`: Y position [m] -- `yaw`: Yaw angle [rad] -- `yaw_bias`: Yaw bias [rad] -- `vx`: X velocity [m/s] -- `wz`: Z angular velocity [rad/s] - -## Usage - -### Basic Usage - -```rust -use ekf_localizer::{EKFModule, EKFParameters, Pose, Transform, Point3D, Quaternion}; - -// Create EKF parameters -let params = EKFParameters::default(); - -// Create EKF module -let mut ekf = EKFModule::new(params); - -// Initialize with initial pose -let initial_pose = Pose { - position: Point3D { x: 0.0, y: 0.0, z: 0.0 }, - orientation: Quaternion { x: 0.0, y: 0.0, z: 0.0, w: 1.0 }, -}; - -let transform = Transform { - translation: Point3D { x: 0.0, y: 0.0, z: 0.0 }, - rotation: Quaternion { x: 0.0, y: 0.0, z: 0.0, w: 1.0 }, -}; - -ekf.initialize(initial_pose, transform); - -// Prediction step -ekf.predict(0.01); // dt = 10ms - -// Get current pose for tf publishing -let pose = ekf.get_current_pose(false); -let transform = ekf.get_transform("base_link"); - -// Get covariance for uncertainty representation -let pose_covariance = ekf.get_current_pose_covariance(); -let twist_covariance = ekf.get_current_twist_covariance(); -``` - -### TF Publishing - -To publish transforms for ROS2 tf, use the `get_transform` method: - -```rust -// Get transform from map to base_link -let transform = ekf.get_transform("base_link"); - -// The transform contains: -// - translation: (x, y, z) position -// - rotation: quaternion orientation - -// Use this data to publish tf2_msgs/TransformStamped -``` - -### Integration with awkernel Reactor API - -The EKF module is designed to be used with awkernel's reactor API. You can create a separate file for pub/sub implementation: - -```rust -// In your reactor implementation file -use ekf_localizer::EKFModule; - -pub struct EKFLocalizerReactor { - ekf: EKFModule, - // Add other fields for pub/sub -} - -impl EKFLocalizerReactor { - pub fn new() -> Self { - let params = EKFParameters::default(); - let ekf = EKFModule::new(params); - - Self { - ekf, - // Initialize other fields - } - } - - pub fn timer_callback(&mut self) { - // Predict step - self.ekf.predict(0.01); - - // Get transform for publishing - let transform = self.ekf.get_transform("base_link"); - - // Publish transform using awkernel reactor API - // self.publish_tf(transform); - } -} -``` - -## Parameters - -Key parameters that can be tuned: - -- `enable_yaw_bias_estimation`: Enable/disable yaw bias estimation -- `extend_state_step`: Number of extended state steps for delay compensation -- `proc_stddev_vx_c`: Process noise standard deviation for velocity -- `proc_stddev_wz_c`: Process noise standard deviation for angular velocity -- `proc_stddev_yaw_c`: Process noise standard deviation for yaw -- `z_filter_proc_dev`: Process noise for z filter -- `roll_filter_proc_dev`: Process noise for roll filter -- `pitch_filter_proc_dev`: Process noise for pitch filter - -## Dependencies - -- `libm`: Mathematical functions for no_std -- `nalgebra`: Linear algebra operations -- `approx`: Approximate equality comparisons for tests - -## Building - -```bash -cd ~/azumi-lab/awkernel_1/ekf_localizer -cargo build --target thumbv7em-none-eabihf # For ARM Cortex-M4 -``` - -## Testing - -```bash -cargo test -``` - -## Notes - -- This implementation focuses on the core EKF calculation and tf generation -- Pub/sub functionality should be implemented separately using awkernel's reactor API -- The original Autoware implementation includes additional features like measurement updates, diagnostics, etc. -- This version is simplified for embedded use but maintains the essential EKF functionality \ No newline at end of file diff --git a/applications/tests/test_autoware/ekf_localizer/src/lib.rs b/applications/tests/test_autoware/ekf_localizer/src/lib.rs index f7a9396ed..ec77b805e 100644 --- a/applications/tests/test_autoware/ekf_localizer/src/lib.rs +++ b/applications/tests/test_autoware/ekf_localizer/src/lib.rs @@ -9,10 +9,11 @@ use core::ptr::null_mut; use core::sync::atomic::{AtomicPtr, Ordering as AtomicOrdering}; use libm::{asin, atan2, cos, sin}; use nalgebra::{Matrix6, Vector3, Vector6}; +pub use imu_driver; +pub use vehicle_velocity_converter::TwistWithCovariance; static EKF_MODULE_INSTANCE: AtomicPtr = AtomicPtr::new(null_mut()); -/// State indices for EKF #[derive(Debug, Clone, Copy, PartialEq)] pub enum StateIndex { X = 0, @@ -23,14 +24,9 @@ pub enum StateIndex { Wz = 5, } -/// EKF State vector (6x1) -/// [x, y, yaw, yaw_bias, vx, wz] pub type StateVector = Vector6; - -/// EKF Covariance matrix (6x6) pub type StateCovariance = Matrix6; -/// 3D Point structure #[derive(Debug, Clone, Copy)] pub struct Point3D { pub x: f64, @@ -38,7 +34,6 @@ pub struct Point3D { pub z: f64, } -/// Quaternion structure #[derive(Debug, Clone, Copy)] pub struct Quaternion { pub x: f64, @@ -47,28 +42,32 @@ pub struct Quaternion { pub w: f64, } -/// Pose structure #[derive(Debug, Clone, Copy)] pub struct Pose { pub position: Point3D, pub orientation: Quaternion, } -/// Twist structure #[derive(Debug, Clone, Copy)] pub struct Twist { pub linear: Vector3, pub angular: Vector3, } -/// PoseWithCovariance structure #[derive(Debug, Clone, Copy)] pub struct PoseWithCovariance { pub pose: Pose, pub covariance: [f64; 36], } -/// EKF Parameters +#[derive(Debug, Clone)] +pub struct EKFOdometry { + pub header: imu_driver::Header, + pub child_frame_id: &'static str, + pub pose: PoseWithCovariance, + pub twist: TwistWithCovariance, +} + #[derive(Debug, Clone)] pub struct EKFParameters { pub enable_yaw_bias_estimation: bool, @@ -96,7 +95,6 @@ impl Default for EKFParameters { } } -/// Simple 1D Filter for z, roll, pitch #[derive(Debug, Clone)] pub struct Simple1DFilter { initialized: bool, @@ -127,11 +125,9 @@ impl Simple1DFilter { return; } - // Prediction step let proc_var_x_d = self.proc_var_x_c * dt * dt; self.var = self.var + proc_var_x_d; - // Update step let kalman_gain = self.var / (self.var + obs_var); self.x = self.x + kalman_gain * (obs - self.x); self.var = (1.0 - kalman_gain) * self.var; @@ -150,7 +146,6 @@ impl Simple1DFilter { } } -/// Main EKF Module #[derive(Debug, Clone)] pub struct EKFModule { params: EKFParameters, @@ -162,8 +157,7 @@ pub struct EKFModule { pitch_filter: Simple1DFilter, accumulated_delay_times: Vec, last_angular_velocity: Vector3, - /// MRM (Minimal Risk Maneuver) mode flag - /// When true, only prediction is performed (no measurement updates) + // When true, only prediction is performed (no measurement updates) is_mrm_mode: bool, } @@ -173,7 +167,6 @@ impl EKFModule { let mut state = StateVector::zeros(); let mut covariance = StateCovariance::identity() * 1e15; - // Initialize covariance with reasonable values covariance[(StateIndex::Yaw as usize, StateIndex::Yaw as usize)] = 50.0; if params.enable_yaw_bias_estimation { covariance[(StateIndex::YawBias as usize, StateIndex::YawBias as usize)] = 50.0; @@ -205,9 +198,7 @@ impl EKFModule { } } - /// Initialize EKF with initial pose pub fn initialize(&mut self, initial_pose: Pose) { - // Set initial state directly from pose self.state[StateIndex::X as usize] = initial_pose.position.x; self.state[StateIndex::Y as usize] = initial_pose.position.y; self.state[StateIndex::Yaw as usize] = self.quaternion_to_yaw(initial_pose.orientation); @@ -215,20 +206,16 @@ impl EKFModule { self.state[StateIndex::Vx as usize] = 0.0; self.state[StateIndex::Wz as usize] = 0.0; - // Initialize covariance (simplified) self.covariance = StateCovariance::identity() * 0.01; if self.params.enable_yaw_bias_estimation { self.covariance[(StateIndex::YawBias as usize, StateIndex::YawBias as usize)] = 0.0001; } - // Initialize filters self.z_filter.init(initial_pose.position.z, 0.01); self.roll_filter.init(0.0, 0.01); self.pitch_filter.init(0.0, 0.01); } - /// Predict next state using nonlinear state transition (core prediction logic) - /// x_{k+1} = x_k + vx * cos(yaw + bias) * dt, y_{k+1} = y_k + vx * sin(yaw + bias) * dt, etc. fn predict_next_state(&self, dt: f64) -> StateVector { let mut x_next = self.state.clone(); let x = self.state[StateIndex::X as usize]; @@ -238,28 +225,23 @@ impl EKFModule { let vx = self.state[StateIndex::Vx as usize]; let wz = self.state[StateIndex::Wz as usize]; - // Nonlinear state transition x_next[StateIndex::X as usize] = x + vx * cos(yaw + yaw_bias) * dt; x_next[StateIndex::Y as usize] = y + vx * sin(yaw + yaw_bias) * dt; - // Normalize yaw to [-π, π] range (Autoware compatible) let yaw_next = yaw + wz * dt; x_next[StateIndex::Yaw as usize] = atan2(sin(yaw_next), cos(yaw_next)); - x_next[StateIndex::YawBias as usize] = yaw_bias; // yaw bias doesn't change - x_next[StateIndex::Vx as usize] = vx; // velocity doesn't change in predict - x_next[StateIndex::Wz as usize] = wz; // angular velocity doesn't change in predict + x_next[StateIndex::YawBias as usize] = yaw_bias; + x_next[StateIndex::Vx as usize] = vx; + x_next[StateIndex::Wz as usize] = wz; x_next } - /// Create state transition (Jacobian) matrix F - /// F = d(f)/d(x) where f is the nonlinear state transition function fn create_state_transition_matrix(&self, dt: f64) -> Matrix6 { let mut F = Matrix6::identity(); let yaw = self.state[StateIndex::Yaw as usize]; let yaw_bias = self.state[StateIndex::YawBias as usize]; let vx = self.state[StateIndex::Vx as usize]; - // Jacobian of position with respect to yaw and velocity F[(StateIndex::X as usize, StateIndex::Yaw as usize)] = -vx * sin(yaw + yaw_bias) * dt; F[(StateIndex::X as usize, StateIndex::YawBias as usize)] = -vx * sin(yaw + yaw_bias) * dt; F[(StateIndex::X as usize, StateIndex::Vx as usize)] = cos(yaw + yaw_bias) * dt; @@ -273,12 +255,9 @@ impl EKFModule { F } - /// Calculate process noise covariance Q - /// Q represents the uncertainty in the motion model fn process_noise_covariance(&self, dt: f64) -> Matrix6 { let mut Q = Matrix6::zeros(); - // Process noise for each state variable Q[(StateIndex::Vx as usize, StateIndex::Vx as usize)] = self.params.proc_stddev_vx_c * self.params.proc_stddev_vx_c * dt * dt; Q[(StateIndex::Wz as usize, StateIndex::Wz as usize)] = @@ -286,7 +265,6 @@ impl EKFModule { Q[(StateIndex::Yaw as usize, StateIndex::Yaw as usize)] = self.params.proc_stddev_yaw_c * self.params.proc_stddev_yaw_c * dt * dt; - // No process noise for position and yaw bias Q[(StateIndex::X as usize, StateIndex::X as usize)] = 0.0; Q[(StateIndex::Y as usize, StateIndex::Y as usize)] = 0.0; Q[(StateIndex::YawBias as usize, StateIndex::YawBias as usize)] = 0.0; @@ -294,37 +272,22 @@ impl EKFModule { Q } - /// Predict step of EKF (uses predict_next_state, create_state_transition_matrix, and process_noise_covariance) pub fn predict(&mut self, dt: f64) { - // 1. Predict next state using nonlinear motion model self.state = self.predict_next_state(dt); - - // 2. Create state transition (Jacobian) matrix let F = self.create_state_transition_matrix(dt); - - // 3. Calculate process noise covariance let Q = self.process_noise_covariance(dt); - - // 4. Predict covariance: P = F * P * F^T + Q self.covariance = F * self.covariance * F.transpose() + Q; - - // 5. Update accumulated delay times self.accumulate_delay_time(dt); } - /// Predict with delay support (Autoware compatible) - /// This version maintains the delay history for measurement updates pub fn predict_with_delay(&mut self, dt: f64) { self.predict(dt); } - /// Predict-only step (for MRM mode when measurement updates are not available) - /// Only performs prediction without any measurement updates pub fn predict_only(&mut self, dt: f64) { self.predict(dt); } - /// Get current pose for tf publishing pub fn get_current_pose(&self, get_biased_yaw: bool) -> Pose { let z = self.z_filter.get_x(); let roll = self.roll_filter.get_x(); @@ -347,7 +310,6 @@ impl EKFModule { } } - /// Get current twist pub fn get_current_twist(&self) -> Twist { let vx = self.state[StateIndex::Vx as usize]; let wz = self.state[StateIndex::Wz as usize]; @@ -358,72 +320,52 @@ impl EKFModule { } } - /// Get yaw bias pub fn get_yaw_bias(&self) -> f64 { self.state[StateIndex::YawBias as usize] } - /// Get current pose with covariance for publishing pub fn get_current_pose_with_covariance(&self) -> PoseWithCovariance { - // Get current pose let pose = self.get_current_pose(false); - - // Get covariance matrix let pose_covariance = self.get_current_pose_covariance(); - - // Create and return PoseWithCovariance PoseWithCovariance { pose, covariance: pose_covariance, } } - /// Get pose covariance (simplified 6x6 to 36-element array) pub fn get_current_pose_covariance(&self) -> [f64; 36] { let mut cov = [0.0; 36]; - // Copy 6x6 covariance matrix to 36-element array for i in 0..6 { for j in 0..6 { cov[i * 6 + j] = self.covariance[(i, j)]; } } - // Add z, roll, pitch variances - cov[14] = self.z_filter.get_var(); // Z_Z - cov[21] = self.roll_filter.get_var(); // ROLL_ROLL - cov[28] = self.pitch_filter.get_var(); // PITCH_PITCH + cov[14] = self.z_filter.get_var(); + cov[21] = self.roll_filter.get_var(); + cov[28] = self.pitch_filter.get_var(); cov } - /// Get twist covariance pub fn get_current_twist_covariance(&self) -> [f64; 36] { let mut cov = [0.0; 36]; - // Simplified: only vx and wz have significant covariance - cov[0] = self.covariance[(StateIndex::Vx as usize, StateIndex::Vx as usize)]; // VX_VX - cov[35] = self.covariance[(StateIndex::Wz as usize, StateIndex::Wz as usize)]; // WZ_WZ + cov[0] = self.covariance[(StateIndex::Vx as usize, StateIndex::Vx as usize)]; + cov[35] = self.covariance[(StateIndex::Wz as usize, StateIndex::Wz as usize)]; cov } - /// Update velocity measurement (measurement update for Vx and Wz) - /// This is NOT executed during MRM mode (dead reckoning only) pub fn update_velocity(&mut self, vx_measurement: f64, wz_measurement: f64) { - // Skip measurement update during MRM mode if self.is_mrm_mode { return; } - // Simple measurement update using Kalman gain - // This assumes direct observation of velocity states - - // Measurement variance (assumed) let vx_obs_var = 1.0; let wz_obs_var = 0.1; - // Update Vx let vx_var = self.covariance[(StateIndex::Vx as usize, StateIndex::Vx as usize)]; let vx_gain = vx_var / (vx_var + vx_obs_var); self.state[StateIndex::Vx as usize] = self.state[StateIndex::Vx as usize] @@ -431,7 +373,6 @@ impl EKFModule { self.covariance[(StateIndex::Vx as usize, StateIndex::Vx as usize)] = (1.0 - vx_gain) * vx_var; - // Update Wz let wz_var = self.covariance[(StateIndex::Wz as usize, StateIndex::Wz as usize)]; let wz_gain = wz_var / (wz_var + wz_obs_var); self.state[StateIndex::Wz as usize] = self.state[StateIndex::Wz as usize] @@ -440,18 +381,14 @@ impl EKFModule { (1.0 - wz_gain) * wz_var; } - /// Set MRM (Minimal Risk Maneuver) mode - /// When MRM mode is active, only prediction is performed (no measurement updates) pub fn set_mrm_mode(&mut self, is_mrm: bool) { self.is_mrm_mode = is_mrm; } - /// Get current MRM mode status pub fn is_mrm(&self) -> bool { self.is_mrm_mode } - /// Accumulate delay time pub fn accumulate_delay_time(&mut self, dt: f64) { let len = self.accumulated_delay_times.len(); if len == 0 { @@ -461,14 +398,12 @@ impl EKFModule { let last_time = self.accumulated_delay_times[len - 1]; let new_time = last_time + dt; - // Shift and add new time for i in 0..len - 1 { self.accumulated_delay_times[i] = self.accumulated_delay_times[i + 1]; } self.accumulated_delay_times[len - 1] = new_time; } - /// Find closest delay time index pub fn find_closest_delay_time_index(&self, target_value: f64) -> usize { let len = self.accumulated_delay_times.len(); if len == 0 { @@ -479,7 +414,6 @@ impl EKFModule { return len; } - // Simple linear search for closest value let mut closest_index = 0; let mut min_diff = f64::MAX; @@ -495,7 +429,6 @@ impl EKFModule { closest_index } - // Utility functions for quaternion and euler angle conversions fn quaternion_to_yaw(&self, q: Quaternion) -> f64 { atan2( 2.0 * (q.w * q.z + q.x * q.y), @@ -520,12 +453,10 @@ impl EKFModule { } fn quaternion_to_rpy(&self, q: Quaternion) -> (f64, f64, f64) { - // Roll (x-axis rotation) let sinr_cosp = 2.0 * (q.w * q.x + q.y * q.z); let cosr_cosp = 1.0 - 2.0 * (q.x * q.x + q.y * q.y); let roll = atan2(sinr_cosp, cosr_cosp); - // Pitch (y-axis rotation) let sinp = 2.0 * (q.w * q.y - q.z * q.x); let pitch = if sinp.abs() >= 1.0 { PI / 2.0 * sinp.signum() @@ -533,7 +464,6 @@ impl EKFModule { asin(sinp) }; - // Yaw (z-axis rotation) let siny_cosp = 2.0 * (q.w * q.z + q.x * q.y); let cosy_cosp = 1.0 - 2.0 * (q.y * q.y + q.z * q.z); let yaw = atan2(siny_cosp, cosy_cosp); @@ -635,11 +565,8 @@ mod tests { let pose_with_cov = ekf.get_current_pose_with_covariance(); - // Check pose assert!((pose_with_cov.pose.position.x - 1.0).abs() < 1e-6); assert!((pose_with_cov.pose.position.y - 2.0).abs() < 1e-6); - - // Check covariance array assert_eq!(pose_with_cov.covariance.len(), 36); } } diff --git a/applications/tests/test_autoware/gyro_odometer/src/lib.rs b/applications/tests/test_autoware/gyro_odometer/src/lib.rs index c6659acb7..8a5b30ee8 100644 --- a/applications/tests/test_autoware/gyro_odometer/src/lib.rs +++ b/applications/tests/test_autoware/gyro_odometer/src/lib.rs @@ -3,11 +3,9 @@ extern crate alloc; use alloc::{borrow::Cow, collections::VecDeque, string::String, vec::Vec}; use core::time::Duration; -// Global instance and lazy initialization support use core::ptr::null_mut; use core::sync::atomic::{AtomicPtr, Ordering as AtomicOrdering}; -// Re-export common types for consistency with other libraries pub use imu_corrector::{transform_covariance, ImuWithCovariance, Transform}; pub use imu_driver::{Header, ImuMsg, Quaternion, Vector3}; pub use vehicle_velocity_converter::{ @@ -16,12 +14,9 @@ pub use vehicle_velocity_converter::{ static GYRO_ODOMETER_INSTANCE: AtomicPtr = AtomicPtr::new(null_mut()); -// Constants for covariance indices (matching C++ implementation) const COV_IDX_X_X: usize = 0; const COV_IDX_Y_Y: usize = 4; const COV_IDX_Z_Z: usize = 8; - -// XYZRPY covariance indices (matching C++ implementation) const COV_IDX_XYZRPY_X_X: usize = 0; const COV_IDX_XYZRPY_Y_Y: usize = 7; const COV_IDX_XYZRPY_Z_Z: usize = 14; @@ -29,19 +24,13 @@ const COV_IDX_XYZRPY_ROLL_ROLL: usize = 21; const COV_IDX_XYZRPY_PITCH_PITCH: usize = 28; const COV_IDX_XYZRPY_YAW_YAW: usize = 35; -// GyroOdometerCore implementation pub struct GyroOdometerCore { - // Parameters pub output_frame: String, pub message_timeout_sec: f64, - - // State pub vehicle_twist_arrived: bool, pub imu_arrived: bool, pub vehicle_twist_queue: VecDeque, pub gyro_queue: VecDeque, - - // Configuration pub config: GyroOdometerConfig, } @@ -62,15 +51,10 @@ impl GyroOdometerCore { }) } - /// Main processing function (matching C++ concat_gyro_and_odometer) - /// - /// # Arguments - /// * `current_time` - Current system time in nanoseconds (matching C++ this->now()) pub fn concat_gyro_and_odometer( &mut self, current_time: u64, ) -> Result> { - // Check if first messages have arrived (matching C++ implementation) if !self.vehicle_twist_arrived { self.vehicle_twist_queue.clear(); self.gyro_queue.clear(); @@ -81,15 +65,11 @@ impl GyroOdometerCore { self.gyro_queue.clear(); return Ok(None); } - - // Check timeout (matching C++ implementation) - // C++: vehicle_twist_dt = std::abs((this->now() - latest_vehicle_twist_ros_time_).seconds()) if !self.vehicle_twist_queue.is_empty() && !self.gyro_queue.is_empty() { let latest_vehicle_twist_stamp = self.vehicle_twist_queue.back().unwrap().header.timestamp; let latest_imu_stamp = self.gyro_queue.back().unwrap().header.timestamp; - // Check vehicle twist timeout (matching C++ vehicle_twist_dt > message_timeout_sec_) if Self::check_timeout( current_time, latest_vehicle_twist_stamp, @@ -102,7 +82,6 @@ impl GyroOdometerCore { ))); } - // Check IMU timeout (matching C++ imu_dt > message_timeout_sec_) if Self::check_timeout(current_time, latest_imu_stamp, self.message_timeout_sec) { self.vehicle_twist_queue.clear(); self.gyro_queue.clear(); @@ -112,33 +91,25 @@ impl GyroOdometerCore { } } - // Check queue size (matching C++ implementation) if self.vehicle_twist_queue.is_empty() || self.gyro_queue.is_empty() { return Ok(None); } - // Get transformation (matching C++ implementation) let tf = self.get_transform( &self.gyro_queue.front().unwrap().header.frame_id, &self.output_frame, )?; - // Transform gyro frame (matching C++ implementation) for gyro in &mut self.gyro_queue { let transformed_angular_velocity = tf.apply_to_vector(gyro.angular_velocity.clone()); - // Note: In C++ implementation, frame_id is updated to output_frame - // but for now we keep the original frame_id to avoid lifetime issues gyro.angular_velocity = transformed_angular_velocity; - // Covariance is already calculated and transformed by imu_corrector } - // Calculate mean and covariance (matching C++ implementation exactly) let mut vx_mean = 0.0; let mut gyro_mean = Vector3::new(0.0, 0.0, 0.0); let mut vx_covariance_original = 0.0; let mut gyro_covariance_original = Vector3::new(0.0, 0.0, 0.0); - // Calculate vehicle twist mean and covariance for vehicle_twist in &self.vehicle_twist_queue { vx_mean += vehicle_twist.twist.twist.linear.x; vx_covariance_original += vehicle_twist.twist.covariance[0 * 6 + 0]; @@ -146,12 +117,10 @@ impl GyroOdometerCore { vx_mean /= self.vehicle_twist_queue.len() as f64; vx_covariance_original /= self.vehicle_twist_queue.len() as f64; - // Calculate gyro mean and covariance (using pre-calculated covariance from imu_corrector) for gyro in &self.gyro_queue { gyro_mean.x += gyro.angular_velocity.x; gyro_mean.y += gyro.angular_velocity.y; gyro_mean.z += gyro.angular_velocity.z; - // Use pre-calculated covariance from imu_corrector (already transformed) gyro_covariance_original.x += gyro.angular_velocity_covariance[COV_IDX_X_X]; gyro_covariance_original.y += gyro.angular_velocity_covariance[COV_IDX_Y_Y]; gyro_covariance_original.z += gyro.angular_velocity_covariance[COV_IDX_Z_Z]; @@ -163,7 +132,6 @@ impl GyroOdometerCore { gyro_covariance_original.y /= self.gyro_queue.len() as f64; gyro_covariance_original.z /= self.gyro_queue.len() as f64; - // Create result (matching C++ implementation) let latest_vehicle_twist_stamp = self.vehicle_twist_queue.back().unwrap().header.timestamp; let latest_imu_stamp = self.gyro_queue.back().unwrap().header.timestamp; @@ -187,7 +155,6 @@ impl GyroOdometerCore { }, }; - // Set covariance (matching C++ implementation exactly) result.twist.covariance[COV_IDX_XYZRPY_X_X] = vx_covariance_original / self.vehicle_twist_queue.len() as f64; result.twist.covariance[COV_IDX_XYZRPY_Y_Y] = 100000.0; @@ -199,40 +166,28 @@ impl GyroOdometerCore { result.twist.covariance[COV_IDX_XYZRPY_YAW_YAW] = gyro_covariance_original.z / self.gyro_queue.len() as f64; - // Clear queues (matching C++ implementation) self.vehicle_twist_queue.clear(); self.gyro_queue.clear(); Ok(Some(result)) } - /// Check timeout (matching C++ implementation) - // Timeout checking function (matching C++ implementation) pub fn check_timeout(current_timestamp: u64, last_timestamp: u64, timeout_sec: f64) -> bool { - let dt = (current_timestamp as f64 - last_timestamp as f64) / 1_000_000_000.0; // Convert to seconds + let dt = (current_timestamp as f64 - last_timestamp as f64) / 1_000_000_000.0; dt.abs() > timeout_sec } - - /// Get transform (to be implemented by the caller) - /// Returns identity transform by default. Override this behavior by providing transform externally. pub fn get_transform(&self, from_frame: &str, to_frame: &str) -> Result { - // This should be implemented by the caller (e.g., transform listener) - // For now, return identity transform if from_frame == to_frame || from_frame == "" || to_frame == "" { Ok(Transform::identity()) } else { - // In a real implementation, this would query the transform tree - // For awkernel, we assume all frames are aligned (identity transform) Ok(Transform::identity()) } } - /// Process result and apply vehicle stop logic pub fn process_result( &self, twist_with_cov_raw: TwistWithCovarianceStamped, ) -> TwistWithCovarianceStamped { - // 車両が停止している場合の処理 (matching C++ implementation exactly) if twist_with_cov_raw.twist.twist.angular.z.abs() < 0.01 && twist_with_cov_raw.twist.twist.linear.x.abs() < 0.01 { @@ -246,7 +201,6 @@ impl GyroOdometerCore { } } - /// Convert vehicle velocity data to twist format pub fn convert_vehicle_velocity_to_twist( &self, odometry: &Odometry, @@ -267,19 +221,16 @@ impl GyroOdometerCore { } } - /// Add vehicle twist to queue (matching test_autoware usage pattern) pub fn add_vehicle_twist(&mut self, twist: TwistWithCovarianceStamped) { self.vehicle_twist_arrived = true; self.vehicle_twist_queue.push_back(twist); } - /// Add IMU data to queue (matching test_autoware usage pattern) pub fn add_imu(&mut self, imu: ImuWithCovariance) { self.imu_arrived = true; self.gyro_queue.push_back(imu); } - /// Process queues and get result (matching test_autoware process_queues_and_get_result) pub fn process_and_get_result( &mut self, current_time: u64, @@ -290,18 +241,15 @@ impl GyroOdometerCore { } } - /// Get queue sizes pub fn get_queue_sizes(&self) -> (usize, usize) { (self.vehicle_twist_queue.len(), self.gyro_queue.len()) } - /// Clear both queues pub fn clear_queues(&mut self) { self.vehicle_twist_queue.clear(); self.gyro_queue.clear(); } - /// Reset arrival flags pub fn reset_arrival_flags(&mut self) { self.vehicle_twist_arrived = false; self.imu_arrived = false; @@ -421,7 +369,6 @@ mod tests { let config = GyroOdometerConfig::default(); let mut core = GyroOdometerCore::new(config).unwrap(); - // Create IMU with covariance from imu_corrector let imu_with_cov = ImuWithCovariance { header: Header { frame_id: "imu_link", @@ -446,17 +393,15 @@ mod tests { 0.0, 0.0, 100000000.0, - ], // 10000^2 + ], }; - // Process IMU with covariance let result = core.process_imu_with_covariance(imu_with_cov); assert!(result.is_ok()); } #[test] fn test_transform_covariance_from_imu_corrector() { - // Test that we can use the transform_covariance function from imu_corrector let input = [1.0, 0.0, 0.0, 0.0, 2.0, 0.0, 0.0, 0.0, 3.0]; let output = transform_covariance(&input); assert_eq!(output[COV_IDX_X_X], 3.0); @@ -465,8 +410,6 @@ mod tests { } } -/// Get or initialize the global GyroOdometerCore instance -/// This provides lazy initialization with thread-safe access pub fn get_or_initialize() -> Result<&'static mut GyroOdometerCore> { let ptr = GYRO_ODOMETER_INSTANCE.load(AtomicOrdering::Acquire); @@ -474,15 +417,11 @@ pub fn get_or_initialize() -> Result<&'static mut GyroOdometerCore> { return Ok(unsafe { &mut *ptr }); } - // Not initialized, try to initialize let config = GyroOdometerConfig::default(); let core = GyroOdometerCore::new(config)?; - - // Allocate on heap and store pointer let boxed_core = alloc::boxed::Box::new(core); let new_ptr = alloc::boxed::Box::into_raw(boxed_core); - // Try to store the pointer atomically match GYRO_ODOMETER_INSTANCE.compare_exchange( null_mut(), new_ptr, @@ -490,11 +429,9 @@ pub fn get_or_initialize() -> Result<&'static mut GyroOdometerCore> { AtomicOrdering::Relaxed, ) { Ok(_) => { - // We successfully initialized Ok(unsafe { &mut *new_ptr }) } Err(existing_ptr) => { - // Another thread already initialized it, clean up our allocation unsafe { let _ = alloc::boxed::Box::from_raw(new_ptr); } diff --git a/applications/tests/test_autoware/imu_corrector/src/lib.rs b/applications/tests/test_autoware/imu_corrector/src/lib.rs index 97db33846..893efb3a8 100644 --- a/applications/tests/test_autoware/imu_corrector/src/lib.rs +++ b/applications/tests/test_autoware/imu_corrector/src/lib.rs @@ -5,7 +5,6 @@ use alloc::{format, string::String}; use imu_driver::{Header, ImuMsg, Quaternion, Vector3}; use nalgebra::{Matrix3, Quaternion as NQuaternion, UnitQuaternion, Vector3 as NVector3}; -// Transform structure (simplified TF representation) #[derive(Clone, Debug)] pub struct Transform { pub translation: Vector3, @@ -25,19 +24,15 @@ impl Transform { } } - /// Convert imu_driver Vector3 to nalgebra Vector3 fn to_nalgebra_vector3(&self, vec: &Vector3) -> NVector3 { NVector3::new(vec.x, vec.y, vec.z) } - /// Convert nalgebra Vector3 to imu_driver Vector3 fn to_imu_vector3(&self, vec: &NVector3) -> Vector3 { Vector3::new(vec.x, vec.y, vec.z) } - /// Convert imu_driver Quaternion to nalgebra UnitQuaternion fn to_nalgebra_quaternion(&self, quat: &Quaternion) -> UnitQuaternion { - // Create nalgebra Quaternion first, then normalize to UnitQuaternion let n_quat = NQuaternion::new(quat.w, quat.x, quat.y, quat.z); UnitQuaternion::from_quaternion(n_quat) } @@ -52,7 +47,6 @@ impl Transform { } } -// Dynamic TF listener interface (simplified version) pub trait TransformListener { fn get_latest_transform(&self, from_frame: &str, to_frame: &str) -> Option; fn get_transform_at_time( @@ -63,7 +57,6 @@ pub trait TransformListener { ) -> Option; } -// Mock TF listener for testing (can be replaced with actual ROS2 TF implementation) pub struct MockTransformListener { transforms: alloc::collections::BTreeMap, } @@ -93,12 +86,10 @@ impl TransformListener for MockTransformListener { to_frame: &str, _timestamp: u64, ) -> Option { - // For mock implementation, ignore timestamp and return latest self.get_latest_transform(from_frame, to_frame) } } -// Enhanced IMU structure with covariance information #[derive(Clone, Debug)] pub struct ImuWithCovariance { pub header: Header, @@ -131,7 +122,6 @@ impl ImuWithCovariance { } } -// Configuration structure pub struct ImuCorrectorConfig { pub angular_velocity_offset_x: f64, pub angular_velocity_offset_y: f64, @@ -144,7 +134,6 @@ pub struct ImuCorrectorConfig { } impl Default for ImuCorrectorConfig { - //sensing/autoware_imu_corrector/config/imu_corrector.param.yaml fn default() -> Self { Self { angular_velocity_offset_x: 0.0, @@ -159,7 +148,6 @@ impl Default for ImuCorrectorConfig { } } -// IMU corrector implementation pub struct ImuCorrector { config: ImuCorrectorConfig, transform_listener: T, @@ -186,60 +174,42 @@ impl ImuCorrector { self.config = config; } - /// Convert imu_driver Vector3 to nalgebra Vector3 fn to_nalgebra_vector3(&self, vec: &Vector3) -> NVector3 { NVector3::new(vec.x, vec.y, vec.z) } - /// Convert nalgebra Vector3 to imu_driver Vector3 fn to_imu_vector3(&self, vec: &NVector3) -> Vector3 { Vector3::new(vec.x, vec.y, vec.z) } - /// Convert imu_driver Quaternion to nalgebra UnitQuaternion fn to_nalgebra_quaternion(&self, quat: &Quaternion) -> UnitQuaternion { - // Create nalgebra Quaternion first, then normalize to UnitQuaternion let n_quat = NQuaternion::new(quat.w, quat.x, quat.y, quat.z); UnitQuaternion::from_quaternion(n_quat) } - /// Transform vector3 using transform (simplified version) fn transform_vector3(&self, vec: &Vector3, transform: &Transform) -> Vector3 { - // Convert to nalgebra types for transformation let nalgebra_vec = self.to_nalgebra_vector3(vec); let nalgebra_quat = self.to_nalgebra_quaternion(&transform.rotation); let nalgebra_trans = self.to_nalgebra_vector3(&transform.translation); - - // Apply rotation and translation let rotated = nalgebra_quat * nalgebra_vec; let result = rotated + nalgebra_trans; - - // Convert back to imu_driver Vector3 self.to_imu_vector3(&result) } - /// Transform covariance matrix (matches C++ transform_covariance function) - /// Takes the maximum covariance value and applies it to diagonal elements fn transform_covariance(&self, cov: &[f64; 9]) -> [f64; 9] { - // Find maximum covariance value from diagonal elements (xx, yy, zz) - let max_cov = cov[0].max(cov[4]).max(cov[8]); // X_X, Y_Y, Z_Z indices - - // Create new covariance matrix with max_cov on diagonal, zeros elsewhere + let max_cov = cov[0].max(cov[4]).max(cov[8]); let mut cov_transformed = [0.0; 9]; - cov_transformed[0] = max_cov; // X_X - cov_transformed[4] = max_cov; // Y_Y - cov_transformed[8] = max_cov; // Z_Z - // Other elements remain 0.0 + cov_transformed[0] = max_cov; + cov_transformed[4] = max_cov; + cov_transformed[8] = max_cov; cov_transformed } - /// Create default covariance matrix as array fn create_default_covariance_array(&self) -> [f64; 9] { [0.0; 9] } - /// Convert Matrix3 to array format for compatibility fn matrix3_to_array(&self, matrix: &Matrix3) -> [f64; 9] { [ matrix[(0, 0)], @@ -254,107 +224,78 @@ impl ImuCorrector { ] } - /// Correct IMU data with covariance (enhanced version for gyro_odometer) - /// This function matches the C++ callback_imu function more faithfully pub fn correct_imu_with_covariance( &self, imu_msg: &ImuMsg, transform: Option<&Transform>, ) -> ImuWithCovariance { - // Start with a copy of the input IMU message (matches C++ line 82) let mut corrected_imu = ImuWithCovariance::from_imu_msg(imu_msg); - - // Apply angular velocity offset correction (matches C++ lines 85-87) corrected_imu.angular_velocity.x -= self.config.angular_velocity_offset_x; corrected_imu.angular_velocity.y -= self.config.angular_velocity_offset_y; corrected_imu.angular_velocity.z -= self.config.angular_velocity_offset_z; - - // Calculate angular velocity covariance (matches C++ lines 89-93) - // Convert to array format: [xx, xy, xz, yx, yy, yz, zx, zy, zz] corrected_imu.angular_velocity_covariance[0] = - self.config.angular_velocity_stddev_xx * self.config.angular_velocity_stddev_xx; // xx + self.config.angular_velocity_stddev_xx * self.config.angular_velocity_stddev_xx; corrected_imu.angular_velocity_covariance[4] = - self.config.angular_velocity_stddev_yy * self.config.angular_velocity_stddev_yy; // yy + self.config.angular_velocity_stddev_yy * self.config.angular_velocity_stddev_yy; corrected_imu.angular_velocity_covariance[8] = - self.config.angular_velocity_stddev_zz * self.config.angular_velocity_stddev_zz; // zz - - // Calculate acceleration covariance (matches C++ lines 98-103) + self.config.angular_velocity_stddev_zz * self.config.angular_velocity_stddev_zz; let accel_var = self.config.acceleration_stddev * self.config.acceleration_stddev; - corrected_imu.linear_acceleration_covariance[0] = accel_var; // xx - corrected_imu.linear_acceleration_covariance[4] = accel_var; // yy - corrected_imu.linear_acceleration_covariance[8] = accel_var; // zz + corrected_imu.linear_acceleration_covariance[0] = accel_var; + corrected_imu.linear_acceleration_covariance[4] = accel_var; + corrected_imu.linear_acceleration_covariance[8] = accel_var; - // Apply TF transformation if provided (matches C++ lines 105-125) if let Some(tf) = transform { - // Transform linear acceleration (matches C++ line 115) corrected_imu.linear_acceleration = self.transform_vector3(&corrected_imu.linear_acceleration, tf); - // Transform linear acceleration covariance (matches C++ line 116) corrected_imu.linear_acceleration_covariance = self.transform_covariance(&corrected_imu.linear_acceleration_covariance); - - // Transform angular velocity (matches C++ line 118) corrected_imu.angular_velocity = self.transform_vector3(&corrected_imu.angular_velocity, tf); - // Transform angular velocity covariance (matches C++ line 119) corrected_imu.angular_velocity_covariance = self.transform_covariance(&corrected_imu.angular_velocity_covariance); - - // Update frame_id (matches C++ line 113) corrected_imu.header.frame_id = self.config.output_frame; } corrected_imu } - /// Correct IMU data (matches C++ implementation more closely) pub fn correct_imu(&self, imu_msg: &ImuMsg, transform: Option<&Transform>) -> ImuMsg { let corrected_with_cov = self.correct_imu_with_covariance(imu_msg, transform); corrected_with_cov.to_imu_msg() } - /// Correct IMU data with dynamic TF lookup (matches C++ callback_imu function) pub fn correct_imu_with_dynamic_tf(&self, imu_msg: &ImuMsg) -> Option { - // Get latest transform dynamically (matches C++ lines 106-107) let transform = self .transform_listener .get_latest_transform(&imu_msg.header.frame_id, self.config.output_frame)?; - // Apply correction with the dynamic transform let corrected_with_cov = self.correct_imu_with_covariance(imu_msg, Some(&transform)); Some(corrected_with_cov.to_imu_msg()) } - /// Correct IMU data with dynamic TF lookup and covariance pub fn correct_imu_with_dynamic_tf_covariance( &self, imu_msg: &ImuMsg, ) -> Option { - // Get latest transform dynamically (matches C++ lines 106-107) let transform = self .transform_listener .get_latest_transform(&imu_msg.header.frame_id, self.config.output_frame)?; - // Apply correction with the dynamic transform Some(self.correct_imu_with_covariance(imu_msg, Some(&transform))) } - /// Correct IMU data without TF transformation (simplified version) pub fn correct_imu_simple(&self, imu_msg: &ImuMsg) -> ImuMsg { let mut corrected_msg = imu_msg.clone(); - // Apply angular velocity offset correction corrected_msg.angular_velocity.x -= self.config.angular_velocity_offset_x; corrected_msg.angular_velocity.y -= self.config.angular_velocity_offset_y; corrected_msg.angular_velocity.z -= self.config.angular_velocity_offset_z; - // Update frame_id corrected_msg.header.frame_id = self.config.output_frame; corrected_msg } - /// Get covariance configuration for external use pub fn get_covariance_config(&self) -> (f64, f64, f64, f64) { ( self.config.angular_velocity_stddev_xx, @@ -365,20 +306,12 @@ impl ImuCorrector { } } -/// Public transform_covariance function that can be called from other libraries -/// Transform covariance matrix (matches C++ transform_covariance function) -/// Takes the maximum covariance value and applies it to diagonal elements pub fn transform_covariance(cov: &[f64; 9]) -> [f64; 9] { - // Find maximum covariance value from diagonal elements (xx, yy, zz) - let max_cov = cov[0].max(cov[4]).max(cov[8]); // X_X, Y_Y, Z_Z indices - - // Create new covariance matrix with max_cov on diagonal, zeros elsewhere + let max_cov = cov[0].max(cov[4]).max(cov[8]); let mut cov_transformed = [0.0; 9]; - cov_transformed[0] = max_cov; // X_X - cov_transformed[4] = max_cov; // Y_Y - cov_transformed[8] = max_cov; // Z_Z - // Other elements remain 0.0 - + cov_transformed[0] = max_cov; + cov_transformed[4] = max_cov; + cov_transformed[8] = max_cov; cov_transformed } @@ -406,8 +339,6 @@ mod tests { let corrected_msg = corrector.correct_imu_simple(&imu_msg); assert_eq!(corrected_msg.header.frame_id, "base_link"); - - // Check that offset correction was applied (no offset in default config) assert_eq!(corrected_msg.angular_velocity.x, 0.1); assert_eq!(corrected_msg.angular_velocity.y, 0.2); assert_eq!(corrected_msg.angular_velocity.z, 0.3); @@ -440,7 +371,6 @@ mod tests { let corrected_msg = corrector.correct_imu_simple(&imu_msg); - // Check that offset correction was applied assert_eq!(corrected_msg.angular_velocity.x, 0.1 - 0.05); assert_eq!(corrected_msg.angular_velocity.y, 0.2 - 0.1); assert_eq!(corrected_msg.angular_velocity.z, 0.3 - 0.15); @@ -465,77 +395,64 @@ mod tests { }; let corrected_with_cov = corrector.correct_imu_with_covariance(&imu_msg, None); - - // Check that covariance was calculated correctly - let expected_angular_var = 0.03 * 0.03; // stddev^2 + let expected_angular_var = 0.03 * 0.03; assert_eq!( corrected_with_cov.angular_velocity_covariance[0], expected_angular_var - ); // xx + ); assert_eq!( corrected_with_cov.angular_velocity_covariance[4], expected_angular_var - ); // yy + ); assert_eq!( corrected_with_cov.angular_velocity_covariance[8], expected_angular_var - ); // zz - - let expected_accel_var = 10000.0 * 10000.0; // stddev^2 + ); + let expected_accel_var = 10000.0 * 10000.0; assert_eq!( corrected_with_cov.linear_acceleration_covariance[0], expected_accel_var - ); // xx + ); assert_eq!( corrected_with_cov.linear_acceleration_covariance[4], expected_accel_var - ); // yy + ); assert_eq!( corrected_with_cov.linear_acceleration_covariance[8], expected_accel_var - ); // zz + ); } #[test] fn test_transform_covariance() { let corrector = ImuCorrector::new(); - - // Test covariance transformation (matches C++ transform_covariance function) - let input_cov = [1.0, 0.5, 0.3, 0.5, 2.0, 0.4, 0.3, 0.4, 3.0]; // xx=1, yy=2, zz=3 + let input_cov = [1.0, 0.5, 0.3, 0.5, 2.0, 0.4, 0.3, 0.4, 3.0]; let transformed_cov = corrector.transform_covariance(&input_cov); - // Should take maximum value (3.0) and apply to diagonal - assert_eq!(transformed_cov[0], 3.0); // xx - assert_eq!(transformed_cov[4], 3.0); // yy - assert_eq!(transformed_cov[8], 3.0); // zz - - // Off-diagonal elements should be 0 - assert_eq!(transformed_cov[1], 0.0); // xy - assert_eq!(transformed_cov[2], 0.0); // xz - assert_eq!(transformed_cov[3], 0.0); // yx - assert_eq!(transformed_cov[5], 0.0); // yz - assert_eq!(transformed_cov[6], 0.0); // zx - assert_eq!(transformed_cov[7], 0.0); // zy + assert_eq!(transformed_cov[0], 3.0); + assert_eq!(transformed_cov[4], 3.0); + assert_eq!(transformed_cov[8], 3.0); + assert_eq!(transformed_cov[1], 0.0); + assert_eq!(transformed_cov[2], 0.0); + assert_eq!(transformed_cov[3], 0.0); + assert_eq!(transformed_cov[5], 0.0); + assert_eq!(transformed_cov[6], 0.0); + assert_eq!(transformed_cov[7], 0.0); } #[test] fn test_public_transform_covariance() { - // Test the public transform_covariance function - let input_cov = [1.0, 0.5, 0.3, 0.5, 2.0, 0.4, 0.3, 0.4, 3.0]; // xx=1, yy=2, zz=3 + let input_cov = [1.0, 0.5, 0.3, 0.5, 2.0, 0.4, 0.3, 0.4, 3.0]; let transformed_cov = transform_covariance(&input_cov); - - // Should take maximum value (3.0) and apply to diagonal - assert_eq!(transformed_cov[0], 3.0); // xx - assert_eq!(transformed_cov[4], 3.0); // yy - assert_eq!(transformed_cov[8], 3.0); // zz - - // Off-diagonal elements should be 0 - assert_eq!(transformed_cov[1], 0.0); // xy - assert_eq!(transformed_cov[2], 0.0); // xz - assert_eq!(transformed_cov[3], 0.0); // yx - assert_eq!(transformed_cov[5], 0.0); // yz - assert_eq!(transformed_cov[6], 0.0); // zx - assert_eq!(transformed_cov[7], 0.0); // zy + assert_eq!(transformed_cov[0], 3.0); + assert_eq!(transformed_cov[4], 3.0); + assert_eq!(transformed_cov[8], 3.0); + assert_eq!(transformed_cov[1], 0.0); + assert_eq!(transformed_cov[2], 0.0); + assert_eq!(transformed_cov[3], 0.0); + assert_eq!(transformed_cov[5], 0.0); + assert_eq!(transformed_cov[6], 0.0); + assert_eq!(transformed_cov[7], 0.0); } #[test] @@ -567,24 +484,20 @@ mod tests { }; let corrected_with_cov = corrector.correct_imu_with_covariance(&imu_msg, Some(&transform)); - - // Check that frame_id was updated assert_eq!(corrected_with_cov.header.frame_id, "base_link"); - - // Check that covariance was transformed (should use max value) - let expected_angular_var = 0.03 * 0.03; // stddev^2 + let expected_angular_var = 0.03 * 0.03; assert_eq!( corrected_with_cov.angular_velocity_covariance[0], expected_angular_var - ); // xx + ); assert_eq!( corrected_with_cov.angular_velocity_covariance[4], expected_angular_var - ); // yy + ); assert_eq!( corrected_with_cov.angular_velocity_covariance[8], expected_angular_var - ); // zz + ); } #[test] @@ -621,17 +534,13 @@ mod tests { assert!(corrected_msg.is_some()); let corrected_msg = corrected_msg.unwrap(); - // Check that frame_id was updated assert_eq!(corrected_msg.header.frame_id, "base_link"); - - // Check that translation was applied (linear acceleration should be transformed) - // With translation of (1.0, 0.0, 0.0), the acceleration should be affected - assert_eq!(corrected_msg.linear_acceleration.x, 9.8); // No change for identity rotation + assert_eq!(corrected_msg.linear_acceleration.x, 9.8); } #[test] fn test_imu_corrector_with_dynamic_tf_no_transform() { - let transform_listener = MockTransformListener::new(); // Empty listener + let transform_listener = MockTransformListener::new(); let corrector = ImuCorrector::with_transform_listener(transform_listener); let imu_msg = ImuMsg { header: Header { @@ -649,7 +558,6 @@ mod tests { }; let corrected_msg = corrector.correct_imu_with_dynamic_tf(&imu_msg); - // Should return None when no transform is available assert!(corrected_msg.is_none()); } } diff --git a/applications/tests/test_autoware/imu_driver/src/lib.rs b/applications/tests/test_autoware/imu_driver/src/lib.rs index fa36930eb..3b8a947df 100644 --- a/applications/tests/test_autoware/imu_driver/src/lib.rs +++ b/applications/tests/test_autoware/imu_driver/src/lib.rs @@ -2,10 +2,8 @@ extern crate alloc; use alloc::{format, string::String, vec, vec::Vec}; -//use awkernel_lib::time::Time; use core::f64::consts::PI; -// IMU message structure #[derive(Clone, Debug)] pub struct ImuMsg { pub header: Header, @@ -84,7 +82,6 @@ pub fn build_imu_msg_from_csv_row( } } -/// IMU data parser for Tamagawa IMU pub struct TamagawaImuParser { frame_id: &'static str, dummy_counter: u16, @@ -98,16 +95,7 @@ impl TamagawaImuParser { } } - /// Parse binary IMU data from Tamagawa sensor - /// - /// # Arguments - /// * `data` - Raw binary data from sensor (expected length 58 bytes) - /// * `timestamp` - Current timestamp in nanoseconds - /// - /// # Returns - /// * `Option` - Parsed IMU message if data is valid, None otherwise pub fn parse_binary_data(&self, data: &[u8], timestamp: u64) -> Option { - // Check if data is valid BIN format and correct length if data.len() != 58 || data[5] != b'B' || data[6] != b'I' @@ -121,47 +109,23 @@ impl TamagawaImuParser { imu_msg.header.frame_id = self.frame_id; imu_msg.header.timestamp = timestamp; - // Parse counter (bytes 11-12) let _counter = ((data[11] as u16) << 8) | (data[12] as u16); - - // Parse angular velocity (gyroscope) data - // Bytes 15-16: X-axis angular velocity let raw_data = self.parse_signed_16bit(&data[15..17]); imu_msg.angular_velocity.x = self.convert_angular_velocity(raw_data); - - // Bytes 17-18: Y-axis angular velocity let raw_data = self.parse_signed_16bit(&data[17..19]); imu_msg.angular_velocity.y = self.convert_angular_velocity(raw_data); - - // Bytes 19-20: Z-axis angular velocity let raw_data = self.parse_signed_16bit(&data[19..21]); imu_msg.angular_velocity.z = self.convert_angular_velocity(raw_data); - - // Parse linear acceleration data - // Bytes 21-22: X-axis acceleration let raw_data = self.parse_signed_16bit(&data[21..23]); imu_msg.linear_acceleration.x = self.convert_acceleration(raw_data); - - // Bytes 23-24: Y-axis acceleration let raw_data = self.parse_signed_16bit(&data[23..25]); imu_msg.linear_acceleration.y = self.convert_acceleration(raw_data); - - // Bytes 25-26: Z-axis acceleration let raw_data = self.parse_signed_16bit(&data[25..27]); imu_msg.linear_acceleration.z = self.convert_acceleration(raw_data); Some(imu_msg) } - /// Generate dummy binary data for testing - /// - /// # Arguments - /// * `timestamp` - Current timestamp in nanoseconds - /// * `angular_velocity` - Angular velocity values in rad/s - /// * `linear_acceleration` - Linear acceleration values in m/s² - /// - /// # Returns - /// * `Vec` - 58-byte binary data in Tamagawa format pub fn generate_dummy_binary_data( &mut self, _timestamp: u64, @@ -170,37 +134,28 @@ impl TamagawaImuParser { ) -> Vec { let mut data = vec![0u8; 58]; - // Header: $TSC,BIN, data[0..5].copy_from_slice(b"$TSC,"); data[5] = b'B'; data[6] = b'I'; data[7] = b'N'; data[8] = b','; - - // Counter (bytes 11-12) data[11] = (self.dummy_counter >> 8) as u8; data[12] = (self.dummy_counter & 0xFF) as u8; self.dummy_counter = self.dummy_counter.wrapping_add(1); - // Convert angular velocity from rad/s to LSB let angular_vel_x_lsb = self.convert_angular_velocity_to_lsb(angular_velocity.x); let angular_vel_y_lsb = self.convert_angular_velocity_to_lsb(angular_velocity.y); let angular_vel_z_lsb = self.convert_angular_velocity_to_lsb(angular_velocity.z); - - // Convert acceleration from m/s² to LSB let accel_x_lsb = self.convert_acceleration_to_lsb(linear_acceleration.x); let accel_y_lsb = self.convert_acceleration_to_lsb(linear_acceleration.y); let accel_z_lsb = self.convert_acceleration_to_lsb(linear_acceleration.z); - // Angular velocity data (bytes 15-20) data[15] = (angular_vel_x_lsb >> 8) as u8; data[16] = (angular_vel_x_lsb & 0xFF) as u8; data[17] = (angular_vel_y_lsb >> 8) as u8; data[18] = (angular_vel_y_lsb & 0xFF) as u8; data[19] = (angular_vel_z_lsb >> 8) as u8; data[20] = (angular_vel_z_lsb & 0xFF) as u8; - - // Linear acceleration data (bytes 21-26) data[21] = (accel_x_lsb >> 8) as u8; data[22] = (accel_x_lsb & 0xFF) as u8; data[23] = (accel_y_lsb >> 8) as u8; @@ -211,110 +166,57 @@ impl TamagawaImuParser { data } - /// Generate sinusoidal dummy data for realistic simulation - /// - /// # Arguments - /// * `timestamp` - Current timestamp in nanoseconds - /// * `time_offset` - Time offset for phase calculation - /// - /// # Returns - /// * `Vec` - 58-byte binary data with sinusoidal motion - /* - pub fn generate_sinusoidal_dummy_data(&mut self, timestamp: u64, time_offset: f64) -> Vec { - // Convert timestamp to seconds for sinusoidal calculation - let time_sec = (timestamp as f64) / 1_000_000_000.0 + time_offset; - - // Generate sinusoidal angular velocity (rotation around Z-axis) - let angular_vel_z = 0.5 * (2.0 * PI * 0.1 * time_sec).sin(); // 0.1 Hz, ±0.5 rad/s - - // Generate sinusoidal acceleration (oscillation in X-axis) - let accel_x = 9.8 + 2.0 * (2.0 * PI * 0.05 * time_sec).sin(); // 0.05 Hz, 9.8±2.0 m/s² - - let angular_velocity = Vector3::new(0.1, 0.2, angular_vel_z); - let linear_acceleration = Vector3::new(accel_x, 0.0, 9.8); - - self.generate_dummy_binary_data(timestamp, angular_velocity, linear_acceleration) - } - */ - - /// Generate static dummy data with fixed values - /// - /// # Arguments - /// * `timestamp` - Current timestamp in nanoseconds - /// - /// # Returns - /// * `Vec` - 58-byte binary data with static values - // Autoware側と統一:加速度は重力加速度のみ pub fn generate_static_dummy_data(&mut self, timestamp: u64) -> Vec { let angular_velocity = Vector3::new(0.1, 0.2, 0.01); - let linear_acceleration = Vector3::new(0.0, 0.0, 9.80665); // z方向のみ重力加速度 + let linear_acceleration = Vector3::new(0.0, 0.0, 9.80665); self.generate_dummy_binary_data(timestamp, angular_velocity, linear_acceleration) } - /// Convert angular velocity from rad/s to LSB fn convert_angular_velocity_to_lsb(&self, rad_per_sec: f64) -> i16 { let deg_per_sec = rad_per_sec * 180.0 / PI; let lsb = deg_per_sec / (200.0 / (1 << 15) as f64); lsb as i16 } - /// Convert acceleration from m/s² to LSB fn convert_acceleration_to_lsb(&self, m_per_sec_squared: f64) -> i16 { let lsb = m_per_sec_squared / (100.0 / (1 << 15) as f64); lsb as i16 } - /// Parse signed 16-bit value from 2 bytes - /// - /// This matches the C++ implementation: - /// raw_data = ((((rbuf[15] << 8) & 0xFFFFFF00) | (rbuf[16] & 0x000000FF))); fn parse_signed_16bit(&self, data: &[u8]) -> i16 { if data.len() != 2 { return 0; } - // Match C++ implementation: 32-bit integer with masking let high_byte = (data[0] as i32) << 8; let low_byte = data[1] as i32; let result = (high_byte & 0xFFFFFF00u32 as i32) | (low_byte & 0x000000FF); result as i16 } - /// Convert raw angular velocity data to rad/s - /// - /// Raw data is in LSB units with range ±200 deg/s - /// Conversion: raw * (200 / 2^15) * π / 180 fn convert_angular_velocity(&self, raw_data: i16) -> f64 { let lsb_to_deg_per_sec = 200.0 / (1 << 15) as f64; let deg_to_rad = PI / 180.0; (raw_data as f64) * lsb_to_deg_per_sec * deg_to_rad } - /// Convert raw acceleration data to m/s² - /// - /// Raw data is in LSB units with range ±100 m/s² - /// Conversion: raw * (100 / 2^15) fn convert_acceleration(&self, raw_data: i16) -> f64 { let lsb_to_m_per_sec_squared = 100.0 / (1 << 15) as f64; (raw_data as f64) * lsb_to_m_per_sec_squared } - /// Generate version request command pub fn generate_version_request() -> &'static [u8] { b"$TSC,VER*29\r\n" } - /// Generate offset cancel request command pub fn generate_offset_cancel_request(offset_value: i32) -> String { format!("$TSC,OFC,{}\r\n", offset_value) } - /// Generate heading reset request command pub fn generate_heading_reset_request() -> &'static [u8] { b"$TSC,HRST*29\r\n" } - /// Generate binary data request command pub fn generate_binary_request(rate_hz: u32) -> String { format!("$TSC,BIN,{}\r\n", rate_hz) } @@ -326,32 +228,23 @@ mod tests { #[test] fn example_usage() { - // Create parser instance let mut parser = TamagawaImuParser::new("imu_link"); - - // Generate commands let version_cmd = TamagawaImuParser::generate_version_request(); let binary_cmd = TamagawaImuParser::generate_binary_request(30); let offset_cmd = TamagawaImuParser::generate_offset_cancel_request(123); let heading_cmd = TamagawaImuParser::generate_heading_reset_request(); - - // Example 1: Generate static dummy data let static_dummy_data = parser.generate_static_dummy_data(123456789); if let Some(imu_msg) = parser.parse_binary_data(&static_dummy_data, 123456789) { - // Use the parsed IMU message let _angular_vel = imu_msg.angular_velocity; let _acceleration = imu_msg.linear_acceleration; } - // Example 2: Generate sinusoidal dummy data for realistic simulation let sinusoidal_dummy_data = parser.generate_sinusoidal_dummy_data(123456789, 0.0); if let Some(imu_msg) = parser.parse_binary_data(&sinusoidal_dummy_data, 123456789) { - // Use the parsed IMU message with realistic motion let _angular_vel = imu_msg.angular_velocity; let _acceleration = imu_msg.linear_acceleration; } - // Example 3: Generate custom dummy data let custom_angular_velocity = Vector3::new(0.5, -0.3, 1.2); let custom_acceleration = Vector3::new(8.5, 2.1, 10.2); let custom_dummy_data = parser.generate_dummy_binary_data( @@ -360,7 +253,6 @@ mod tests { custom_acceleration, ); if let Some(imu_msg) = parser.parse_binary_data(&custom_dummy_data, 123456789) { - // Use the parsed IMU message with custom values let _angular_vel = imu_msg.angular_velocity; let _acceleration = imu_msg.linear_acceleration; } diff --git a/applications/tests/test_autoware/src/lib.rs b/applications/tests/test_autoware/src/lib.rs index b0f5a2f9e..24a0fc695 100644 --- a/applications/tests/test_autoware/src/lib.rs +++ b/applications/tests/test_autoware/src/lib.rs @@ -10,40 +10,23 @@ use awkernel_lib::sync::mutex::{MCSNode, Mutex}; use core::net::Ipv4Addr; use core::time::Duration; use csv_core::{ReadRecordResult, Reader}; -// Thread-safe state management using atomic operations use core::sync::atomic::{AtomicBool, AtomicUsize, Ordering}; use imu_corrector::{ImuCorrector, ImuWithCovariance}; use imu_driver::{build_imu_msg_from_csv_row, ImuCsvRow, ImuMsg, TamagawaImuParser}; - use vehicle_velocity_converter::{ build_velocity_report_from_csv_row, reactor_helpers, Twist, TwistWithCovariance, TwistWithCovarianceStamped, VehicleVelocityConverter, VelocityCsvRow, }; - use ekf_localizer::{ - get_or_initialize_default_module, Point3D, Pose, PoseWithCovariance, Quaternion, + get_or_initialize_default_module, EKFOdometry, Point3D, Pose, PoseWithCovariance, Quaternion, }; -/// EKF Odometry structure for publishing (equivalent to C++ nav_msgs::msg::Odometry) -#[derive(Debug, Clone)] -pub struct EKFOdometry { - pub header: imu_driver::Header, - pub child_frame_id: &'static str, - pub pose: PoseWithCovariance, - pub twist: TwistWithCovariance, -} - const LOG_ENABLE: bool = false; const INTERFACE_ID: u64 = 0; - -// 10.0.2.0/24 is the IP address range of the Qemu's network. const INTERFACE_ADDR: Ipv4Addr = Ipv4Addr::new(10, 0, 2, 64); - -// 10.0.2.2 is the IP address of the Qemu's host. const UDP_TCP_DST_ADDR: Ipv4Addr = Ipv4Addr::new(10, 0, 2, 2); - const UDP_DST_PORT: u16 = 26099; const TCP_DST_PORT: u16 = 26099; const TCP_LISTEN_PORT: u16 = 26100; @@ -561,7 +544,6 @@ fn parse_f64(field: &str) -> Result { trimmed.parse::().map_err(|_| "Failed to parse f64") } -// Returns monotonic uptime in nanoseconds clamped to u64. fn get_awkernel_uptime_timestamp() -> u64 { let uptime_nanos = awkernel_lib::delay::uptime_nano(); if uptime_nanos > u64::MAX as u128 { diff --git a/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs b/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs index e94e39e6e..b6ab471d8 100644 --- a/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs +++ b/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs @@ -16,7 +16,6 @@ use imu_driver::{Header, Vector3}; -/// 速度レポートメッセージの構造体 #[derive(Debug, Clone)] pub struct VelocityReport { pub header: Header, @@ -49,21 +48,18 @@ pub fn build_velocity_report_from_csv_row( } } -/// TwistWithCovarianceStampedメッセージの構造体 #[derive(Debug, Clone)] pub struct TwistWithCovarianceStamped { pub header: Header, pub twist: TwistWithCovariance, } -/// TwistWithCovariance構造体 #[derive(Debug, Clone)] pub struct TwistWithCovariance { pub twist: Twist, pub covariance: [f64; 36], } -/// Twist構造体 #[derive(Debug, Clone)] pub struct Twist { pub linear: Vector3, @@ -75,16 +71,14 @@ pub struct Odometry { pub velocity: f64, } -/// 車両速度変換器の構造体 pub struct VehicleVelocityConverter { - frame_id: &'static str, // → frame_id: base_link - stddev_vx: f64, // → velocity_stddev_xx: 0.2 - stddev_wz: f64, // → angular_velocity_stddev_zz: 0.1 - speed_scale_factor: f64, // → speed_scale_factor: 1.0 + frame_id: &'static str, + stddev_vx: f64, + stddev_wz: f64, + speed_scale_factor: f64, } impl VehicleVelocityConverter { - /// 新しいVehicleVelocityConverterインスタンスを作成 pub fn new( frame_id: &'static str, stddev_vx: f64, @@ -99,7 +93,6 @@ impl VehicleVelocityConverter { } } - /// パラメータからVehicleVelocityConverterを作成(配列ベース版) pub fn from_params_array( velocity_stddev_xx: Option, angular_velocity_stddev_zz: Option, @@ -113,17 +106,13 @@ impl VehicleVelocityConverter { Self::new(frame_id, stddev_vx, stddev_wz, speed_scale_factor) } - /// デフォルト設定でVehicleVelocityConverterを作成 pub fn default() -> Self { Self::new("base_link", 0.2, 0.1, 1.0) } - /// 速度レポートをTwistWithCovarianceStampedに変換 pub fn convert_velocity_report(&self, msg: &VelocityReport) -> TwistWithCovarianceStamped { - // WARN Only let _frame_id_mismatch = msg.header.frame_id != self.frame_id; - // TwistWithCovarianceStampedメッセージを生成 TwistWithCovarianceStamped { header: msg.header.clone(), twist: TwistWithCovariance { @@ -144,28 +133,18 @@ impl VehicleVelocityConverter { } } - /// 共分散行列を作成 fn create_covariance_matrix(&self) -> [f64; 36] { let mut covariance = [0.0; 36]; - - // 線形速度の分散 (x方向) covariance[0 + 0 * 6] = self.stddev_vx * self.stddev_vx; - - // その他の線形速度成分は大きな値(低い信頼度)を設定 - covariance[1 + 1 * 6] = 10000.0; // y方向 - covariance[2 + 2 * 6] = 10000.0; // z方向 - - // 角速度成分は大きな値(低い信頼度)を設定 - covariance[3 + 3 * 6] = 10000.0; // x方向 - covariance[4 + 4 * 6] = 10000.0; // y方向 - - // 角速度の分散 (z方向) + covariance[1 + 1 * 6] = 10000.0; + covariance[2 + 2 * 6] = 10000.0; + covariance[3 + 3 * 6] = 10000.0; + covariance[4 + 4 * 6] = 10000.0; covariance[5 + 5 * 6] = self.stddev_wz * self.stddev_wz; covariance } - /// パラメータを取得 pub fn get_frame_id(&self) -> &'static str { self.frame_id } @@ -183,11 +162,9 @@ impl VehicleVelocityConverter { } } -/// リアクターAPI用のヘルパー関数 pub mod reactor_helpers { use super::*; - /// 空のTwistWithCovarianceStampedを生成 pub fn create_empty_twist(timestamp: u64) -> TwistWithCovarianceStamped { TwistWithCovarianceStamped { header: Header { @@ -257,8 +234,8 @@ mod tests { assert_eq!(twist_msg.twist.twist.linear.x, 10.0); assert_eq!(twist_msg.twist.twist.linear.y, 2.0); assert_eq!(twist_msg.twist.twist.angular.z, 0.5); - assert_eq!(twist_msg.twist.covariance[0], 0.01); // 0.1^2 - assert_eq!(twist_msg.twist.covariance[35], 0.01); // 0.1^2 + assert_eq!(twist_msg.twist.covariance[0], 0.01); + assert_eq!(twist_msg.twist.covariance[35], 0.01); } #[test] From 4e8a8c355f926856a83ebd5ced8f75abd1c22fcb Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 3 Apr 2026 17:08:34 +0900 Subject: [PATCH 13/60] fix: delete warnings 1 Signed-off-by: nokosaaan --- .../test_autoware/ekf_localizer/src/lib.rs | 19 ------------------- .../test_autoware/gyro_odometer/src/lib.rs | 2 +- .../test_autoware/imu_corrector/src/lib.rs | 18 ------------------ applications/tests/test_autoware/src/lib.rs | 2 -- awkernel_async_lib/src/dag.rs | 5 ++--- awkernel_async_lib/src/pubsub.rs | 12 ++++++------ awkernel_async_lib/src/task.rs | 2 +- awkernel_async_lib/src/time_interval.rs | 7 +++++-- 8 files changed, 15 insertions(+), 52 deletions(-) diff --git a/applications/tests/test_autoware/ekf_localizer/src/lib.rs b/applications/tests/test_autoware/ekf_localizer/src/lib.rs index ec77b805e..7f70f4274 100644 --- a/applications/tests/test_autoware/ekf_localizer/src/lib.rs +++ b/applications/tests/test_autoware/ekf_localizer/src/lib.rs @@ -451,25 +451,6 @@ impl EKFModule { z: cr * cp * sy - sr * sp * cy, } } - - fn quaternion_to_rpy(&self, q: Quaternion) -> (f64, f64, f64) { - let sinr_cosp = 2.0 * (q.w * q.x + q.y * q.z); - let cosr_cosp = 1.0 - 2.0 * (q.x * q.x + q.y * q.y); - let roll = atan2(sinr_cosp, cosr_cosp); - - let sinp = 2.0 * (q.w * q.y - q.z * q.x); - let pitch = if sinp.abs() >= 1.0 { - PI / 2.0 * sinp.signum() - } else { - asin(sinp) - }; - - let siny_cosp = 2.0 * (q.w * q.z + q.x * q.y); - let cosy_cosp = 1.0 - 2.0 * (q.y * q.y + q.z * q.z); - let yaw = atan2(siny_cosp, cosy_cosp); - - (roll, pitch, yaw) - } } pub fn get_or_initialize_default_module() -> &'static mut EKFModule { diff --git a/applications/tests/test_autoware/gyro_odometer/src/lib.rs b/applications/tests/test_autoware/gyro_odometer/src/lib.rs index 8a5b30ee8..743015e1c 100644 --- a/applications/tests/test_autoware/gyro_odometer/src/lib.rs +++ b/applications/tests/test_autoware/gyro_odometer/src/lib.rs @@ -1,7 +1,7 @@ #![no_std] extern crate alloc; -use alloc::{borrow::Cow, collections::VecDeque, string::String, vec::Vec}; +use alloc::{collections::VecDeque, string::String}; use core::time::Duration; use core::ptr::null_mut; use core::sync::atomic::{AtomicPtr, Ordering as AtomicOrdering}; diff --git a/applications/tests/test_autoware/imu_corrector/src/lib.rs b/applications/tests/test_autoware/imu_corrector/src/lib.rs index 893efb3a8..e92acab4a 100644 --- a/applications/tests/test_autoware/imu_corrector/src/lib.rs +++ b/applications/tests/test_autoware/imu_corrector/src/lib.rs @@ -206,24 +206,6 @@ impl ImuCorrector { cov_transformed } - fn create_default_covariance_array(&self) -> [f64; 9] { - [0.0; 9] - } - - fn matrix3_to_array(&self, matrix: &Matrix3) -> [f64; 9] { - [ - matrix[(0, 0)], - matrix[(0, 1)], - matrix[(0, 2)], - matrix[(1, 0)], - matrix[(1, 1)], - matrix[(1, 2)], - matrix[(2, 0)], - matrix[(2, 1)], - matrix[(2, 2)], - ] - } - pub fn correct_imu_with_covariance( &self, imu_msg: &ImuMsg, diff --git a/applications/tests/test_autoware/src/lib.rs b/applications/tests/test_autoware/src/lib.rs index 24a0fc695..f2c5ae8e5 100644 --- a/applications/tests/test_autoware/src/lib.rs +++ b/applications/tests/test_autoware/src/lib.rs @@ -28,8 +28,6 @@ const INTERFACE_ID: u64 = 0; const INTERFACE_ADDR: Ipv4Addr = Ipv4Addr::new(10, 0, 2, 64); const UDP_TCP_DST_ADDR: Ipv4Addr = Ipv4Addr::new(10, 0, 2, 2); const UDP_DST_PORT: u16 = 26099; -const TCP_DST_PORT: u16 = 26099; -const TCP_LISTEN_PORT: u16 = 26100; static mut LATEST_JSON_DATA: Option = None; static JSON_DATA_READY: AtomicBool = AtomicBool::new(false); diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index da12e208d..743e75632 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -67,9 +67,8 @@ use crate::{ task::{ perf::{ get_period_count, get_pub_count, get_sink_count, get_sub_count, increment_period_count, - increment_pub_count, increment_sink_count, increment_sub_count, node_finish, - node_start, publish_timestamp_at, subscribe_timestamp_at, - update_fin_recv_outer_timestamp_at, update_pre_send_outer_timestamp_at, NodeRecord, + increment_pub_count, increment_sink_count, increment_sub_count, publish_timestamp_at, subscribe_timestamp_at, + update_fin_recv_outer_timestamp_at, update_pre_send_outer_timestamp_at, }, DagInfo, }, diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index efb07ab17..109fb0682 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -52,9 +52,7 @@ use core::{ use futures::Future; use pin_project::pin_project; -use crate::task; -use crate::task::perf::{get_pub_count, publish_timestamp_at, PUB_COUNT}; -use crate::task::DagInfo; +use crate::task::perf::publish_timestamp_at; /// Data and timestamp. #[derive(Clone)] @@ -387,9 +385,11 @@ where { /// Send with metadata forwarded from `send_all_with_meta`. pub async fn send_with_meta(&self, data: T, pub_id: u32, index: usize, node_id: u32) { - // record publish timestamp at send start - // let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - // publish_timestamp_at(index, start, pub_id, node_id); + #[cfg(not(feature = "relax-get-period"))] + { + let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + publish_timestamp_at(index, start, pub_id, node_id); + } let sender = Sender::new(self, data); sender.await; diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index db982e06e..4634a3510 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -469,7 +469,7 @@ pub mod perf { use crate::task::{self}; use alloc::string::{String, ToString}; use array_macro::array; - use awkernel_lib::{cpu::NUM_MAX_CPU, device_tree::node}; + use awkernel_lib::cpu::NUM_MAX_CPU; use core::ptr::{read_volatile, write_volatile}; use core::sync::atomic::{AtomicBool, AtomicU32, Ordering}; diff --git a/awkernel_async_lib/src/time_interval.rs b/awkernel_async_lib/src/time_interval.rs index ec5bc6248..8bf645887 100644 --- a/awkernel_async_lib/src/time_interval.rs +++ b/awkernel_async_lib/src/time_interval.rs @@ -103,8 +103,11 @@ pub fn interval(period: Duration, dag_id: u32) -> Interval { pub fn interval_at(start: Time, period: Duration, dag_id: u32) -> Interval { assert!(!period.is_zero(), "`period` must be non-zero."); - let index = get_period_count(dag_id.clone() as usize) as usize; - update_pre_send_outer_timestamp_at(index, start.uptime().as_nanos() as u64, dag_id.clone()); + #[cfg(not(feature = "relax-get-period"))] + { + let index = get_period_count(dag_id.clone() as usize) as usize; + update_pre_send_outer_timestamp_at(index, start.uptime().as_nanos() as u64, dag_id.clone()); + } Interval { delay: None, next_tick_target: start, From 60d50db67de619cbae2463ed1ba3c7c0c946814b Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Wed, 15 Apr 2026 17:08:10 +0900 Subject: [PATCH 14/60] fix: delete warnings 2 Signed-off-by: nokosaaan --- .../tests/test_autoware/ekf_localizer/src/lib.rs | 10 ++-------- .../tests/test_autoware/imu_corrector/src/lib.rs | 2 +- 2 files changed, 3 insertions(+), 9 deletions(-) diff --git a/applications/tests/test_autoware/ekf_localizer/src/lib.rs b/applications/tests/test_autoware/ekf_localizer/src/lib.rs index 7f70f4274..99c7d9410 100644 --- a/applications/tests/test_autoware/ekf_localizer/src/lib.rs +++ b/applications/tests/test_autoware/ekf_localizer/src/lib.rs @@ -4,10 +4,9 @@ extern crate alloc; use alloc::{vec, vec::Vec}; -use core::f64::consts::PI; use core::ptr::null_mut; use core::sync::atomic::{AtomicPtr, Ordering as AtomicOrdering}; -use libm::{asin, atan2, cos, sin}; +use libm::{atan2, cos, sin}; use nalgebra::{Matrix6, Vector3, Vector6}; pub use imu_driver; pub use vehicle_velocity_converter::TwistWithCovariance; @@ -149,22 +148,19 @@ impl Simple1DFilter { #[derive(Debug, Clone)] pub struct EKFModule { params: EKFParameters, - dim_x: usize, state: StateVector, covariance: StateCovariance, z_filter: Simple1DFilter, roll_filter: Simple1DFilter, pitch_filter: Simple1DFilter, accumulated_delay_times: Vec, - last_angular_velocity: Vector3, // When true, only prediction is performed (no measurement updates) is_mrm_mode: bool, } impl EKFModule { pub fn new(params: EKFParameters) -> Self { - let dim_x = 6; - let mut state = StateVector::zeros(); + let state = StateVector::zeros(); let mut covariance = StateCovariance::identity() * 1e15; covariance[(StateIndex::Yaw as usize, StateIndex::Yaw as usize)] = 50.0; @@ -186,14 +182,12 @@ impl EKFModule { Self { params, - dim_x, state, covariance, z_filter, roll_filter, pitch_filter, accumulated_delay_times, - last_angular_velocity: Vector3::zeros(), is_mrm_mode: false, } } diff --git a/applications/tests/test_autoware/imu_corrector/src/lib.rs b/applications/tests/test_autoware/imu_corrector/src/lib.rs index e92acab4a..a32f8d850 100644 --- a/applications/tests/test_autoware/imu_corrector/src/lib.rs +++ b/applications/tests/test_autoware/imu_corrector/src/lib.rs @@ -3,7 +3,7 @@ extern crate alloc; use alloc::{format, string::String}; use imu_driver::{Header, ImuMsg, Quaternion, Vector3}; -use nalgebra::{Matrix3, Quaternion as NQuaternion, UnitQuaternion, Vector3 as NVector3}; +use nalgebra::{Quaternion as NQuaternion, UnitQuaternion, Vector3 as NVector3}; #[derive(Clone, Debug)] pub struct Transform { From 48f29f1a3d5e746c99984ba6bf31f0a505851e8c Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Wed, 15 Apr 2026 17:23:56 +0900 Subject: [PATCH 15/60] fix: delete warnings 3 Signed-off-by: nokosaaan --- applications/tests/test_autoware/src/lib.rs | 3 ++- awkernel_async_lib/src/pubsub.rs | 4 ++-- awkernel_async_lib/src/time_interval.rs | 6 +++--- 3 files changed, 7 insertions(+), 6 deletions(-) diff --git a/applications/tests/test_autoware/src/lib.rs b/applications/tests/test_autoware/src/lib.rs index f2c5ae8e5..2d58963da 100644 --- a/applications/tests/test_autoware/src/lib.rs +++ b/applications/tests/test_autoware/src/lib.rs @@ -1,4 +1,5 @@ #![no_std] +#![allow(static_mut_refs)] extern crate alloc; use alloc::{borrow::Cow, format, string::String, vec, vec::Vec}; @@ -51,7 +52,7 @@ pub async fn run() { log::info!("Starting Autoware test application with simplified TCP networking"); let dag = create_dag(); - let dag_id = dag.get_id(); + let _dag_id = dag.get_id(); dag.register_periodic_reactor::<_, (i32, i32, i32)>( "start_dummy_data".into(), diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index 109fb0682..8ad694c5a 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -384,11 +384,11 @@ where T: Clone + Sync + Send, { /// Send with metadata forwarded from `send_all_with_meta`. - pub async fn send_with_meta(&self, data: T, pub_id: u32, index: usize, node_id: u32) { + pub async fn send_with_meta(&self, data: T, _pub_id: u32, _index: usize, _node_id: u32) { #[cfg(not(feature = "relax-get-period"))] { let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - publish_timestamp_at(index, start, pub_id, node_id); + publish_timestamp_at(_index, start, _pub_id, _node_id); } let sender = Sender::new(self, data); diff --git a/awkernel_async_lib/src/time_interval.rs b/awkernel_async_lib/src/time_interval.rs index 8bf645887..10a87b0ec 100644 --- a/awkernel_async_lib/src/time_interval.rs +++ b/awkernel_async_lib/src/time_interval.rs @@ -101,12 +101,12 @@ pub fn interval(period: Duration, dag_id: u32) -> Interval { interval_at(Time::now(), period, dag_id) } -pub fn interval_at(start: Time, period: Duration, dag_id: u32) -> Interval { +pub fn interval_at(start: Time, period: Duration, _dag_id: u32) -> Interval { assert!(!period.is_zero(), "`period` must be non-zero."); #[cfg(not(feature = "relax-get-period"))] { - let index = get_period_count(dag_id.clone() as usize) as usize; - update_pre_send_outer_timestamp_at(index, start.uptime().as_nanos() as u64, dag_id.clone()); + let index = get_period_count(_dag_id.clone() as usize) as usize; + update_pre_send_outer_timestamp_at(index, start.uptime().as_nanos() as u64, _dag_id.clone()); } Interval { delay: None, From aed1c5c35acfe7e41f20bcd6efe90d30bc412df9 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Wed, 15 Apr 2026 17:40:40 +0900 Subject: [PATCH 16/60] fix: sync bootloader-fix Signed-off-by: nokosaaan --- x86bootdisk/Cargo.toml | 2 +- x86bootdisk/src/main.rs | 3 +++ 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/x86bootdisk/Cargo.toml b/x86bootdisk/Cargo.toml index 49afc75ae..fab5ac981 100644 --- a/x86bootdisk/Cargo.toml +++ b/x86bootdisk/Cargo.toml @@ -6,7 +6,7 @@ edition = "2021" # See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html [features] -default = ["bios", "uefi"] +default = ["uefi"] bios = ["bootloader/bios"] uefi = ["bootloader/uefi"] diff --git a/x86bootdisk/src/main.rs b/x86bootdisk/src/main.rs index d03aecedf..37a3899df 100644 --- a/x86bootdisk/src/main.rs +++ b/x86bootdisk/src/main.rs @@ -2,6 +2,9 @@ use clap::Parser; use ovmf_prebuilt::{Prebuilt, Source}; use std::{fs::File, io::Write, path::Path}; +#[cfg(not(any(feature = "bios", feature = "uefi")))] +compile_error!("At least one of the `bios` or `uefi` features must be enabled."); + #[cfg(feature = "bios")] use bootloader::BiosBoot; #[cfg(feature = "uefi")] From f024138ed849efcb6aaba72084ecb7f3811e3cbd Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Wed, 15 Apr 2026 17:53:52 +0900 Subject: [PATCH 17/60] sync bootloader-fix 2 Signed-off-by: nokosaaan --- Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Makefile b/Makefile index a6ac1121a..680e189f4 100644 --- a/Makefile +++ b/Makefile @@ -147,7 +147,7 @@ kernel-x86_64.elf: $(X86ASM) FORCE python3 scripts/embed_debug_info.py $@ x86_64_boot.img: kernel-x86_64.elf - RUSTFLAGS="$(RUSTC_MISC_ARGS)" cargo +$(RUSTV) run --release --package x86bootdisk --no-default-features --features bios -- --kernel $< --output $@ + RUSTFLAGS="$(RUSTC_MISC_ARGS)" cargo +$(RUSTV) run --release --package x86bootdisk --no-default-features --features bios -- --kernel $< --output $@ --boot-type bios x86_64_uefi.img: kernel-x86_64.elf RUSTFLAGS="$(RUSTC_MISC_ARGS)" cargo +$(RUSTV) run --release --package x86bootdisk --no-default-features --features uefi -- --kernel $< --output $@ --pxe x86_64_uefi_pxe_boot --boot-type uefi From 3aca1f93233d59b747b21f1ef9bb5bd1959e7e0e Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Wed, 15 Apr 2026 18:20:40 +0900 Subject: [PATCH 18/60] fix: add need-get-period feature Signed-off-by: nokosaaan --- applications/tests/test_autoware/Cargo.toml | 20 - .../test_autoware/ekf_localizer/Cargo.toml | 15 - .../test_autoware/ekf_localizer/src/lib.rs | 547 -- .../test_autoware/gyro_odometer/Cargo.toml | 12 - .../test_autoware/gyro_odometer/src/lib.rs | 441 -- .../test_autoware/imu_corrector/Cargo.toml | 11 - .../test_autoware/imu_corrector/src/lib.rs | 545 -- .../tests/test_autoware/imu_driver/Cargo.toml | 9 - .../tests/test_autoware/imu_driver/src/lib.rs | 260 - applications/tests/test_autoware/imu_raw.csv | 5709 ----------------- applications/tests/test_autoware/src/lib.rs | 637 -- .../vehicle_velocity_converter/Cargo.toml | 11 - .../vehicle_velocity_converter/src/lib.rs | 289 - .../tests/test_autoware/velocity_status.csv | 5700 ---------------- awkernel_async_lib/Cargo.toml | 2 +- awkernel_async_lib/src/dag.rs | 23 +- awkernel_async_lib/src/pubsub.rs | 2 +- awkernel_async_lib/src/task.rs | 4 +- awkernel_async_lib/src/time_interval.rs | 2 +- userland/Cargo.toml | 7 +- userland/src/lib.rs | 3 - 21 files changed, 15 insertions(+), 14234 deletions(-) delete mode 100644 applications/tests/test_autoware/Cargo.toml delete mode 100644 applications/tests/test_autoware/ekf_localizer/Cargo.toml delete mode 100644 applications/tests/test_autoware/ekf_localizer/src/lib.rs delete mode 100644 applications/tests/test_autoware/gyro_odometer/Cargo.toml delete mode 100644 applications/tests/test_autoware/gyro_odometer/src/lib.rs delete mode 100644 applications/tests/test_autoware/imu_corrector/Cargo.toml delete mode 100644 applications/tests/test_autoware/imu_corrector/src/lib.rs delete mode 100644 applications/tests/test_autoware/imu_driver/Cargo.toml delete mode 100644 applications/tests/test_autoware/imu_driver/src/lib.rs delete mode 100644 applications/tests/test_autoware/imu_raw.csv delete mode 100644 applications/tests/test_autoware/src/lib.rs delete mode 100644 applications/tests/test_autoware/vehicle_velocity_converter/Cargo.toml delete mode 100644 applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs delete mode 100644 applications/tests/test_autoware/velocity_status.csv diff --git a/applications/tests/test_autoware/Cargo.toml b/applications/tests/test_autoware/Cargo.toml deleted file mode 100644 index 5e7075844..000000000 --- a/applications/tests/test_autoware/Cargo.toml +++ /dev/null @@ -1,20 +0,0 @@ -[package] -name = "test_autoware" -version = "0.1.0" -edition = "2021" - -[lib] -path = "src/lib.rs" -crate-type = ["rlib"] - -[dependencies] -log = "0.4" -libm = "0.2" -csv-core = "0.1" -awkernel_async_lib = { path = "../../../awkernel_async_lib", default-features = false, features = ["relax-get-period"] } -awkernel_lib = { path = "../../../awkernel_lib", default-features = false } -imu_driver = { path = "./imu_driver", default-features = false } -imu_corrector = { path = "./imu_corrector", default-features = false } -vehicle_velocity_converter = { path = "./vehicle_velocity_converter", default-features = false } -gyro_odometer = { path = "./gyro_odometer", default-features = false} -ekf_localizer = { path = "./ekf_localizer", default-features = false} \ No newline at end of file diff --git a/applications/tests/test_autoware/ekf_localizer/Cargo.toml b/applications/tests/test_autoware/ekf_localizer/Cargo.toml deleted file mode 100644 index 92111e0cb..000000000 --- a/applications/tests/test_autoware/ekf_localizer/Cargo.toml +++ /dev/null @@ -1,15 +0,0 @@ -[package] -name = "ekf_localizer" -version = "0.1.0" -edition = "2021" - -[dependencies] -# no_std compatible dependencies -libm = "0.2" -nalgebra = { version = "0.32", default-features = false} -approx = "0.5" -imu_driver = { path = "../imu_driver", default-features = false } -vehicle_velocity_converter = { path = "../vehicle_velocity_converter", default-features = false} - -# Optional: for better math functions -micromath = "2.1" \ No newline at end of file diff --git a/applications/tests/test_autoware/ekf_localizer/src/lib.rs b/applications/tests/test_autoware/ekf_localizer/src/lib.rs deleted file mode 100644 index 99c7d9410..000000000 --- a/applications/tests/test_autoware/ekf_localizer/src/lib.rs +++ /dev/null @@ -1,547 +0,0 @@ -#![no_std] -#![allow(non_snake_case)] - -extern crate alloc; - -use alloc::{vec, vec::Vec}; -use core::ptr::null_mut; -use core::sync::atomic::{AtomicPtr, Ordering as AtomicOrdering}; -use libm::{atan2, cos, sin}; -use nalgebra::{Matrix6, Vector3, Vector6}; -pub use imu_driver; -pub use vehicle_velocity_converter::TwistWithCovariance; - -static EKF_MODULE_INSTANCE: AtomicPtr = AtomicPtr::new(null_mut()); - -#[derive(Debug, Clone, Copy, PartialEq)] -pub enum StateIndex { - X = 0, - Y = 1, - Yaw = 2, - YawBias = 3, - Vx = 4, - Wz = 5, -} - -pub type StateVector = Vector6; -pub type StateCovariance = Matrix6; - -#[derive(Debug, Clone, Copy)] -pub struct Point3D { - pub x: f64, - pub y: f64, - pub z: f64, -} - -#[derive(Debug, Clone, Copy)] -pub struct Quaternion { - pub x: f64, - pub y: f64, - pub z: f64, - pub w: f64, -} - -#[derive(Debug, Clone, Copy)] -pub struct Pose { - pub position: Point3D, - pub orientation: Quaternion, -} - -#[derive(Debug, Clone, Copy)] -pub struct Twist { - pub linear: Vector3, - pub angular: Vector3, -} - -#[derive(Debug, Clone, Copy)] -pub struct PoseWithCovariance { - pub pose: Pose, - pub covariance: [f64; 36], -} - -#[derive(Debug, Clone)] -pub struct EKFOdometry { - pub header: imu_driver::Header, - pub child_frame_id: &'static str, - pub pose: PoseWithCovariance, - pub twist: TwistWithCovariance, -} - -#[derive(Debug, Clone)] -pub struct EKFParameters { - pub enable_yaw_bias_estimation: bool, - pub extend_state_step: usize, - pub proc_stddev_vx_c: f64, - pub proc_stddev_wz_c: f64, - pub proc_stddev_yaw_c: f64, - pub z_filter_proc_dev: f64, - pub roll_filter_proc_dev: f64, - pub pitch_filter_proc_dev: f64, -} - -impl Default for EKFParameters { - fn default() -> Self { - Self { - enable_yaw_bias_estimation: true, - extend_state_step: 50, - proc_stddev_vx_c: 2.0, - proc_stddev_wz_c: 1.0, - proc_stddev_yaw_c: 0.005, - z_filter_proc_dev: 1.0, - roll_filter_proc_dev: 0.1, - pitch_filter_proc_dev: 0.1, - } - } -} - -#[derive(Debug, Clone)] -pub struct Simple1DFilter { - initialized: bool, - x: f64, - var: f64, - proc_var_x_c: f64, -} - -impl Simple1DFilter { - pub fn new() -> Self { - Self { - initialized: false, - x: 0.0, - var: 1e9, - proc_var_x_c: 0.0, - } - } - - pub fn init(&mut self, init_obs: f64, obs_var: f64) { - self.x = init_obs; - self.var = obs_var; - self.initialized = true; - } - - pub fn update(&mut self, obs: f64, obs_var: f64, dt: f64) { - if !self.initialized { - self.init(obs, obs_var); - return; - } - - let proc_var_x_d = self.proc_var_x_c * dt * dt; - self.var = self.var + proc_var_x_d; - - let kalman_gain = self.var / (self.var + obs_var); - self.x = self.x + kalman_gain * (obs - self.x); - self.var = (1.0 - kalman_gain) * self.var; - } - - pub fn set_proc_var(&mut self, proc_var: f64) { - self.proc_var_x_c = proc_var; - } - - pub fn get_x(&self) -> f64 { - self.x - } - - pub fn get_var(&self) -> f64 { - self.var - } -} - -#[derive(Debug, Clone)] -pub struct EKFModule { - params: EKFParameters, - state: StateVector, - covariance: StateCovariance, - z_filter: Simple1DFilter, - roll_filter: Simple1DFilter, - pitch_filter: Simple1DFilter, - accumulated_delay_times: Vec, - // When true, only prediction is performed (no measurement updates) - is_mrm_mode: bool, -} - -impl EKFModule { - pub fn new(params: EKFParameters) -> Self { - let state = StateVector::zeros(); - let mut covariance = StateCovariance::identity() * 1e15; - - covariance[(StateIndex::Yaw as usize, StateIndex::Yaw as usize)] = 50.0; - if params.enable_yaw_bias_estimation { - covariance[(StateIndex::YawBias as usize, StateIndex::YawBias as usize)] = 50.0; - } - covariance[(StateIndex::Vx as usize, StateIndex::Vx as usize)] = 1000.0; - covariance[(StateIndex::Wz as usize, StateIndex::Wz as usize)] = 50.0; - - let mut z_filter = Simple1DFilter::new(); - let mut roll_filter = Simple1DFilter::new(); - let mut pitch_filter = Simple1DFilter::new(); - - z_filter.set_proc_var(params.z_filter_proc_dev * params.z_filter_proc_dev); - roll_filter.set_proc_var(params.roll_filter_proc_dev * params.roll_filter_proc_dev); - pitch_filter.set_proc_var(params.pitch_filter_proc_dev * params.pitch_filter_proc_dev); - - let accumulated_delay_times = vec![1e15; params.extend_state_step]; - - Self { - params, - state, - covariance, - z_filter, - roll_filter, - pitch_filter, - accumulated_delay_times, - is_mrm_mode: false, - } - } - - pub fn initialize(&mut self, initial_pose: Pose) { - self.state[StateIndex::X as usize] = initial_pose.position.x; - self.state[StateIndex::Y as usize] = initial_pose.position.y; - self.state[StateIndex::Yaw as usize] = self.quaternion_to_yaw(initial_pose.orientation); - self.state[StateIndex::YawBias as usize] = 0.0; - self.state[StateIndex::Vx as usize] = 0.0; - self.state[StateIndex::Wz as usize] = 0.0; - - self.covariance = StateCovariance::identity() * 0.01; - if self.params.enable_yaw_bias_estimation { - self.covariance[(StateIndex::YawBias as usize, StateIndex::YawBias as usize)] = 0.0001; - } - - self.z_filter.init(initial_pose.position.z, 0.01); - self.roll_filter.init(0.0, 0.01); - self.pitch_filter.init(0.0, 0.01); - } - - fn predict_next_state(&self, dt: f64) -> StateVector { - let mut x_next = self.state.clone(); - let x = self.state[StateIndex::X as usize]; - let y = self.state[StateIndex::Y as usize]; - let yaw = self.state[StateIndex::Yaw as usize]; - let yaw_bias = self.state[StateIndex::YawBias as usize]; - let vx = self.state[StateIndex::Vx as usize]; - let wz = self.state[StateIndex::Wz as usize]; - - x_next[StateIndex::X as usize] = x + vx * cos(yaw + yaw_bias) * dt; - x_next[StateIndex::Y as usize] = y + vx * sin(yaw + yaw_bias) * dt; - let yaw_next = yaw + wz * dt; - x_next[StateIndex::Yaw as usize] = atan2(sin(yaw_next), cos(yaw_next)); - x_next[StateIndex::YawBias as usize] = yaw_bias; - x_next[StateIndex::Vx as usize] = vx; - x_next[StateIndex::Wz as usize] = wz; - - x_next - } - - fn create_state_transition_matrix(&self, dt: f64) -> Matrix6 { - let mut F = Matrix6::identity(); - let yaw = self.state[StateIndex::Yaw as usize]; - let yaw_bias = self.state[StateIndex::YawBias as usize]; - let vx = self.state[StateIndex::Vx as usize]; - - F[(StateIndex::X as usize, StateIndex::Yaw as usize)] = -vx * sin(yaw + yaw_bias) * dt; - F[(StateIndex::X as usize, StateIndex::YawBias as usize)] = -vx * sin(yaw + yaw_bias) * dt; - F[(StateIndex::X as usize, StateIndex::Vx as usize)] = cos(yaw + yaw_bias) * dt; - - F[(StateIndex::Y as usize, StateIndex::Yaw as usize)] = vx * cos(yaw + yaw_bias) * dt; - F[(StateIndex::Y as usize, StateIndex::YawBias as usize)] = vx * cos(yaw + yaw_bias) * dt; - F[(StateIndex::Y as usize, StateIndex::Vx as usize)] = sin(yaw + yaw_bias) * dt; - - F[(StateIndex::Yaw as usize, StateIndex::Wz as usize)] = dt; - - F - } - - fn process_noise_covariance(&self, dt: f64) -> Matrix6 { - let mut Q = Matrix6::zeros(); - - Q[(StateIndex::Vx as usize, StateIndex::Vx as usize)] = - self.params.proc_stddev_vx_c * self.params.proc_stddev_vx_c * dt * dt; - Q[(StateIndex::Wz as usize, StateIndex::Wz as usize)] = - self.params.proc_stddev_wz_c * self.params.proc_stddev_wz_c * dt * dt; - Q[(StateIndex::Yaw as usize, StateIndex::Yaw as usize)] = - self.params.proc_stddev_yaw_c * self.params.proc_stddev_yaw_c * dt * dt; - - Q[(StateIndex::X as usize, StateIndex::X as usize)] = 0.0; - Q[(StateIndex::Y as usize, StateIndex::Y as usize)] = 0.0; - Q[(StateIndex::YawBias as usize, StateIndex::YawBias as usize)] = 0.0; - - Q - } - - pub fn predict(&mut self, dt: f64) { - self.state = self.predict_next_state(dt); - let F = self.create_state_transition_matrix(dt); - let Q = self.process_noise_covariance(dt); - self.covariance = F * self.covariance * F.transpose() + Q; - self.accumulate_delay_time(dt); - } - - pub fn predict_with_delay(&mut self, dt: f64) { - self.predict(dt); - } - - pub fn predict_only(&mut self, dt: f64) { - self.predict(dt); - } - - pub fn get_current_pose(&self, get_biased_yaw: bool) -> Pose { - let z = self.z_filter.get_x(); - let roll = self.roll_filter.get_x(); - let pitch = self.pitch_filter.get_x(); - - let x = self.state[StateIndex::X as usize]; - let y = self.state[StateIndex::Y as usize]; - let biased_yaw = self.state[StateIndex::Yaw as usize]; - let yaw_bias = self.state[StateIndex::YawBias as usize]; - - let yaw = if get_biased_yaw { - biased_yaw - } else { - biased_yaw + yaw_bias - }; - - Pose { - position: Point3D { x, y, z }, - orientation: self.rpy_to_quaternion(roll, pitch, yaw), - } - } - - pub fn get_current_twist(&self) -> Twist { - let vx = self.state[StateIndex::Vx as usize]; - let wz = self.state[StateIndex::Wz as usize]; - - Twist { - linear: Vector3::new(vx, 0.0, 0.0), - angular: Vector3::new(0.0, 0.0, wz), - } - } - - pub fn get_yaw_bias(&self) -> f64 { - self.state[StateIndex::YawBias as usize] - } - - pub fn get_current_pose_with_covariance(&self) -> PoseWithCovariance { - let pose = self.get_current_pose(false); - let pose_covariance = self.get_current_pose_covariance(); - PoseWithCovariance { - pose, - covariance: pose_covariance, - } - } - - pub fn get_current_pose_covariance(&self) -> [f64; 36] { - let mut cov = [0.0; 36]; - - for i in 0..6 { - for j in 0..6 { - cov[i * 6 + j] = self.covariance[(i, j)]; - } - } - - cov[14] = self.z_filter.get_var(); - cov[21] = self.roll_filter.get_var(); - cov[28] = self.pitch_filter.get_var(); - - cov - } - - pub fn get_current_twist_covariance(&self) -> [f64; 36] { - let mut cov = [0.0; 36]; - - cov[0] = self.covariance[(StateIndex::Vx as usize, StateIndex::Vx as usize)]; - cov[35] = self.covariance[(StateIndex::Wz as usize, StateIndex::Wz as usize)]; - - cov - } - - pub fn update_velocity(&mut self, vx_measurement: f64, wz_measurement: f64) { - if self.is_mrm_mode { - return; - } - - let vx_obs_var = 1.0; - let wz_obs_var = 0.1; - - let vx_var = self.covariance[(StateIndex::Vx as usize, StateIndex::Vx as usize)]; - let vx_gain = vx_var / (vx_var + vx_obs_var); - self.state[StateIndex::Vx as usize] = self.state[StateIndex::Vx as usize] - + vx_gain * (vx_measurement - self.state[StateIndex::Vx as usize]); - self.covariance[(StateIndex::Vx as usize, StateIndex::Vx as usize)] = - (1.0 - vx_gain) * vx_var; - - let wz_var = self.covariance[(StateIndex::Wz as usize, StateIndex::Wz as usize)]; - let wz_gain = wz_var / (wz_var + wz_obs_var); - self.state[StateIndex::Wz as usize] = self.state[StateIndex::Wz as usize] - + wz_gain * (wz_measurement - self.state[StateIndex::Wz as usize]); - self.covariance[(StateIndex::Wz as usize, StateIndex::Wz as usize)] = - (1.0 - wz_gain) * wz_var; - } - - pub fn set_mrm_mode(&mut self, is_mrm: bool) { - self.is_mrm_mode = is_mrm; - } - - pub fn is_mrm(&self) -> bool { - self.is_mrm_mode - } - - pub fn accumulate_delay_time(&mut self, dt: f64) { - let len = self.accumulated_delay_times.len(); - if len == 0 { - return; - } - - let last_time = self.accumulated_delay_times[len - 1]; - let new_time = last_time + dt; - - for i in 0..len - 1 { - self.accumulated_delay_times[i] = self.accumulated_delay_times[i + 1]; - } - self.accumulated_delay_times[len - 1] = new_time; - } - - pub fn find_closest_delay_time_index(&self, target_value: f64) -> usize { - let len = self.accumulated_delay_times.len(); - if len == 0 { - return 0; - } - - if target_value > self.accumulated_delay_times[len - 1] { - return len; - } - - let mut closest_index = 0; - let mut min_diff = f64::MAX; - - for i in 0..len { - let time = self.accumulated_delay_times[i]; - let diff = (target_value - time).abs(); - if diff < min_diff { - min_diff = diff; - closest_index = i; - } - } - - closest_index - } - - fn quaternion_to_yaw(&self, q: Quaternion) -> f64 { - atan2( - 2.0 * (q.w * q.z + q.x * q.y), - 1.0 - 2.0 * (q.y * q.y + q.z * q.z), - ) - } - - fn rpy_to_quaternion(&self, roll: f64, pitch: f64, yaw: f64) -> Quaternion { - let cy = cos(yaw * 0.5); - let sy = sin(yaw * 0.5); - let cp = cos(pitch * 0.5); - let sp = sin(pitch * 0.5); - let cr = cos(roll * 0.5); - let sr = sin(roll * 0.5); - - Quaternion { - w: cr * cp * cy + sr * sp * sy, - x: sr * cp * cy - cr * sp * sy, - y: cr * sp * cy + sr * cp * sy, - z: cr * cp * sy - sr * sp * cy, - } - } -} - -pub fn get_or_initialize_default_module() -> &'static mut EKFModule { - let existing = EKF_MODULE_INSTANCE.load(AtomicOrdering::Acquire); - if !existing.is_null() { - return unsafe { &mut *existing }; - } - - let boxed = alloc::boxed::Box::new(EKFModule::new(EKFParameters::default())); - let ptr = alloc::boxed::Box::into_raw(boxed); - - match EKF_MODULE_INSTANCE.compare_exchange( - null_mut(), - ptr, - AtomicOrdering::AcqRel, - AtomicOrdering::Acquire, - ) { - Ok(_) => unsafe { &mut *ptr }, - Err(existing_ptr) => unsafe { - let _ = alloc::boxed::Box::from_raw(ptr); - &mut *existing_ptr - }, - } -} - -#[cfg(test)] -mod tests { - use super::*; - - #[test] - fn test_ekf_initialization() { - let params = EKFParameters::default(); - let mut ekf = EKFModule::new(params); - - let initial_pose = Pose { - position: Point3D { - x: 1.0, - y: 2.0, - z: 0.0, - }, - orientation: Quaternion { - x: 0.0, - y: 0.0, - z: 0.0, - w: 1.0, - }, - }; - - ekf.initialize(initial_pose); - - let pose = ekf.get_current_pose(false); - assert!((pose.position.x - 1.0).abs() < 1e-6); - assert!((pose.position.y - 2.0).abs() < 1e-6); - } - - #[test] - fn test_quaternion_conversions() { - let params = EKFParameters::default(); - let ekf = EKFModule::new(params); - - let roll = 0.1; - let pitch = 0.2; - let yaw = 0.3; - - let q = ekf.rpy_to_quaternion(roll, pitch, yaw); - let (r, p, y) = ekf.quaternion_to_rpy(q); - - assert!((roll - r).abs() < 1e-6); - assert!((pitch - p).abs() < 1e-6); - assert!((yaw - y).abs() < 1e-6); - } - - #[test] - fn test_pose_with_covariance_generation() { - let params = EKFParameters::default(); - let mut ekf = EKFModule::new(params); - - let initial_pose = Pose { - position: Point3D { - x: 1.0, - y: 2.0, - z: 0.0, - }, - orientation: Quaternion { - x: 0.0, - y: 0.0, - z: 0.0, - w: 1.0, - }, - }; - - ekf.initialize(initial_pose); - - let pose_with_cov = ekf.get_current_pose_with_covariance(); - - assert!((pose_with_cov.pose.position.x - 1.0).abs() < 1e-6); - assert!((pose_with_cov.pose.position.y - 2.0).abs() < 1e-6); - assert_eq!(pose_with_cov.covariance.len(), 36); - } -} diff --git a/applications/tests/test_autoware/gyro_odometer/Cargo.toml b/applications/tests/test_autoware/gyro_odometer/Cargo.toml deleted file mode 100644 index b7890f557..000000000 --- a/applications/tests/test_autoware/gyro_odometer/Cargo.toml +++ /dev/null @@ -1,12 +0,0 @@ -[package] -name = "gyro_odometer" -version = "0.1.0" -edition = "2021" - -[dependencies] -log = "0.4" -awkernel_async_lib = { path = "../../../../awkernel_async_lib", default-features = false } -awkernel_lib = { path = "../../../../awkernel_lib", default-features = false } -imu_driver = { path = "../imu_driver", default-features = false } -imu_corrector = { path = "../imu_corrector", default-features = false } -vehicle_velocity_converter = { path = "../vehicle_velocity_converter", default-features = false} \ No newline at end of file diff --git a/applications/tests/test_autoware/gyro_odometer/src/lib.rs b/applications/tests/test_autoware/gyro_odometer/src/lib.rs deleted file mode 100644 index 743015e1c..000000000 --- a/applications/tests/test_autoware/gyro_odometer/src/lib.rs +++ /dev/null @@ -1,441 +0,0 @@ -#![no_std] -extern crate alloc; - -use alloc::{collections::VecDeque, string::String}; -use core::time::Duration; -use core::ptr::null_mut; -use core::sync::atomic::{AtomicPtr, Ordering as AtomicOrdering}; - -pub use imu_corrector::{transform_covariance, ImuWithCovariance, Transform}; -pub use imu_driver::{Header, ImuMsg, Quaternion, Vector3}; -pub use vehicle_velocity_converter::{ - Odometry, Twist, TwistWithCovariance, TwistWithCovarianceStamped, -}; - -static GYRO_ODOMETER_INSTANCE: AtomicPtr = AtomicPtr::new(null_mut()); - -const COV_IDX_X_X: usize = 0; -const COV_IDX_Y_Y: usize = 4; -const COV_IDX_Z_Z: usize = 8; -const COV_IDX_XYZRPY_X_X: usize = 0; -const COV_IDX_XYZRPY_Y_Y: usize = 7; -const COV_IDX_XYZRPY_Z_Z: usize = 14; -const COV_IDX_XYZRPY_ROLL_ROLL: usize = 21; -const COV_IDX_XYZRPY_PITCH_PITCH: usize = 28; -const COV_IDX_XYZRPY_YAW_YAW: usize = 35; - -pub struct GyroOdometerCore { - pub output_frame: String, - pub message_timeout_sec: f64, - pub vehicle_twist_arrived: bool, - pub imu_arrived: bool, - pub vehicle_twist_queue: VecDeque, - pub gyro_queue: VecDeque, - pub config: GyroOdometerConfig, -} - -impl GyroOdometerCore { - pub fn new(config: GyroOdometerConfig) -> Result { - let queue_size = config.queue_size; - let output_frame = config.output_frame.clone(); - let message_timeout_sec = config.message_timeout_sec; - - Ok(Self { - output_frame, - message_timeout_sec, - vehicle_twist_arrived: false, - imu_arrived: false, - vehicle_twist_queue: VecDeque::with_capacity(queue_size), - gyro_queue: VecDeque::with_capacity(queue_size), - config, - }) - } - - pub fn concat_gyro_and_odometer( - &mut self, - current_time: u64, - ) -> Result> { - if !self.vehicle_twist_arrived { - self.vehicle_twist_queue.clear(); - self.gyro_queue.clear(); - return Ok(None); - } - if !self.imu_arrived { - self.vehicle_twist_queue.clear(); - self.gyro_queue.clear(); - return Ok(None); - } - if !self.vehicle_twist_queue.is_empty() && !self.gyro_queue.is_empty() { - let latest_vehicle_twist_stamp = - self.vehicle_twist_queue.back().unwrap().header.timestamp; - let latest_imu_stamp = self.gyro_queue.back().unwrap().header.timestamp; - - if Self::check_timeout( - current_time, - latest_vehicle_twist_stamp, - self.message_timeout_sec, - ) { - self.vehicle_twist_queue.clear(); - self.gyro_queue.clear(); - return Err(GyroOdometerError::TimeoutError(String::from( - "Vehicle twist message timeout", - ))); - } - - if Self::check_timeout(current_time, latest_imu_stamp, self.message_timeout_sec) { - self.vehicle_twist_queue.clear(); - self.gyro_queue.clear(); - return Err(GyroOdometerError::TimeoutError(String::from( - "IMU message timeout", - ))); - } - } - - if self.vehicle_twist_queue.is_empty() || self.gyro_queue.is_empty() { - return Ok(None); - } - - let tf = self.get_transform( - &self.gyro_queue.front().unwrap().header.frame_id, - &self.output_frame, - )?; - - for gyro in &mut self.gyro_queue { - let transformed_angular_velocity = tf.apply_to_vector(gyro.angular_velocity.clone()); - gyro.angular_velocity = transformed_angular_velocity; - } - - let mut vx_mean = 0.0; - let mut gyro_mean = Vector3::new(0.0, 0.0, 0.0); - let mut vx_covariance_original = 0.0; - let mut gyro_covariance_original = Vector3::new(0.0, 0.0, 0.0); - - for vehicle_twist in &self.vehicle_twist_queue { - vx_mean += vehicle_twist.twist.twist.linear.x; - vx_covariance_original += vehicle_twist.twist.covariance[0 * 6 + 0]; - } - vx_mean /= self.vehicle_twist_queue.len() as f64; - vx_covariance_original /= self.vehicle_twist_queue.len() as f64; - - for gyro in &self.gyro_queue { - gyro_mean.x += gyro.angular_velocity.x; - gyro_mean.y += gyro.angular_velocity.y; - gyro_mean.z += gyro.angular_velocity.z; - gyro_covariance_original.x += gyro.angular_velocity_covariance[COV_IDX_X_X]; - gyro_covariance_original.y += gyro.angular_velocity_covariance[COV_IDX_Y_Y]; - gyro_covariance_original.z += gyro.angular_velocity_covariance[COV_IDX_Z_Z]; - } - gyro_mean.x /= self.gyro_queue.len() as f64; - gyro_mean.y /= self.gyro_queue.len() as f64; - gyro_mean.z /= self.gyro_queue.len() as f64; - gyro_covariance_original.x /= self.gyro_queue.len() as f64; - gyro_covariance_original.y /= self.gyro_queue.len() as f64; - gyro_covariance_original.z /= self.gyro_queue.len() as f64; - - let latest_vehicle_twist_stamp = self.vehicle_twist_queue.back().unwrap().header.timestamp; - let latest_imu_stamp = self.gyro_queue.back().unwrap().header.timestamp; - - let result_timestamp = if latest_vehicle_twist_stamp < latest_imu_stamp { - latest_imu_stamp - } else { - latest_vehicle_twist_stamp - }; - - let mut result = TwistWithCovarianceStamped { - header: Header { - frame_id: self.gyro_queue.front().unwrap().header.frame_id, - timestamp: result_timestamp, - }, - twist: TwistWithCovariance { - twist: Twist { - linear: Vector3::new(vx_mean, 0.0, 0.0), - angular: gyro_mean, - }, - covariance: [0.0; 36], - }, - }; - - result.twist.covariance[COV_IDX_XYZRPY_X_X] = - vx_covariance_original / self.vehicle_twist_queue.len() as f64; - result.twist.covariance[COV_IDX_XYZRPY_Y_Y] = 100000.0; - result.twist.covariance[COV_IDX_XYZRPY_Z_Z] = 100000.0; - result.twist.covariance[COV_IDX_XYZRPY_ROLL_ROLL] = - gyro_covariance_original.x / self.gyro_queue.len() as f64; - result.twist.covariance[COV_IDX_XYZRPY_PITCH_PITCH] = - gyro_covariance_original.y / self.gyro_queue.len() as f64; - result.twist.covariance[COV_IDX_XYZRPY_YAW_YAW] = - gyro_covariance_original.z / self.gyro_queue.len() as f64; - - self.vehicle_twist_queue.clear(); - self.gyro_queue.clear(); - - Ok(Some(result)) - } - - pub fn check_timeout(current_timestamp: u64, last_timestamp: u64, timeout_sec: f64) -> bool { - let dt = (current_timestamp as f64 - last_timestamp as f64) / 1_000_000_000.0; - dt.abs() > timeout_sec - } - pub fn get_transform(&self, from_frame: &str, to_frame: &str) -> Result { - if from_frame == to_frame || from_frame == "" || to_frame == "" { - Ok(Transform::identity()) - } else { - Ok(Transform::identity()) - } - } - - pub fn process_result( - &self, - twist_with_cov_raw: TwistWithCovarianceStamped, - ) -> TwistWithCovarianceStamped { - if twist_with_cov_raw.twist.twist.angular.z.abs() < 0.01 - && twist_with_cov_raw.twist.twist.linear.x.abs() < 0.01 - { - let mut twist = twist_with_cov_raw; - twist.twist.twist.angular.x = 0.0; - twist.twist.twist.angular.y = 0.0; - twist.twist.twist.angular.z = 0.0; - twist - } else { - twist_with_cov_raw - } - } - - pub fn convert_vehicle_velocity_to_twist( - &self, - odometry: &Odometry, - timestamp: u64, - ) -> TwistWithCovarianceStamped { - TwistWithCovarianceStamped { - header: Header { - frame_id: "base_link", - timestamp, - }, - twist: TwistWithCovariance { - twist: Twist { - linear: Vector3::new(odometry.velocity, 0.0, 0.0), - angular: Vector3::new(0.0, 0.0, 0.0), - }, - covariance: [0.0; 36], - }, - } - } - - pub fn add_vehicle_twist(&mut self, twist: TwistWithCovarianceStamped) { - self.vehicle_twist_arrived = true; - self.vehicle_twist_queue.push_back(twist); - } - - pub fn add_imu(&mut self, imu: ImuWithCovariance) { - self.imu_arrived = true; - self.gyro_queue.push_back(imu); - } - - pub fn process_and_get_result( - &mut self, - current_time: u64, - ) -> Option { - match self.concat_gyro_and_odometer(current_time) { - Ok(result) => result, - Err(_) => None, - } - } - - pub fn get_queue_sizes(&self) -> (usize, usize) { - (self.vehicle_twist_queue.len(), self.gyro_queue.len()) - } - - pub fn clear_queues(&mut self) { - self.vehicle_twist_queue.clear(); - self.gyro_queue.clear(); - } - - pub fn reset_arrival_flags(&mut self) { - self.vehicle_twist_arrived = false; - self.imu_arrived = false; - } -} - -#[derive(Debug)] -pub enum GyroOdometerError { - TransformError(String), - TimeoutError(String), - QueueError(String), - ParameterError(String), -} - -impl core::fmt::Display for GyroOdometerError { - fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result { - match self { - GyroOdometerError::TransformError(msg) => write!(f, "Transform error: {}", msg), - GyroOdometerError::TimeoutError(msg) => write!(f, "Timeout error: {}", msg), - GyroOdometerError::QueueError(msg) => write!(f, "Queue error: {}", msg), - GyroOdometerError::ParameterError(msg) => write!(f, "Invalid parameter: {}", msg), - } - } -} - -impl core::error::Error for GyroOdometerError {} - -type Result = core::result::Result; - -#[derive(Debug, Clone)] -pub struct GyroOdometerConfig { - pub output_frame: String, - pub message_timeout_sec: f64, - pub queue_size: usize, - pub transform_timeout: Duration, - pub min_velocity_threshold: f64, - pub covariance_scale: f64, -} - -impl Default for GyroOdometerConfig { - fn default() -> Self { - Self { - output_frame: String::from("base_link"), - message_timeout_sec: 1.0, - queue_size: 100, - transform_timeout: Duration::from_secs(1), - min_velocity_threshold: 0.01, - covariance_scale: 100000.0, - } - } -} - -#[cfg(test)] -mod tests { - use super::*; - - #[test] - fn test_gyro_odometer_core_creation() { - let config = GyroOdometerConfig::default(); - let core = GyroOdometerCore::new(config); - assert!(core.is_ok()); - } - - #[test] - fn test_imu_with_covariance_conversion() { - let imu_msg = ImuMsg { - header: Header { - frame_id: "imu_link", - timestamp: 123456789, - }, - orientation: Quaternion { - x: 0.0, - y: 0.0, - z: 0.0, - w: 1.0, - }, - angular_velocity: Vector3::new(0.1, 0.2, 0.3), - linear_acceleration: Vector3::new(9.8, 0.0, 0.0), - }; - - let imu_with_cov = ImuWithCovariance::from_imu_msg(&imu_msg); - let converted_back = imu_with_cov.to_imu_msg(); - - assert_eq!(imu_msg.header.frame_id, converted_back.header.frame_id); - assert_eq!(imu_msg.header.timestamp, converted_back.header.timestamp); - assert_eq!( - imu_msg.angular_velocity.x, - converted_back.angular_velocity.x - ); - assert_eq!( - imu_msg.angular_velocity.y, - converted_back.angular_velocity.y - ); - assert_eq!( - imu_msg.angular_velocity.z, - converted_back.angular_velocity.z - ); - } - - #[test] - fn test_vehicle_velocity_conversion() { - let config = GyroOdometerConfig::default(); - let core = GyroOdometerCore::new(config).unwrap(); - - let odometry = Odometry { velocity: 15.5 }; - let twist = core.convert_vehicle_velocity_to_twist(&odometry, 123456789); - - assert_eq!(twist.header.frame_id, "base_link"); - assert_eq!(twist.header.timestamp, 123456789); - assert_eq!(twist.twist.twist.linear.x, 15.5); - assert_eq!(twist.twist.twist.linear.y, 0.0); - assert_eq!(twist.twist.twist.linear.z, 0.0); - } - - #[test] - fn test_imu_corrector_integration() { - let config = GyroOdometerConfig::default(); - let mut core = GyroOdometerCore::new(config).unwrap(); - - let imu_with_cov = ImuWithCovariance { - header: Header { - frame_id: "imu_link", - timestamp: 123456789, - }, - orientation: Quaternion { - x: 0.0, - y: 0.0, - z: 0.0, - w: 1.0, - }, - angular_velocity: Vector3::new(0.1, 0.2, 0.3), - angular_velocity_covariance: [0.0009, 0.0, 0.0, 0.0, 0.0009, 0.0, 0.0, 0.0, 0.0009], // 0.03^2 - linear_acceleration: Vector3::new(9.8, 0.0, 0.0), - linear_acceleration_covariance: [ - 100000000.0, - 0.0, - 0.0, - 0.0, - 100000000.0, - 0.0, - 0.0, - 0.0, - 100000000.0, - ], - }; - - let result = core.process_imu_with_covariance(imu_with_cov); - assert!(result.is_ok()); - } - - #[test] - fn test_transform_covariance_from_imu_corrector() { - let input = [1.0, 0.0, 0.0, 0.0, 2.0, 0.0, 0.0, 0.0, 3.0]; - let output = transform_covariance(&input); - assert_eq!(output[COV_IDX_X_X], 3.0); - assert_eq!(output[COV_IDX_Y_Y], 3.0); - assert_eq!(output[COV_IDX_Z_Z], 3.0); - } -} - -pub fn get_or_initialize() -> Result<&'static mut GyroOdometerCore> { - let ptr = GYRO_ODOMETER_INSTANCE.load(AtomicOrdering::Acquire); - - if !ptr.is_null() { - return Ok(unsafe { &mut *ptr }); - } - - let config = GyroOdometerConfig::default(); - let core = GyroOdometerCore::new(config)?; - let boxed_core = alloc::boxed::Box::new(core); - let new_ptr = alloc::boxed::Box::into_raw(boxed_core); - - match GYRO_ODOMETER_INSTANCE.compare_exchange( - null_mut(), - new_ptr, - AtomicOrdering::Acquire, - AtomicOrdering::Relaxed, - ) { - Ok(_) => { - Ok(unsafe { &mut *new_ptr }) - } - Err(existing_ptr) => { - unsafe { - let _ = alloc::boxed::Box::from_raw(new_ptr); - } - Ok(unsafe { &mut *existing_ptr }) - } - } -} diff --git a/applications/tests/test_autoware/imu_corrector/Cargo.toml b/applications/tests/test_autoware/imu_corrector/Cargo.toml deleted file mode 100644 index 30b5ce849..000000000 --- a/applications/tests/test_autoware/imu_corrector/Cargo.toml +++ /dev/null @@ -1,11 +0,0 @@ -[package] -name = "imu_corrector" -version = "0.1.0" -edition = "2021" - -[dependencies] -log = "0.4" -nalgebra = { version = "0.32", default-features = false, features = ["libm"] } -awkernel_async_lib = { path = "../../../../awkernel_async_lib", default-features = false } -awkernel_lib = { path = "../../../../awkernel_lib", default-features = false } -imu_driver = { path = "../imu_driver", default-features = false } \ No newline at end of file diff --git a/applications/tests/test_autoware/imu_corrector/src/lib.rs b/applications/tests/test_autoware/imu_corrector/src/lib.rs deleted file mode 100644 index a32f8d850..000000000 --- a/applications/tests/test_autoware/imu_corrector/src/lib.rs +++ /dev/null @@ -1,545 +0,0 @@ -#![no_std] -extern crate alloc; - -use alloc::{format, string::String}; -use imu_driver::{Header, ImuMsg, Quaternion, Vector3}; -use nalgebra::{Quaternion as NQuaternion, UnitQuaternion, Vector3 as NVector3}; - -#[derive(Clone, Debug)] -pub struct Transform { - pub translation: Vector3, - pub rotation: Quaternion, -} - -impl Transform { - pub fn identity() -> Self { - Self { - translation: imu_driver::Vector3::new(5.22444, 0.07615, 2.72762), // use aip_x2_gen2_description. - rotation: imu_driver::Quaternion { - x: 1.0, - y: 0.0, - z: 0.0, - w: 0.0, - }, - } - } - - fn to_nalgebra_vector3(&self, vec: &Vector3) -> NVector3 { - NVector3::new(vec.x, vec.y, vec.z) - } - - fn to_imu_vector3(&self, vec: &NVector3) -> Vector3 { - Vector3::new(vec.x, vec.y, vec.z) - } - - fn to_nalgebra_quaternion(&self, quat: &Quaternion) -> UnitQuaternion { - let n_quat = NQuaternion::new(quat.w, quat.x, quat.y, quat.z); - UnitQuaternion::from_quaternion(n_quat) - } - - pub fn apply_to_vector(&self, vec: Vector3) -> Vector3 { - let nalgebra_vec = self.to_nalgebra_vector3(&vec); - let nalgebra_quat = self.to_nalgebra_quaternion(&self.rotation); - let nalgebra_trans = self.to_nalgebra_vector3(&self.translation); - let rotated = nalgebra_quat * nalgebra_vec; - let result = rotated + nalgebra_trans; - self.to_imu_vector3(&result) - } -} - -pub trait TransformListener { - fn get_latest_transform(&self, from_frame: &str, to_frame: &str) -> Option; - fn get_transform_at_time( - &self, - from_frame: &str, - to_frame: &str, - timestamp: u64, - ) -> Option; -} - -pub struct MockTransformListener { - transforms: alloc::collections::BTreeMap, -} - -impl MockTransformListener { - pub fn new() -> Self { - Self { - transforms: alloc::collections::BTreeMap::new(), - } - } - - pub fn add_transform(&mut self, from_frame: &str, to_frame: &str, transform: Transform) { - let key = format!("{}_to_{}", from_frame, to_frame); - self.transforms.insert(key, transform); - } -} - -impl TransformListener for MockTransformListener { - fn get_latest_transform(&self, from_frame: &str, to_frame: &str) -> Option { - let key = format!("{}_to_{}", from_frame, to_frame); - self.transforms.get(&key).cloned() - } - - fn get_transform_at_time( - &self, - from_frame: &str, - to_frame: &str, - _timestamp: u64, - ) -> Option { - self.get_latest_transform(from_frame, to_frame) - } -} - -#[derive(Clone, Debug)] -pub struct ImuWithCovariance { - pub header: Header, - pub orientation: Quaternion, - pub angular_velocity: Vector3, - pub angular_velocity_covariance: [f64; 9], - pub linear_acceleration: Vector3, - pub linear_acceleration_covariance: [f64; 9], -} - -impl ImuWithCovariance { - pub fn from_imu_msg(imu_msg: &ImuMsg) -> Self { - Self { - header: imu_msg.header.clone(), - orientation: imu_msg.orientation.clone(), - angular_velocity: imu_msg.angular_velocity.clone(), - angular_velocity_covariance: [0.0; 9], - linear_acceleration: imu_msg.linear_acceleration.clone(), - linear_acceleration_covariance: [0.0; 9], - } - } - - pub fn to_imu_msg(&self) -> ImuMsg { - ImuMsg { - header: self.header.clone(), - orientation: self.orientation.clone(), - angular_velocity: self.angular_velocity.clone(), - linear_acceleration: self.linear_acceleration.clone(), - } - } -} - -pub struct ImuCorrectorConfig { - pub angular_velocity_offset_x: f64, - pub angular_velocity_offset_y: f64, - pub angular_velocity_offset_z: f64, - pub angular_velocity_stddev_xx: f64, - pub angular_velocity_stddev_yy: f64, - pub angular_velocity_stddev_zz: f64, - pub acceleration_stddev: f64, - pub output_frame: &'static str, -} - -impl Default for ImuCorrectorConfig { - fn default() -> Self { - Self { - angular_velocity_offset_x: 0.0, - angular_velocity_offset_y: 0.0, - angular_velocity_offset_z: 0.0, - angular_velocity_stddev_xx: 0.03, - angular_velocity_stddev_yy: 0.03, - angular_velocity_stddev_zz: 0.03, - acceleration_stddev: 10000.0, - output_frame: "base_link", - } - } -} - -pub struct ImuCorrector { - config: ImuCorrectorConfig, - transform_listener: T, -} - -impl ImuCorrector { - pub fn new() -> Self { - Self { - config: ImuCorrectorConfig::default(), - transform_listener: MockTransformListener::new(), - } - } - - pub fn with_transform_listener(transform_listener: MockTransformListener) -> Self { - Self { - config: ImuCorrectorConfig::default(), - transform_listener, - } - } -} - -impl ImuCorrector { - pub fn set_config(&mut self, config: ImuCorrectorConfig) { - self.config = config; - } - - fn to_nalgebra_vector3(&self, vec: &Vector3) -> NVector3 { - NVector3::new(vec.x, vec.y, vec.z) - } - - fn to_imu_vector3(&self, vec: &NVector3) -> Vector3 { - Vector3::new(vec.x, vec.y, vec.z) - } - - fn to_nalgebra_quaternion(&self, quat: &Quaternion) -> UnitQuaternion { - let n_quat = NQuaternion::new(quat.w, quat.x, quat.y, quat.z); - UnitQuaternion::from_quaternion(n_quat) - } - - fn transform_vector3(&self, vec: &Vector3, transform: &Transform) -> Vector3 { - let nalgebra_vec = self.to_nalgebra_vector3(vec); - let nalgebra_quat = self.to_nalgebra_quaternion(&transform.rotation); - let nalgebra_trans = self.to_nalgebra_vector3(&transform.translation); - let rotated = nalgebra_quat * nalgebra_vec; - let result = rotated + nalgebra_trans; - self.to_imu_vector3(&result) - } - - fn transform_covariance(&self, cov: &[f64; 9]) -> [f64; 9] { - let max_cov = cov[0].max(cov[4]).max(cov[8]); - let mut cov_transformed = [0.0; 9]; - cov_transformed[0] = max_cov; - cov_transformed[4] = max_cov; - cov_transformed[8] = max_cov; - - cov_transformed - } - - pub fn correct_imu_with_covariance( - &self, - imu_msg: &ImuMsg, - transform: Option<&Transform>, - ) -> ImuWithCovariance { - let mut corrected_imu = ImuWithCovariance::from_imu_msg(imu_msg); - corrected_imu.angular_velocity.x -= self.config.angular_velocity_offset_x; - corrected_imu.angular_velocity.y -= self.config.angular_velocity_offset_y; - corrected_imu.angular_velocity.z -= self.config.angular_velocity_offset_z; - corrected_imu.angular_velocity_covariance[0] = - self.config.angular_velocity_stddev_xx * self.config.angular_velocity_stddev_xx; - corrected_imu.angular_velocity_covariance[4] = - self.config.angular_velocity_stddev_yy * self.config.angular_velocity_stddev_yy; - corrected_imu.angular_velocity_covariance[8] = - self.config.angular_velocity_stddev_zz * self.config.angular_velocity_stddev_zz; - let accel_var = self.config.acceleration_stddev * self.config.acceleration_stddev; - corrected_imu.linear_acceleration_covariance[0] = accel_var; - corrected_imu.linear_acceleration_covariance[4] = accel_var; - corrected_imu.linear_acceleration_covariance[8] = accel_var; - - if let Some(tf) = transform { - corrected_imu.linear_acceleration = - self.transform_vector3(&corrected_imu.linear_acceleration, tf); - corrected_imu.linear_acceleration_covariance = - self.transform_covariance(&corrected_imu.linear_acceleration_covariance); - corrected_imu.angular_velocity = - self.transform_vector3(&corrected_imu.angular_velocity, tf); - corrected_imu.angular_velocity_covariance = - self.transform_covariance(&corrected_imu.angular_velocity_covariance); - corrected_imu.header.frame_id = self.config.output_frame; - } - - corrected_imu - } - - pub fn correct_imu(&self, imu_msg: &ImuMsg, transform: Option<&Transform>) -> ImuMsg { - let corrected_with_cov = self.correct_imu_with_covariance(imu_msg, transform); - corrected_with_cov.to_imu_msg() - } - - pub fn correct_imu_with_dynamic_tf(&self, imu_msg: &ImuMsg) -> Option { - let transform = self - .transform_listener - .get_latest_transform(&imu_msg.header.frame_id, self.config.output_frame)?; - - let corrected_with_cov = self.correct_imu_with_covariance(imu_msg, Some(&transform)); - Some(corrected_with_cov.to_imu_msg()) - } - - pub fn correct_imu_with_dynamic_tf_covariance( - &self, - imu_msg: &ImuMsg, - ) -> Option { - let transform = self - .transform_listener - .get_latest_transform(&imu_msg.header.frame_id, self.config.output_frame)?; - - Some(self.correct_imu_with_covariance(imu_msg, Some(&transform))) - } - - pub fn correct_imu_simple(&self, imu_msg: &ImuMsg) -> ImuMsg { - let mut corrected_msg = imu_msg.clone(); - - corrected_msg.angular_velocity.x -= self.config.angular_velocity_offset_x; - corrected_msg.angular_velocity.y -= self.config.angular_velocity_offset_y; - corrected_msg.angular_velocity.z -= self.config.angular_velocity_offset_z; - - corrected_msg.header.frame_id = self.config.output_frame; - - corrected_msg - } - - pub fn get_covariance_config(&self) -> (f64, f64, f64, f64) { - ( - self.config.angular_velocity_stddev_xx, - self.config.angular_velocity_stddev_yy, - self.config.angular_velocity_stddev_zz, - self.config.acceleration_stddev, - ) - } -} - -pub fn transform_covariance(cov: &[f64; 9]) -> [f64; 9] { - let max_cov = cov[0].max(cov[4]).max(cov[8]); - let mut cov_transformed = [0.0; 9]; - cov_transformed[0] = max_cov; - cov_transformed[4] = max_cov; - cov_transformed[8] = max_cov; - cov_transformed -} - -#[cfg(test)] -mod tests { - use super::*; - - #[test] - fn test_imu_corrector() { - let corrector = ImuCorrector::new(); - let imu_msg = ImuMsg { - header: Header { - frame_id: "imu_link", - timestamp: 0, - }, - orientation: Quaternion { - x: 0.0, - y: 0.0, - z: 0.0, - w: 1.0, - }, - angular_velocity: Vector3::new(0.1, 0.2, 0.3), - linear_acceleration: Vector3::new(9.8, 0.0, 0.0), - }; - - let corrected_msg = corrector.correct_imu_simple(&imu_msg); - assert_eq!(corrected_msg.header.frame_id, "base_link"); - assert_eq!(corrected_msg.angular_velocity.x, 0.1); - assert_eq!(corrected_msg.angular_velocity.y, 0.2); - assert_eq!(corrected_msg.angular_velocity.z, 0.3); - } - - #[test] - fn test_imu_corrector_with_offset() { - let mut config = ImuCorrectorConfig::default(); - config.angular_velocity_offset_x = 0.05; - config.angular_velocity_offset_y = 0.1; - config.angular_velocity_offset_z = 0.15; - - let mut corrector = ImuCorrector::new(); - corrector.set_config(config); - - let imu_msg = ImuMsg { - header: Header { - frame_id: "imu_link", - timestamp: 0, - }, - orientation: Quaternion { - x: 0.0, - y: 0.0, - z: 0.0, - w: 1.0, - }, - angular_velocity: Vector3::new(0.1, 0.2, 0.3), - linear_acceleration: Vector3::new(9.8, 0.0, 0.0), - }; - - let corrected_msg = corrector.correct_imu_simple(&imu_msg); - - assert_eq!(corrected_msg.angular_velocity.x, 0.1 - 0.05); - assert_eq!(corrected_msg.angular_velocity.y, 0.2 - 0.1); - assert_eq!(corrected_msg.angular_velocity.z, 0.3 - 0.15); - } - - #[test] - fn test_imu_corrector_with_covariance() { - let corrector = ImuCorrector::new(); - let imu_msg = ImuMsg { - header: Header { - frame_id: "imu_link", - timestamp: 0, - }, - orientation: Quaternion { - x: 0.0, - y: 0.0, - z: 0.0, - w: 1.0, - }, - angular_velocity: Vector3::new(0.1, 0.2, 0.3), - linear_acceleration: Vector3::new(9.8, 0.0, 0.0), - }; - - let corrected_with_cov = corrector.correct_imu_with_covariance(&imu_msg, None); - let expected_angular_var = 0.03 * 0.03; - assert_eq!( - corrected_with_cov.angular_velocity_covariance[0], - expected_angular_var - ); - assert_eq!( - corrected_with_cov.angular_velocity_covariance[4], - expected_angular_var - ); - assert_eq!( - corrected_with_cov.angular_velocity_covariance[8], - expected_angular_var - ); - let expected_accel_var = 10000.0 * 10000.0; - assert_eq!( - corrected_with_cov.linear_acceleration_covariance[0], - expected_accel_var - ); - assert_eq!( - corrected_with_cov.linear_acceleration_covariance[4], - expected_accel_var - ); - assert_eq!( - corrected_with_cov.linear_acceleration_covariance[8], - expected_accel_var - ); - } - - #[test] - fn test_transform_covariance() { - let corrector = ImuCorrector::new(); - let input_cov = [1.0, 0.5, 0.3, 0.5, 2.0, 0.4, 0.3, 0.4, 3.0]; - let transformed_cov = corrector.transform_covariance(&input_cov); - - assert_eq!(transformed_cov[0], 3.0); - assert_eq!(transformed_cov[4], 3.0); - assert_eq!(transformed_cov[8], 3.0); - assert_eq!(transformed_cov[1], 0.0); - assert_eq!(transformed_cov[2], 0.0); - assert_eq!(transformed_cov[3], 0.0); - assert_eq!(transformed_cov[5], 0.0); - assert_eq!(transformed_cov[6], 0.0); - assert_eq!(transformed_cov[7], 0.0); - } - - #[test] - fn test_public_transform_covariance() { - let input_cov = [1.0, 0.5, 0.3, 0.5, 2.0, 0.4, 0.3, 0.4, 3.0]; - let transformed_cov = transform_covariance(&input_cov); - assert_eq!(transformed_cov[0], 3.0); - assert_eq!(transformed_cov[4], 3.0); - assert_eq!(transformed_cov[8], 3.0); - assert_eq!(transformed_cov[1], 0.0); - assert_eq!(transformed_cov[2], 0.0); - assert_eq!(transformed_cov[3], 0.0); - assert_eq!(transformed_cov[5], 0.0); - assert_eq!(transformed_cov[6], 0.0); - assert_eq!(transformed_cov[7], 0.0); - } - - #[test] - fn test_imu_corrector_with_transform() { - let corrector = ImuCorrector::new(); - let imu_msg = ImuMsg { - header: Header { - frame_id: "imu_link", - timestamp: 0, - }, - orientation: Quaternion { - x: 0.0, - y: 0.0, - z: 0.0, - w: 1.0, - }, - angular_velocity: Vector3::new(0.1, 0.2, 0.3), - linear_acceleration: Vector3::new(9.8, 0.0, 0.0), - }; - - let transform = Transform { - translation: Vector3::new(0.0, 0.0, 0.0), - rotation: Quaternion { - x: 0.0, - y: 0.0, - z: 0.0, - w: 1.0, - }, - }; - - let corrected_with_cov = corrector.correct_imu_with_covariance(&imu_msg, Some(&transform)); - assert_eq!(corrected_with_cov.header.frame_id, "base_link"); - let expected_angular_var = 0.03 * 0.03; - assert_eq!( - corrected_with_cov.angular_velocity_covariance[0], - expected_angular_var - ); - assert_eq!( - corrected_with_cov.angular_velocity_covariance[4], - expected_angular_var - ); - assert_eq!( - corrected_with_cov.angular_velocity_covariance[8], - expected_angular_var - ); - } - - #[test] - fn test_imu_corrector_with_dynamic_tf() { - let mut transform_listener = MockTransformListener::new(); - let transform = Transform { - translation: Vector3::new(1.0, 0.0, 0.0), - rotation: Quaternion { - x: 0.0, - y: 0.0, - z: 0.0, - w: 1.0, - }, - }; - transform_listener.add_transform("imu_link", "base_link", transform); - - let corrector = ImuCorrector::with_transform_listener(transform_listener); - let imu_msg = ImuMsg { - header: Header { - frame_id: "imu_link", - timestamp: 0, - }, - orientation: Quaternion { - x: 0.0, - y: 0.0, - z: 0.0, - w: 1.0, - }, - angular_velocity: Vector3::new(0.1, 0.2, 0.3), - linear_acceleration: Vector3::new(9.8, 0.0, 0.0), - }; - - let corrected_msg = corrector.correct_imu_with_dynamic_tf(&imu_msg); - assert!(corrected_msg.is_some()); - - let corrected_msg = corrected_msg.unwrap(); - assert_eq!(corrected_msg.header.frame_id, "base_link"); - assert_eq!(corrected_msg.linear_acceleration.x, 9.8); - } - - #[test] - fn test_imu_corrector_with_dynamic_tf_no_transform() { - let transform_listener = MockTransformListener::new(); - let corrector = ImuCorrector::with_transform_listener(transform_listener); - let imu_msg = ImuMsg { - header: Header { - frame_id: "imu_link", - timestamp: 0, - }, - orientation: Quaternion { - x: 0.0, - y: 0.0, - z: 0.0, - w: 1.0, - }, - angular_velocity: Vector3::new(0.1, 0.2, 0.3), - linear_acceleration: Vector3::new(9.8, 0.0, 0.0), - }; - - let corrected_msg = corrector.correct_imu_with_dynamic_tf(&imu_msg); - assert!(corrected_msg.is_none()); - } -} diff --git a/applications/tests/test_autoware/imu_driver/Cargo.toml b/applications/tests/test_autoware/imu_driver/Cargo.toml deleted file mode 100644 index f08727aa3..000000000 --- a/applications/tests/test_autoware/imu_driver/Cargo.toml +++ /dev/null @@ -1,9 +0,0 @@ -[package] -name = "imu_driver" -version = "0.1.0" -edition = "2021" - -[dependencies] -log = "0.4" -awkernel_async_lib = { path = "../../../../awkernel_async_lib", default-features = false } -awkernel_lib = { path = "../../../../awkernel_lib", default-features = false } \ No newline at end of file diff --git a/applications/tests/test_autoware/imu_driver/src/lib.rs b/applications/tests/test_autoware/imu_driver/src/lib.rs deleted file mode 100644 index 3b8a947df..000000000 --- a/applications/tests/test_autoware/imu_driver/src/lib.rs +++ /dev/null @@ -1,260 +0,0 @@ -#![no_std] -extern crate alloc; - -use alloc::{format, string::String, vec, vec::Vec}; -use core::f64::consts::PI; - -#[derive(Clone, Debug)] -pub struct ImuMsg { - pub header: Header, - pub orientation: Quaternion, - pub angular_velocity: Vector3, - pub linear_acceleration: Vector3, -} - -#[derive(Clone, Debug)] -pub struct ImuCsvRow { - pub timestamp: u64, - pub orientation: Quaternion, - pub angular_velocity: Vector3, - pub linear_acceleration: Vector3, -} - -#[derive(Clone, Debug)] -pub struct Header { - pub frame_id: &'static str, - pub timestamp: u64, -} - -#[derive(Debug, Clone)] -pub struct Quaternion { - pub x: f64, - pub y: f64, - pub z: f64, - pub w: f64, -} - -#[derive(Clone, Debug)] -pub struct Vector3 { - pub x: f64, - pub y: f64, - pub z: f64, -} - -impl Vector3 { - pub fn new(x: f64, y: f64, z: f64) -> Self { - Self { x, y, z } - } -} - -impl Default for ImuMsg { - fn default() -> Self { - Self { - header: Header { - frame_id: "imu", - timestamp: 0, - }, - orientation: Quaternion { - x: 1.0, - y: 0.0, - z: 0.0, - w: 0.0, - }, - angular_velocity: Vector3::new(0.0, 0.0, 0.0), - linear_acceleration: Vector3::new(0.0, 0.0, 0.0), - } - } -} - -pub fn build_imu_msg_from_csv_row( - row: &ImuCsvRow, - frame_id: &'static str, - timestamp: u64, -) -> ImuMsg { - ImuMsg { - header: Header { - frame_id, - timestamp, - }, - orientation: row.orientation.clone(), - angular_velocity: row.angular_velocity.clone(), - linear_acceleration: row.linear_acceleration.clone(), - } -} - -pub struct TamagawaImuParser { - frame_id: &'static str, - dummy_counter: u16, -} - -impl TamagawaImuParser { - pub fn new(frame_id: &'static str) -> Self { - Self { - frame_id, - dummy_counter: 0, - } - } - - pub fn parse_binary_data(&self, data: &[u8], timestamp: u64) -> Option { - if data.len() != 58 - || data[5] != b'B' - || data[6] != b'I' - || data[7] != b'N' - || data[8] != b',' - { - return None; - } - - let mut imu_msg = ImuMsg::default(); - imu_msg.header.frame_id = self.frame_id; - imu_msg.header.timestamp = timestamp; - - let _counter = ((data[11] as u16) << 8) | (data[12] as u16); - let raw_data = self.parse_signed_16bit(&data[15..17]); - imu_msg.angular_velocity.x = self.convert_angular_velocity(raw_data); - let raw_data = self.parse_signed_16bit(&data[17..19]); - imu_msg.angular_velocity.y = self.convert_angular_velocity(raw_data); - let raw_data = self.parse_signed_16bit(&data[19..21]); - imu_msg.angular_velocity.z = self.convert_angular_velocity(raw_data); - let raw_data = self.parse_signed_16bit(&data[21..23]); - imu_msg.linear_acceleration.x = self.convert_acceleration(raw_data); - let raw_data = self.parse_signed_16bit(&data[23..25]); - imu_msg.linear_acceleration.y = self.convert_acceleration(raw_data); - let raw_data = self.parse_signed_16bit(&data[25..27]); - imu_msg.linear_acceleration.z = self.convert_acceleration(raw_data); - - Some(imu_msg) - } - - pub fn generate_dummy_binary_data( - &mut self, - _timestamp: u64, - angular_velocity: Vector3, - linear_acceleration: Vector3, - ) -> Vec { - let mut data = vec![0u8; 58]; - - data[0..5].copy_from_slice(b"$TSC,"); - data[5] = b'B'; - data[6] = b'I'; - data[7] = b'N'; - data[8] = b','; - data[11] = (self.dummy_counter >> 8) as u8; - data[12] = (self.dummy_counter & 0xFF) as u8; - self.dummy_counter = self.dummy_counter.wrapping_add(1); - - let angular_vel_x_lsb = self.convert_angular_velocity_to_lsb(angular_velocity.x); - let angular_vel_y_lsb = self.convert_angular_velocity_to_lsb(angular_velocity.y); - let angular_vel_z_lsb = self.convert_angular_velocity_to_lsb(angular_velocity.z); - let accel_x_lsb = self.convert_acceleration_to_lsb(linear_acceleration.x); - let accel_y_lsb = self.convert_acceleration_to_lsb(linear_acceleration.y); - let accel_z_lsb = self.convert_acceleration_to_lsb(linear_acceleration.z); - - data[15] = (angular_vel_x_lsb >> 8) as u8; - data[16] = (angular_vel_x_lsb & 0xFF) as u8; - data[17] = (angular_vel_y_lsb >> 8) as u8; - data[18] = (angular_vel_y_lsb & 0xFF) as u8; - data[19] = (angular_vel_z_lsb >> 8) as u8; - data[20] = (angular_vel_z_lsb & 0xFF) as u8; - data[21] = (accel_x_lsb >> 8) as u8; - data[22] = (accel_x_lsb & 0xFF) as u8; - data[23] = (accel_y_lsb >> 8) as u8; - data[24] = (accel_y_lsb & 0xFF) as u8; - data[25] = (accel_z_lsb >> 8) as u8; - data[26] = (accel_z_lsb & 0xFF) as u8; - - data - } - - pub fn generate_static_dummy_data(&mut self, timestamp: u64) -> Vec { - let angular_velocity = Vector3::new(0.1, 0.2, 0.01); - let linear_acceleration = Vector3::new(0.0, 0.0, 9.80665); - - self.generate_dummy_binary_data(timestamp, angular_velocity, linear_acceleration) - } - - fn convert_angular_velocity_to_lsb(&self, rad_per_sec: f64) -> i16 { - let deg_per_sec = rad_per_sec * 180.0 / PI; - let lsb = deg_per_sec / (200.0 / (1 << 15) as f64); - lsb as i16 - } - - fn convert_acceleration_to_lsb(&self, m_per_sec_squared: f64) -> i16 { - let lsb = m_per_sec_squared / (100.0 / (1 << 15) as f64); - lsb as i16 - } - - fn parse_signed_16bit(&self, data: &[u8]) -> i16 { - if data.len() != 2 { - return 0; - } - let high_byte = (data[0] as i32) << 8; - let low_byte = data[1] as i32; - let result = (high_byte & 0xFFFFFF00u32 as i32) | (low_byte & 0x000000FF); - result as i16 - } - - fn convert_angular_velocity(&self, raw_data: i16) -> f64 { - let lsb_to_deg_per_sec = 200.0 / (1 << 15) as f64; - let deg_to_rad = PI / 180.0; - (raw_data as f64) * lsb_to_deg_per_sec * deg_to_rad - } - - fn convert_acceleration(&self, raw_data: i16) -> f64 { - let lsb_to_m_per_sec_squared = 100.0 / (1 << 15) as f64; - (raw_data as f64) * lsb_to_m_per_sec_squared - } - - pub fn generate_version_request() -> &'static [u8] { - b"$TSC,VER*29\r\n" - } - - pub fn generate_offset_cancel_request(offset_value: i32) -> String { - format!("$TSC,OFC,{}\r\n", offset_value) - } - - pub fn generate_heading_reset_request() -> &'static [u8] { - b"$TSC,HRST*29\r\n" - } - - pub fn generate_binary_request(rate_hz: u32) -> String { - format!("$TSC,BIN,{}\r\n", rate_hz) - } -} - -#[cfg(test)] -mod tests { - use super::*; - - #[test] - fn example_usage() { - let mut parser = TamagawaImuParser::new("imu_link"); - let version_cmd = TamagawaImuParser::generate_version_request(); - let binary_cmd = TamagawaImuParser::generate_binary_request(30); - let offset_cmd = TamagawaImuParser::generate_offset_cancel_request(123); - let heading_cmd = TamagawaImuParser::generate_heading_reset_request(); - let static_dummy_data = parser.generate_static_dummy_data(123456789); - if let Some(imu_msg) = parser.parse_binary_data(&static_dummy_data, 123456789) { - let _angular_vel = imu_msg.angular_velocity; - let _acceleration = imu_msg.linear_acceleration; - } - - let sinusoidal_dummy_data = parser.generate_sinusoidal_dummy_data(123456789, 0.0); - if let Some(imu_msg) = parser.parse_binary_data(&sinusoidal_dummy_data, 123456789) { - let _angular_vel = imu_msg.angular_velocity; - let _acceleration = imu_msg.linear_acceleration; - } - - let custom_angular_velocity = Vector3::new(0.5, -0.3, 1.2); - let custom_acceleration = Vector3::new(8.5, 2.1, 10.2); - let custom_dummy_data = parser.generate_dummy_binary_data( - 123456789, - custom_angular_velocity, - custom_acceleration, - ); - if let Some(imu_msg) = parser.parse_binary_data(&custom_dummy_data, 123456789) { - let _angular_vel = imu_msg.angular_velocity; - let _acceleration = imu_msg.linear_acceleration; - } - } -} diff --git a/applications/tests/test_autoware/imu_raw.csv b/applications/tests/test_autoware/imu_raw.csv deleted file mode 100644 index 4886b7850..000000000 --- a/applications/tests/test_autoware/imu_raw.csv +++ /dev/null @@ -1,5709 +0,0 @@ -timestamp_sec,timestamp_nanosec,orientation_x,orientation_y,orientation_z,orientation_w,angular_velocity_x,angular_velocity_y,angular_velocity_z,linear_acceleration_x,linear_acceleration_y,linear_acceleration_z -1769682011,410121472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682011,462363136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682011,469166592,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682011,509448960,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682011,543781120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682011,570960384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682011,609601792,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682011,659680256,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682011,666435840,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682011,701181184,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682011,759175424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682011,770347264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682011,809539328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682011,865306112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682011,880912896,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682011,910638592,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682011,950943488,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682011,978671360,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,10963968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,52329472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,76876544,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,114380288,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,158851328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,170333952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,209740288,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,264206336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,273925632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,309050368,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,356011264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,376484608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,400628736,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,452687104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,476804608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,511975936,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,555344128,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,573499648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,609228288,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,647077120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,669924608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,709627904,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,747266304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,776354560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,809455616,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,853366016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,877307136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,909498624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,947997696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682012,979754496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,9405696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,43408640,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,67382272,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,109652480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,144094208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,175933440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,213615104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,258479872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,268090368,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,308947200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,363198720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,380390400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,409442304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,446046208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,477171456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,511062016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,548630784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,576634880,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,614119424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,659646208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,669505792,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,709091072,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,754778880,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,777250816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,809955840,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,842801920,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,878489088,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,910355968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,961571328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682013,968428032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,500224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,61579520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,72642816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,110277888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,163835648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,175374336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,209796608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,244276224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,276851200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,310392320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,353491456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,376546560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,409061120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,459643392,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,469405184,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,509146624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,544073216,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,578467072,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,610523392,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,645220864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,676251648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,709531392,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,743406848,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,776807168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,812845824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,846098432,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,878514688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,911022848,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,958437376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682014,969724672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,10676480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,43781632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,78323712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,110242816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,145303040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,179990784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,209876224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,246270208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,278840064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,314503168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,349533440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,375959040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,409660928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,454444800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,476497920,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,509792512,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,543955456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,580643584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,612306944,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,645478656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,676257536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,709653760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,755419648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,776323072,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,809076736,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,862409472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,869460224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,911052544,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,945050624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682015,980811008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,9593344,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,45559552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,76001536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,110477568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,144845568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,177478400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,209633024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,266411008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,274794496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,309711872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,343024128,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,377344512,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,411144192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,456842496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,476329216,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,510285312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,552322048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,576834560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,609375232,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,644767232,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,665960192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,713820416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,747127040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,828725760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,830855168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,864070656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,871448064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,911274752,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,944341504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682016,976420864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,9947136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,49340160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,77211904,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,109819136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,158978816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,170197760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,209368064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,244061696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,276502016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,310521856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,357883136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,384333824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,410472960,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,446477312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,477434112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,511023872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,549916416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,577069824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,609644800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,662749696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,669412352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,709689088,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,744481024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,776696320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,809918464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,846062848,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,877307904,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,915363328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,947344640,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682017,976938496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682018,9361152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682018,57942016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682018,67345152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682018,110760704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682018,143277824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682018,181226752,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682018,209636864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682018,245412096,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682018,277799680,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682018,314036224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682018,354016512,0.0,0.0,0.0,1.0,0.014358777552843094,-0.03264179825782776,0.00043512278352864087,1.6609306335449219,0.8149923086166382,-4.72646951675415 -1769682018,378463232,0.0,0.0,0.0,1.0,0.01761149987578392,-0.05850871279835701,0.0009570895927026868,0.9481403827667236,0.2100292444229126,-2.714618444442749 -1769682018,410350848,0.0,0.0,0.0,1.0,0.01570582017302513,-0.06417010724544525,0.0012279312359169126,-0.5181403756141663,-0.32497110962867737,-0.9743397831916809 -1769682018,464692480,0.0,0.0,0.0,1.0,0.011602478101849556,-0.053104933351278305,0.0012069185031577945,-1.0990111827850342,0.04187984764575958,0.6243825554847717 -1769682018,473776896,0.0,0.0,0.0,1.0,0.009407504461705685,-0.038554079830646515,0.001043057651259005,-1.2761266231536865,-0.24411405622959137,1.3442267179489136 -1769682018,510287872,0.0,0.0,0.0,1.0,0.0070592123083770275,-0.02376710996031761,0.0007886536186560988,-0.8540163040161133,-0.3414801359176636,1.6605005264282227 -1769682018,549068800,0.0,0.0,0.0,1.0,0.005631800275295973,-0.00807406846433878,0.0004554156621452421,-0.8337791562080383,0.208700031042099,1.6470088958740234 -1769682018,577014528,0.0,0.0,0.0,1.0,0.0043827383778989315,-0.0005656213033944368,0.00021280259534250945,-0.4945983588695526,0.2380276322364807,1.4357680082321167 -1769682018,610034432,0.0,0.0,0.0,1.0,0.0033162739127874374,0.0037964421790093184,1.6558158677071333e-05,-0.49590009450912476,0.2362305372953415,1.1162302494049072 -1769682018,646877440,0.0,0.0,0.0,1.0,0.0025875617284327745,0.005088666453957558,-0.00019407004583626986,-0.25737112760543823,-0.1560479700565338,0.668285071849823 -1769682018,676283648,0.0,0.0,0.0,1.0,0.002293581608682871,0.004002165514975786,-0.00027116795536130667,-0.17841367423534393,-0.2878539264202118,0.35529476404190063 -1769682018,715464960,0.0,0.0,0.0,1.0,0.0014286770019680262,0.002398464363068342,-0.000362870137905702,-0.24001342058181763,0.39022552967071533,0.09845121204853058 -1769682018,751439616,0.0,0.0,0.0,1.0,0.0009561797487549484,0.0005182125605642796,-0.00037578027695417404,-0.4204089641571045,0.09861285239458084,-0.13754582405090332 -1769682018,776400384,0.0,0.0,0.0,1.0,-0.00019652271294035017,-0.00030091029475443065,-0.00038026596303097904,-0.2604846954345703,-0.16172528266906738,-0.2317706197500229 -1769682018,809322240,0.0,0.0,0.0,1.0,-0.0002173051907448098,-0.0007950104773044586,-0.00035245815524831414,-0.5203346014022827,-0.32220444083213806,-0.2680325210094452 -1769682018,859503872,0.0,0.0,0.0,1.0,-0.0010283852461725473,-0.0011585456086322665,-0.0003098126908298582,-0.680616021156311,-0.06254737079143524,-0.2786766290664673 -1769682018,865981696,0.0,0.0,0.0,1.0,-0.0011799205094575882,-0.0011962095741182566,-0.00028650229796767235,0.2589378356933594,0.1587587296962738,-0.23434194922447205 -1769682018,912800512,0.0,0.0,0.0,1.0,-0.0011685179779306054,-0.0005853036418557167,-0.00021313849720172584,-0.420572429895401,0.0983397364616394,-0.17920704185962677 -1769682018,955111424,0.0,0.0,0.0,1.0,-0.0016090166755020618,0.00030316782067529857,-0.0001169246097560972,-0.5999751091003418,-0.19140098989009857,-0.12074214965105057 -1769682018,983323136,0.0,0.0,0.0,1.0,-0.001579517382197082,0.0021224617958068848,-3.8352965930243954e-05,-0.1606135368347168,0.25903943181037903,-0.10955487191677094 -1769682019,9780480,0.0,0.0,0.0,1.0,-0.0011749914847314358,0.0036997233983129263,4.364276901469566e-05,-0.6797910332679749,-0.06098197400569916,-0.031976960599422455 -1769682019,63262208,0.0,0.0,0.0,1.0,-0.0016347073251381516,0.004802745301276445,0.00011798564810305834,-0.5191839933395386,-0.3199845254421234,0.08460760116577148 -1769682019,73359360,0.0,0.0,0.0,1.0,-0.0013325101463124156,0.001962781185284257,0.00015812087804079056,-0.4998626708984375,0.22979100048542023,0.07519267499446869 -1769682019,100884224,0.0,0.0,0.0,1.0,-0.0020272464025765657,0.0007424092618748546,0.00018082863243762404,-0.07987979054450989,0.13035506010055542,0.08170486241579056 -1769682019,149033728,0.0,0.0,0.0,1.0,-0.0013139211805537343,-0.0012264352990314364,0.0002864305570255965,-0.2595556974411011,-0.15990819036960602,0.05656507983803749 -1769682019,178920704,0.0,0.0,0.0,1.0,-0.0014810527209192514,-0.0016676244558766484,0.0003281341341789812,-0.08002602308988571,0.13004358112812042,0.030467208474874496 -1769682019,209931008,0.0,0.0,0.0,1.0,-0.0016177979996427894,-0.0014092583442106843,0.0003889485960826278,-0.5994576215744019,-0.19039477407932281,0.03753240033984184 -1769682019,248896000,0.0,0.0,0.0,1.0,-0.0013614653144031763,-0.0010151714086532593,0.0004848823300562799,-0.5995762348175049,-0.1906040906906128,0.0005959551781415939 -1769682019,279114752,0.0,0.0,0.0,1.0,-0.0014579102862626314,-0.0007408582023344934,0.0005284020444378257,0.25972381234169006,0.16021472215652466,-0.002934660529717803 -1769682019,309730048,0.0,0.0,0.0,1.0,-0.0010531352600082755,-0.00029737415025010705,0.0005952980718575418,-0.5996666550636292,-0.19074003398418427,-0.026813479140400887 -1769682019,342887936,0.0,0.0,0.0,1.0,-0.0012509834486991167,0.00027850648621097207,0.000684003927744925,-0.16030353307724,0.25957852602005005,-0.02838844247162342 -1769682019,377901568,0.0,0.0,0.0,1.0,-0.0008489490137435496,0.0005182474851608276,0.0007465402013622224,-0.8593383431434631,-0.350779265165329,-0.00127364881336689 -1769682019,411501568,0.0,0.0,0.0,1.0,-0.001166374422609806,0.0008277237066067755,0.0008067653980106115,-0.41995808482170105,0.09952292591333389,-0.002821642439812422 -1769682019,447005952,0.0,0.0,0.0,1.0,-0.001723594730719924,0.001105783274397254,0.0008707031956873834,-0.33987852931022644,-0.030375953763723373,-0.009511372074484825 -1769682019,481549568,0.0,0.0,0.0,1.0,-0.0009703924297355115,0.0012781331315636635,0.000955854426138103,-0.25972533226013184,-0.16013191640377045,0.011211629956960678 -1769682019,509959424,0.0,0.0,0.0,1.0,-0.001493085059337318,0.0014055684441700578,0.001013646018691361,-0.1602206528186798,0.25968489050865173,-0.014050970785319805 -1769682019,555195392,0.0,0.0,0.0,1.0,-0.0017278699669986963,0.0013918228214606643,0.0010778849245980382,-0.16021603345870972,0.2596796751022339,-0.01642657443881035 -1769682019,576477184,0.0,0.0,0.0,1.0,-0.0019736974500119686,0.00144700868986547,0.001145191490650177,-0.599660336971283,-0.19050364196300507,-0.011538006365299225 -1769682019,613140224,0.0,0.0,0.0,1.0,-0.0017546213930472732,0.0013152147876098752,0.0012115506688132882,-0.500006377696991,0.22950899600982666,-0.0009735384956002235 -1769682019,649756160,0.0,0.0,0.0,1.0,-0.0016882875934243202,0.0013868293026462197,0.0012890693033114076,-0.5996822714805603,-0.19046321511268616,-0.014001766219735146 -1769682019,676992000,0.0,0.0,0.0,1.0,-0.0016811522655189037,0.001570007181726396,0.001355680637061596,-0.5996759533882141,-0.1904139518737793,-0.009269829839468002 -1769682019,709649920,0.0,0.0,0.0,1.0,-0.0018769016023725271,0.001583663048222661,0.0014017962384968996,-0.08007518947124481,0.1298673450946808,-0.006407645530998707 -1769682019,761499136,0.0,0.0,0.0,1.0,-0.0017820842331275344,0.0014813162852078676,0.0014707462396472692,-0.5996589064598083,-0.19028717279434204,0.0037515098229050636 -1769682019,770610688,0.0,0.0,0.0,1.0,-0.002011739183217287,0.0012669740244746208,0.0015132620465010405,-0.6797248125076294,-0.06038839370012283,-0.00148025993257761 -1769682019,810937856,0.0,0.0,0.0,1.0,-0.0021897268015891314,0.0013511055149137974,0.001579607604071498,0.17976222932338715,0.28994879126548767,-0.009048134088516235 -1769682019,844546560,0.0,0.0,0.0,1.0,-0.0018184375949203968,0.0014753910945728421,0.001645161071792245,-0.6600278615951538,0.4894373416900635,-0.017398148775100708 -1769682019,879716864,0.0,0.0,0.0,1.0,-0.0018518993165344,0.0015361205441877246,0.0016844415804371238,-0.5799512267112732,0.3596039414405823,-0.006245370954275131 -1769682019,912297216,0.0,0.0,0.0,1.0,-0.0018627013778313994,0.0015311045572161674,0.0017548114992678165,-0.4998740255832672,0.22979000210762024,0.010857288725674152 -1769682019,949766912,0.0,0.0,0.0,1.0,-0.002138451673090458,0.001794222742319107,0.0018183771753683686,-0.5197455883026123,-0.3200805187225342,-0.009205376729369164 -1769682019,977427456,0.0,0.0,0.0,1.0,-0.0022545193787664175,0.0017781752394512296,0.001856209826655686,-0.16003812849521637,0.2597963213920593,-0.016316290944814682 -1769682020,12406272,0.0,0.0,0.0,1.0,-0.002169262384995818,0.001936362124979496,0.0018991457764059305,-0.4998660385608673,0.22981469333171844,-0.003484392538666725 -1769682020,59058432,0.0,0.0,0.0,1.0,-0.0022767132613807917,0.0019258329411968589,0.001974612008780241,-0.08003057539463043,0.1298495978116989,-0.02185678295791149 -1769682020,72169216,0.0,0.0,0.0,1.0,-0.002365145832300186,0.002034558914601803,0.001989185344427824,-6.13878364674747e-05,-0.00012508318468462676,-0.028609907254576683 -1769682020,112495360,0.0,0.0,0.0,1.0,-0.0022194574121385813,0.0020858701318502426,0.002045518485829234,-0.9396838545799255,-0.21993516385555267,-0.007850328460335732 -1769682020,161177856,0.0,0.0,0.0,1.0,-0.002333069685846567,0.0024040595162659883,0.002103828825056553,-0.33989793062210083,-0.029990151524543762,-0.00874185748398304 -1769682020,177283584,0.0,0.0,0.0,1.0,-0.0024103729519993067,0.0022562718950212,0.002129646949470043,-0.6797599196434021,-0.05985264107584953,0.0027295295149087906 -1769682020,201306112,0.0,0.0,0.0,1.0,-0.0025123769883066416,0.0023225913755595684,0.0021410793997347355,-0.25990375876426697,-0.15980631113052368,0.020203109830617905 -1769682020,267985408,0.0,0.0,0.0,1.0,-0.0027702271472662687,0.002176680602133274,0.0021972130052745342,-0.8598073720932007,-0.3496067523956299,-0.0019029416143894196 -1769682020,275361024,0.0,0.0,0.0,1.0,-0.002624168759211898,0.0022626840509474277,0.00223132804967463,0.33990374207496643,0.029891368001699448,0.008854015730321407 -1769682020,300538624,0.0,0.0,0.0,1.0,-0.0025042265187948942,0.0023084685672074556,0.0022458622697740793,-0.2397301197052002,0.38999268412590027,0.007257262244820595 -1769682020,364577024,0.0,0.0,0.0,1.0,-0.0027509843930602074,0.0023654564283788204,0.00230006268247962,-0.7799532413482666,-0.4793204367160797,0.023193076252937317 -1769682020,374328320,0.0,0.0,0.0,1.0,-0.003068530233576894,0.002365312073379755,0.0023150083143264055,-0.41980087757110596,0.10018596798181534,-0.010483062826097012 -1769682020,409896448,0.0,0.0,0.0,1.0,-0.002722540171816945,0.002335426863282919,0.002332766307517886,-0.7800359725952148,-0.47925835847854614,0.009889258071780205 -1769682020,459754496,0.0,0.0,0.0,1.0,-0.00271616387180984,0.002456498332321644,0.002361229620873928,-0.41980838775634766,0.10018832236528397,-0.030800800770521164 -1769682020,468659200,0.0,0.0,0.0,1.0,-0.002707344712689519,0.0023533832281827927,0.0023761133197695017,-0.23956622183322906,0.39012598991394043,0.019261743873357773 -1769682020,510630144,0.0,0.0,0.0,1.0,-0.0024871539790183306,0.0023674294352531433,0.0024078914429992437,-0.6798281669616699,-0.05940405651926994,-0.01692809909582138 -1769682020,545726976,0.0,0.0,0.0,1.0,-0.0028936341404914856,0.0025722591672092676,0.0024070492945611477,-0.3399069309234619,-0.02964075095951557,0.00043869856745004654 -1769682020,573634048,0.0,0.0,0.0,1.0,-0.0029759646859019995,0.002599380211904645,0.002416030503809452,-9.247669368050992e-06,-2.8858350560767576e-05,-0.009536702185869217 -1769682020,610342144,0.0,0.0,0.0,1.0,-0.003187020542100072,0.002594871912151575,0.0024333344772458076,-0.26009008288383484,-0.15963011980056763,0.003072799649089575 -1769682020,644784896,0.0,0.0,0.0,1.0,-0.0029339324682950974,0.0027098197024315596,0.0024739617947489023,-0.6798273324966431,-0.0591033473610878,0.004255509003996849 -1769682020,678584832,0.0,0.0,0.0,1.0,-0.0029738196171820164,0.0026103442069143057,0.0024855879601091146,-0.520237147808075,-0.3191750645637512,0.004787363111972809 -1769682020,710590464,0.0,0.0,0.0,1.0,-0.003265115199610591,0.002732487628236413,0.002488016849383712,4.266970790922642e-06,1.8579510651761666e-05,0.007152630016207695 -1769682020,757523968,0.0,0.0,0.0,1.0,-0.001192536554299295,0.0028862154576927423,0.0032887887209653854,-0.6798295974731445,-0.058864399790763855,0.03027988225221634 -1769682020,779055616,0.0,0.0,0.0,1.0,3.1192321330308914e-06,0.003574145259335637,0.004201407078653574,-0.4994281828403473,0.23081235587596893,0.029420938342809677 -1769682020,811077888,0.0,0.0,0.0,1.0,0.00021784832642879337,0.004155638627707958,0.004856544081121683,-0.3399200737476349,-0.029293043538928032,0.035926949232816696 -1769682020,859848448,0.0,0.0,0.0,1.0,0.0002815593034029007,0.004719587508589029,0.00546981068328023,0.18051429092884064,0.2895667254924774,0.012374421581625938 -1769682020,873881600,0.0,0.0,0.0,1.0,0.00015066724154166877,0.004924987908452749,0.005703721661120653,-9.922950994223356e-08,3.878487041220069e-05,0.015497169457376003 -1769682020,912237056,0.0,0.0,0.0,1.0,0.0003449393843766302,0.005179139319807291,0.0060071395710110664,-0.07966878265142441,0.13017573952674866,0.013960381038486958 -1769682020,943518464,0.0,0.0,0.0,1.0,-0.00011628677020780742,0.005234840791672468,0.006192019209265709,-0.6799085736274719,-0.05823757126927376,-0.007286674343049526 -1769682020,976794880,0.0,0.0,0.0,1.0,0.0006705350824631751,0.005157118197530508,0.006279081106185913,0.5207087993621826,0.31839150190353394,-0.01839715801179409 -1769682021,12615680,0.0,0.0,0.0,1.0,0.0002828471770044416,0.005256240256130695,0.006345172878354788,-0.15916307270526886,0.2603571116924286,-0.009127151221036911 -1769682021,46971136,0.0,0.0,0.0,1.0,9.191378194373101e-05,0.005171367898583412,0.006324755493551493,-0.6003636121749878,-0.18807362020015717,-0.029877468943595886 -1769682021,76916224,0.0,0.0,0.0,1.0,0.0001792931871023029,0.00495016248896718,0.0063250744715332985,-0.4194920063018799,0.1013675406575203,-0.011443562805652618 -1769682021,110328064,0.0,0.0,0.0,1.0,0.00032038730569183826,0.004554418381303549,0.006290524732321501,-0.33997204899787903,-0.028786655515432358,-0.00868501141667366 -1769682021,162013696,0.0,0.0,0.0,1.0,0.0003008018829859793,0.004518935456871986,0.006215964909642935,-0.41945216059684753,0.10156692564487457,-0.005619330797344446 -1769682021,172635392,0.0,0.0,0.0,1.0,-8.896219515008852e-05,0.004325512330979109,0.00617254339158535,-0.15891531109809875,0.2605539858341217,0.0050462521612644196 -1769682021,211464192,0.0,0.0,0.0,1.0,-0.00022953332518227398,0.004473834298551083,0.006108389236032963,-0.3399839699268341,-0.02857929840683937,-0.010027348063886166 -1769682021,247774208,0.0,0.0,0.0,1.0,0.0001401766057824716,0.004503927193582058,0.006037286948412657,0.2605994939804077,0.1588049978017807,0.009602688252925873 -1769682021,278373376,0.0,0.0,0.0,1.0,-0.0003942037292290479,0.00473205279558897,0.005948987323790789,-0.781957745552063,-0.4761722683906555,0.010421765968203545 -1769682021,310172160,0.0,0.0,0.0,1.0,0.0001690940116532147,0.0045538595877587795,0.005885944236069918,0.18135590851306915,0.28900161385536194,-0.00990759115666151 -1769682021,344241664,0.0,0.0,0.0,1.0,0.00011993679072475061,0.00443072896450758,0.005790318828076124,-0.0793125107884407,0.13035471737384796,-0.0005227377405390143 -1769682021,377205504,0.0,0.0,0.0,1.0,0.0003104891220573336,0.004586861934512854,0.005741224158555269,0.10222768783569336,0.4192434549331665,-0.029457520693540573 -1769682021,411677952,0.0,0.0,0.0,1.0,-1.143282133853063e-05,0.004665837623178959,0.00569411925971508,-0.15846459567546844,0.2606922686100006,-0.028507284820079803 -1769682021,446598400,0.0,0.0,0.0,1.0,0.0002836619096342474,0.0043972693383693695,0.005206753965467215,-0.34011417627334595,-0.02800750359892845,0.026555053889751434 -1769682021,477125888,0.0,0.0,0.0,1.0,-0.0012630674755200744,0.0031205317936837673,0.004104235675185919,-0.10248814523220062,-0.41916516423225403,0.03894533962011337 -1769682021,513151488,0.0,0.0,0.0,1.0,-0.0021177385933697224,0.0021629114635288715,0.0032855295576155186,-0.41933274269104004,0.10249053686857224,0.02592773176729679 -1769682021,559305984,0.0,0.0,0.0,1.0,-0.0031242237892001867,0.0015965915517881513,0.002541346475481987,-0.9410632848739624,-0.21421638131141663,0.03465370088815689 -1769682021,568832256,0.0,0.0,0.0,1.0,-0.0037480639293789864,0.001469478360377252,0.0022572509478777647,-0.9410922527313232,-0.214161217212677,0.040568411350250244 -1769682021,609844224,0.0,0.0,0.0,1.0,-0.004667934030294418,0.0013674118090420961,0.0018252590671181679,-0.6009419560432434,-0.1862608790397644,0.0033193137496709824 -1769682021,648161536,0.0,0.0,0.0,1.0,-0.0053909714333713055,0.001497872406616807,0.0015374585054814816,-3.7521122067118995e-06,2.3674986096011708e-06,0.0011920854449272156 -1769682021,679477248,0.0,0.0,0.0,1.0,-0.005256290081888437,0.0018826216692104936,0.0013931109569966793,-0.34002792835235596,-0.027894943952560425,-0.009381272830069065 -1769682021,710776064,0.0,0.0,0.0,1.0,-0.005273687187582254,0.002097558928653598,0.0012741953833028674,-0.8618564009666443,-0.34449219703674316,-0.002233244478702545 -1769682021,761895424,0.0,0.0,0.0,1.0,-0.005240064114332199,0.002320703584700823,0.0011840853840112686,-0.15820905566215515,0.26086682081222534,-0.028329260647296906 -1769682021,776955904,0.0,0.0,0.0,1.0,-0.005117230117321014,0.002550919074565172,0.0011458109365776181,0.2609485983848572,0.15827973186969757,-0.010042271576821804 -1769682021,809715456,0.0,0.0,0.0,1.0,-0.005280615296214819,0.0027243804652243853,0.001122458023019135,-0.340000182390213,-0.027844756841659546,-0.017847727984189987 -1769682021,852265472,0.0,0.0,0.0,1.0,-0.004908241797238588,0.002757570706307888,0.0011116156820207834,-0.5218009948730469,-0.31655818223953247,-0.014700695872306824 -1769682021,882038784,0.0,0.0,0.0,1.0,-0.005110922735184431,0.002876236569136381,0.0011093424400314689,-0.18180707097053528,-0.2887275516986847,0.0019403165206313133 -1769682021,910562304,0.0,0.0,0.0,1.0,-0.004910163581371307,0.0027780334930866957,0.001105863368138671,0.34010645747184753,0.027779676020145416,-0.010652264580130577 -1769682021,944945152,0.0,0.0,0.0,1.0,-0.004704038612544537,0.002948861103504896,0.0011004672851413488,0.18176472187042236,0.28872162103652954,0.014883749186992645 -1769682021,976455936,0.0,0.0,0.0,1.0,-0.004663723986595869,0.002879429142922163,0.001098032807931304,-0.3399682343006134,-0.0277679692953825,-0.025187961757183075 -1769682022,11354880,0.0,0.0,0.0,1.0,-0.00453756470233202,0.002935101045295596,0.0010829137172549963,-0.5218209028244019,-0.31645578145980835,-0.022336140275001526 -1769682022,58962176,0.0,0.0,0.0,1.0,-0.00455908989533782,0.0028786510229110718,0.0010401703184470534,-0.33999523520469666,-0.027734432369470596,-0.018112167716026306 -1769682022,71576576,0.0,0.0,0.0,1.0,-0.0045872521586716175,0.0027450299821794033,0.0010254201479256153,-0.15828394889831543,0.26096197962760925,0.017238546162843704 -1769682022,109678080,0.0,0.0,0.0,1.0,-0.004464726895093918,0.002932851668447256,0.0009765615686774254,-0.07905728369951248,0.13048788905143738,-0.009843803942203522 -1769682022,165895936,0.0,0.0,0.0,1.0,-0.004448650870472193,0.002836560131981969,0.0009396105306223035,-0.6802093386650085,-0.05540888011455536,0.013623273931443691 -1769682022,174504448,0.0,0.0,0.0,1.0,-0.00444706529378891,0.0027948087081313133,0.0008987404289655387,-0.4192452132701874,0.1027878001332283,0.017225250601768494 -1769682022,211208704,0.0,0.0,0.0,1.0,-0.004554073326289654,0.0028900958131998777,0.0008583407034166157,-0.41915544867515564,0.10281050205230713,-0.0018703923560678959 -1769682022,252853760,0.0,0.0,0.0,1.0,-0.0044236755929887295,0.002864146139472723,0.0008228504448197782,-0.18184205889701843,-0.2886486053466797,-0.014243505895137787 -1769682022,278900992,0.0,0.0,0.0,1.0,-0.004577312618494034,0.002774567576125264,0.0008148382767103612,-0.07915423065423965,0.1304808259010315,0.015251725912094116 -1769682022,310474752,0.0,0.0,0.0,1.0,-0.004532750695943832,0.0027848253957927227,0.0007798345177434385,-0.7592989802360535,0.0751723200082779,0.013041593134403229 -1769682022,350478848,0.0,0.0,0.0,1.0,-0.004525846801698208,0.0028451806865632534,0.0007888402324169874,-0.2608250081539154,-0.15809674561023712,-0.03610081225633621 -1769682022,378842880,0.0,0.0,0.0,1.0,-0.00469947000965476,0.002897967817261815,0.0007730756769888103,-0.26089268922805786,-0.15810543298721313,-0.023032452911138535 -1769682022,411169280,0.0,0.0,0.0,1.0,-0.004781089257448912,0.0028516617603600025,0.0007498615887016058,-0.3401752710342407,-0.02766188234090805,0.01606580801308155 -1769682022,463796992,0.0,0.0,0.0,1.0,-0.004808102734386921,0.002877181861549616,0.0007383294869214296,-0.26092180609703064,-0.15809299051761627,-0.018366726115345955 -1769682022,476756224,0.0,0.0,0.0,1.0,-0.004561657551676035,0.0029231582302600145,0.0007071188883855939,7.086689583957195e-05,2.5817509595071897e-05,-0.013112906366586685 -1769682022,511643648,0.0,0.0,0.0,1.0,-0.004737295210361481,0.0030139992013573647,0.0006608128314837813,-0.18194729089736938,-0.2886180877685547,-0.003993373364210129 -1769682022,546880000,0.0,0.0,0.0,1.0,-0.0045842076651751995,0.002930551068857312,0.0005915969959460199,-0.6801910400390625,-0.05519567057490349,0.0032095834612846375 -1769682022,568301056,0.0,0.0,0.0,1.0,-0.004450775217264891,0.002991301007568836,0.0005805643741041422,-0.4191393554210663,0.10292025655508041,0.00025444338098168373 -1769682022,610092032,0.0,0.0,0.0,1.0,-0.004591223318129778,0.0029916793573647738,0.0005023471894674003,0.18199719488620758,0.28862109780311584,-0.001774609787389636 -1769682022,648278528,0.0,0.0,0.0,1.0,-0.004629518371075392,0.0028420838061720133,0.00044076365884393454,0.1820378601551056,0.288634717464447,-0.007658651098608971 -1769682022,676817664,0.0,0.0,0.0,1.0,-0.005571292247623205,0.0034960992634296417,0.0004625300061888993,-0.2613450288772583,-0.15824155509471893,0.050418321043252945 -1769682022,710621184,0.0,0.0,0.0,1.0,-0.0056869350373744965,0.003664272138848901,0.000488597434014082,5.826639971928671e-05,2.9622206056956202e-05,-0.009536526165902615 -1769682022,754890752,0.0,0.0,0.0,1.0,-0.0060885013081133366,0.0038827569223940372,0.0005164111498743296,0.18208430707454681,0.2886461615562439,-0.012198958545923233 -1769682022,776943104,0.0,0.0,0.0,1.0,-0.006425629369914532,0.003987230826169252,0.0005059108370915055,-0.2611284852027893,-0.15812350809574127,0.01207861676812172 -1769682022,810786560,0.0,0.0,0.0,1.0,-0.006350731942802668,0.004076996352523565,0.0005414236220531166,-0.5219933986663818,-0.31608766317367554,-0.017690690234303474 -1769682022,848917248,0.0,0.0,0.0,1.0,-0.006592810619622469,0.004181189462542534,0.0005465829744935036,-0.26092302799224854,-0.1579904854297638,-0.020255709066987038 -1769682022,878193664,0.0,0.0,0.0,1.0,-0.006966360379010439,0.004137731622904539,0.000565669615752995,-0.26102855801582336,-0.15804705023765564,-0.004824052564799786 -1769682022,910323200,0.0,0.0,0.0,1.0,-0.006810111925005913,0.004193337634205818,0.0005892704357393086,-0.6011151075363159,-0.1855708360671997,-0.006173995323479176 -1769682022,944896512,0.0,0.0,0.0,1.0,-0.00682809017598629,0.004057300742715597,0.0006316254148259759,-0.10303331166505814,-0.4191268980503082,0.0020768558606505394 -1769682022,968076032,0.0,0.0,0.0,1.0,-0.006791441701352596,0.004028115421533585,0.0006470362422987819,0.34011077880859375,0.027533255517482758,-0.002196104731410742 -1769682023,12306944,0.0,0.0,0.0,1.0,-0.0039479294791817665,0.0030263070948421955,0.0005534047377295792,-0.07939611375331879,0.13027431070804596,0.051337696611881256 -1769682023,52602368,0.0,0.0,0.0,1.0,-0.0026193992234766483,0.0011950981570407748,0.0004502914089243859,0.07868341356515884,-0.1307680308818817,0.04520835727453232 -1769682023,78546176,0.0,0.0,0.0,1.0,-0.0019906621892005205,0.00042993962415494025,0.00040724524296820164,0.18174384534358978,0.28834858536720276,0.04338814690709114 -1769682023,110942464,0.0,0.0,0.0,1.0,-0.0019326518522575498,-0.00034188898280262947,0.00038247142219915986,0.4428982436656952,0.44642916321754456,0.03425344079732895 -1769682023,150531328,0.0,0.0,0.0,1.0,-0.0016803945181891322,-0.0004860684275627136,0.0003338879032526165,0.6010286211967468,0.18541637063026428,0.020932931452989578 -1769682023,177417472,0.0,0.0,0.0,1.0,-0.001732200151309371,-0.0005121568683534861,0.00030171641265042126,-8.788714694674127e-06,-6.4556061261100695e-06,0.0011920437682420015 -1769682023,210151424,0.0,0.0,0.0,1.0,-0.0016255168011412024,-9.580120968166739e-05,0.00026305264327675104,0.26122573018074036,0.15813077986240387,-0.0186705831438303 -1769682023,260018944,0.0,0.0,0.0,1.0,-0.0014398047933354974,0.0009735508938319981,0.0002519825065974146,0.26120132207870483,0.1581096202135086,-0.015077798627316952 -1769682023,267456000,0.0,0.0,0.0,1.0,-0.0011932122288271785,0.001441214350052178,0.0002427065628580749,0.3643425405025482,0.5772640705108643,-0.02389470301568508 -1769682023,311934464,0.0,0.0,0.0,1.0,-0.0013901668135076761,0.0020995596423745155,0.00021443651348818094,0.18217027187347412,0.2886277139186859,-0.011320717632770538 -1769682023,348523264,0.0,0.0,0.0,1.0,-0.0015179289039224386,0.0025903922505676746,0.00019237269589211792,-0.26085472106933594,-0.15784254670143127,-0.03148750960826874 -1769682023,372276736,0.0,0.0,0.0,1.0,-0.0014749473193660378,0.0025216180365532637,0.00017765199299901724,0.07911587506532669,-0.13045985996723175,-0.014444162137806416 -1769682023,410816768,0.0,0.0,0.0,1.0,-0.001587596139870584,0.0024008513428270817,0.00015964968770276755,-3.693064354592934e-05,-2.746362952166237e-05,0.004768152721226215 -1769682023,448561664,0.0,0.0,0.0,1.0,-0.0014601255534216762,0.0023810577113181353,0.00011923519195988774,-0.0790611207485199,0.13050061464309692,0.0072927637957036495 -1769682023,476992000,0.0,0.0,0.0,1.0,-0.0015421544667333364,0.0022477363236248493,0.00010196937364526093,0.15769827365875244,-0.26131579279899597,0.03905453905463219 -1769682023,501478144,0.0,0.0,0.0,1.0,-0.0014715950237587094,0.0021145902574062347,8.396844350500032e-05,0.26100775599479675,0.15794965624809265,0.011352398432791233 -1769682023,548555264,0.0,0.0,0.0,1.0,-0.0015163597417995334,0.002028438728302717,4.909520430373959e-05,-0.2610741853713989,-0.1579979658126831,-0.003048896323889494 -1769682023,576540160,0.0,0.0,0.0,1.0,-0.0013323320308700204,0.0019623106345534325,2.8547807232826017e-05,-0.07908141613006592,0.1304853856563568,0.009682082571089268 -1769682023,610271744,0.0,0.0,0.0,1.0,-0.0015953108668327332,0.0019504769006744027,-3.792163624893874e-06,0.1578909456729889,-0.2611728608608246,0.014007728546857834 -1769682023,650550784,0.0,0.0,0.0,1.0,-0.0020990613847970963,0.0018307045102119446,-1.1971147614531219e-05,0.0789056196808815,-0.13061626255512238,0.011768573895096779 -1769682023,677761280,0.0,0.0,0.0,1.0,-0.0019098640186712146,0.0017931892070919275,-1.1313595678075217e-05,-0.18206946551799774,-0.28853991627693176,-0.003303603269159794 -1769682023,710422528,0.0,0.0,0.0,1.0,-0.001851406297646463,0.0017039261292666197,-2.8573282179422677e-05,0.3400774300098419,0.02745434269309044,0.00301567860879004 -1769682023,767465472,0.0,0.0,0.0,1.0,-0.0015982529148459435,0.001843755366280675,-1.8797565644490533e-05,0.07903444021940231,-0.13052009046077728,-0.00373563589528203 -1769682023,775609856,0.0,0.0,0.0,1.0,-0.001861603930592537,0.0018535519484430552,-1.66758218256291e-05,0.07918643206357956,-0.13040582835674286,-0.021618565544486046 -1769682023,810900224,0.0,0.0,0.0,1.0,-0.0016450220718979836,0.0018527066567912698,4.668476321967319e-06,-0.07881089299917221,0.13068819046020508,-0.02248453162610531 -1769682023,846051328,0.0,0.0,0.0,1.0,-0.0015907384222373366,0.001819394645281136,3.35047698172275e-05,-0.1820475310087204,-0.28852370381355286,-0.005826436914503574 -1769682023,876978688,0.0,0.0,0.0,1.0,-0.0015728160506114364,0.0018730566371232271,4.270305726095103e-05,-0.26106202602386475,-0.15798823535442352,-0.004489169456064701 -1769682023,911592192,0.0,0.0,0.0,1.0,-0.0016957507468760014,0.0018171851988881826,5.3468815167434514e-05,0.10308535397052765,0.4190969169139862,0.0012778027448803186 -1769682023,950628608,0.0,0.0,0.0,1.0,-0.0011504126014187932,0.0019479203037917614,0.00030516739934682846,-0.44308018684387207,-0.44648313522338867,-0.014021364971995354 -1769682023,979652352,0.0,0.0,0.0,1.0,-0.0004275682440493256,0.002172796055674553,0.0006006965413689613,1.0563991054368671e-05,7.94676088844426e-06,-0.0011920204851776361 -1769682024,9963776,0.0,0.0,0.0,1.0,-0.000243854578002356,0.0025780457071959972,0.0007821746985428035,0.18212275207042694,0.28856202960014343,-0.001214747317135334 -1769682024,49433088,0.0,0.0,0.0,1.0,0.0002083012368530035,0.002713217167183757,0.0009467425406910479,-0.36447128653526306,-0.5772621035575867,0.025039970874786377 -1769682024,79658240,0.0,0.0,0.0,1.0,0.0003045535122510046,0.0028374199755489826,0.0010254407534375787,-0.34005627036094666,-0.027399461716413498,-0.005672721192240715 -1769682024,111691520,0.0,0.0,0.0,1.0,0.00013964406389277428,0.002873390680179,0.0010535138426348567,0.1582132875919342,-0.26093313097953796,-0.026507340371608734 -1769682024,143777280,0.0,0.0,0.0,1.0,6.492636748589575e-05,0.0030179847963154316,0.0010478991316631436,8.90618612174876e-05,6.343828863464296e-05,-0.00953612383455038 -1769682024,177519360,0.0,0.0,0.0,1.0,0.000529253389686346,0.0024657677859067917,0.001066801487468183,0.07908836007118225,-0.13048052787780762,-0.012044357135891914 -1769682024,210771200,0.0,0.0,0.0,1.0,0.00011414129403419793,0.002137495204806328,0.0010426645167171955,-0.6798332333564758,-0.054507769644260406,-0.041384655982255936 -1769682024,248420096,0.0,0.0,0.0,1.0,7.543213723693043e-05,0.0016907607205212116,0.0010180240496993065,0.261365681886673,0.15809419751167297,-0.022680044174194336 -1769682024,277323776,0.0,0.0,0.0,1.0,-0.00014657255087513477,0.0015881586587056518,0.0009879089193418622,0.6803247332572937,0.054799482226371765,-0.009790281765162945 -1769682024,311400960,0.0,0.0,0.0,1.0,-0.0001358057197649032,0.001471725874580443,0.0009409741614945233,-0.18207307159900665,-0.2884118854999542,-0.013206349685788155 -1769682024,347001600,0.0,0.0,0.0,1.0,0.00021336005011107773,0.001440417836420238,0.0009023654274642467,0.33985212445259094,0.027164272964000702,0.027323033660650253 -1769682024,376586240,0.0,0.0,0.0,1.0,0.0002896078513003886,0.0013741147704422474,0.0008770122658461332,-0.4434793293476105,-0.4464624226093292,0.009413884952664375 -1769682024,410203136,0.0,0.0,0.0,1.0,0.00031055189901962876,0.0013945618411526084,0.0008299326291307807,0.26126575469970703,0.15796856582164764,-0.009511101990938187 -1769682024,446993408,0.0,0.0,0.0,1.0,3.856822513625957e-05,0.0013655397342517972,0.0007883140351623297,0.2607666850090027,0.15762126445770264,0.0417594276368618 -1769682024,478015744,0.0,0.0,0.0,1.0,3.638041380327195e-05,0.0013528323033824563,0.0007506097899749875,-0.26112210750579834,-0.15785180032253265,-0.006010167300701141 -1769682024,510290176,0.0,0.0,0.0,1.0,0.00018781237304210663,0.0013761045411229134,0.0007227301248349249,0.2613857388496399,0.15801943838596344,-0.020203370600938797 -1769682024,562672384,0.0,0.0,0.0,1.0,-0.00018199441547039896,0.0013579961378127337,0.0006602095090784132,0.2611173689365387,0.15783114731311798,0.007227485999464989 -1769682024,569429760,0.0,0.0,0.0,1.0,-0.00010999922960763797,0.0015274969628080726,0.0006260153604671359,0.41880425810813904,-0.10346320271492004,0.02497177943587303 -1769682024,611751424,0.0,0.0,0.0,1.0,-0.000824393646325916,0.0006716857315041125,0.00010208832827629521,-0.07945813238620758,0.1302400827407837,0.052519023418426514 -1769682024,646274816,0.0,0.0,0.0,1.0,-0.0013289459748193622,0.0003454602265264839,-0.00030289340065792203,-0.2611795961856842,-0.15786579251289368,-0.00129981548525393 -1769682024,677509120,0.0,0.0,0.0,1.0,-0.00160176248755306,-1.388329837936908e-05,-0.0005377765628509223,0.18208786845207214,0.2883511781692505,0.016882993280887604 -1769682024,710402816,0.0,0.0,0.0,1.0,-0.0018516907002776861,-0.0001383966882713139,-0.00075321871554479,0.4190100431442261,-0.10331770777702332,0.004717601463198662 -1769682024,757998080,0.0,0.0,0.0,1.0,-0.0021057804115116596,-5.845008126925677e-05,-0.0009711916791275144,-0.3402172327041626,-0.02737589366734028,0.009498586878180504 -1769682024,766961152,0.0,0.0,0.0,1.0,-0.002270494820550084,-3.713593469001353e-05,-0.0010651370976120234,-0.18220989406108856,-0.2884606420993805,-0.0026280893944203854 -1769682024,810832896,0.0,0.0,0.0,1.0,-0.0021510201040655375,-3.0867275199852884e-05,-0.0012055148836225271,-0.07884129881858826,0.13065071403980255,-0.010613602586090565 -1769682024,860964352,0.0,0.0,0.0,1.0,-0.0021379380486905575,0.00014650207594968379,-0.0013235254446044564,-0.18234986066818237,-0.2885957360267639,0.01400850247591734 -1769682024,876510976,0.0,0.0,0.0,1.0,-0.0021842338610440493,0.00033904684823937714,-0.001377952634356916,-0.10313619673252106,-0.41900303959846497,-0.009984605014324188 -1769682024,910624512,0.0,0.0,0.0,1.0,-0.001772206393070519,0.00015586239169351757,-0.0014460883103311062,-0.18216949701309204,-0.288501501083374,-0.001525825704447925 -1769682024,946598656,0.0,0.0,0.0,1.0,-0.0018590284744277596,0.0002967343316413462,-0.0014830069849267602,0.26109105348587036,0.15792560577392578,0.004977104719728231 -1769682024,967790592,0.0,0.0,0.0,1.0,-0.002040123101323843,0.00038803659845143557,-0.001518701552413404,0.18219193816184998,0.2885523736476898,-0.0032042283564805984 -1769682025,14878976,0.0,0.0,0.0,1.0,-0.0020106250885874033,0.00027095459518022835,-0.0015566330403089523,-0.18212583661079407,-0.2885287404060364,-0.0015875946264714003 -1769682025,47076096,0.0,0.0,0.0,1.0,-0.0014233876718208194,0.00032799170003272593,-0.001601917203515768,0.33988022804260254,0.027283940464258194,0.02272261306643486 -1769682025,77172736,0.0,0.0,0.0,1.0,-0.0021844676230102777,0.0003547013329807669,-0.0016586793353781104,-0.26107057929039,-0.1579868495464325,-0.0038339910097420216 -1769682025,110536960,0.0,0.0,0.0,1.0,-0.002113817259669304,0.0003940212482120842,-0.0017309397226199508,-7.262994768097997e-05,-5.407795470091514e-05,0.007151988800615072 -1769682025,153158144,0.0,0.0,0.0,1.0,-0.0017873315373435616,0.00040214144974015653,-0.0018121656030416489,-0.00012122451880713925,-9.09105219761841e-05,0.011919974349439144 -1769682025,178824704,0.0,0.0,0.0,1.0,-0.0014060157118365169,0.0003561849589459598,-0.001894650747999549,0.5220340490341187,0.3160257637500763,0.013703161850571632 -1769682025,210188032,0.0,0.0,0.0,1.0,-0.0018152393167838454,0.0004224117728881538,-0.001962834969162941,0.07891089469194412,-0.13061779737472534,0.011716163717210293 -1769682025,250141952,0.0,0.0,0.0,1.0,-0.0015270158182829618,0.0003139556501992047,-0.002063256921246648,-3.648027632152662e-05,-2.7895548555534333e-05,0.0035759862512350082 -1769682025,279085056,0.0,0.0,0.0,1.0,-0.0017247035866603255,0.0001328900398220867,-0.0021460189018398523,-0.34006136655807495,-0.02757083997130394,-0.003687983611598611 -1769682025,311014912,0.0,0.0,0.0,1.0,-0.001962837530300021,0.00023503982811234891,-0.00222213682718575,-0.340376079082489,-0.027838073670864105,0.027300497516989708 -1769682025,344905216,0.0,0.0,0.0,1.0,-0.001546944142319262,0.0002541377325542271,-0.0022920339833945036,0.7039570808410645,0.6049350500106812,0.00486038951203227 -1769682025,367199488,0.0,0.0,0.0,1.0,-0.0012688532005995512,0.00023388181580230594,-0.002354515716433525,-0.18181462585926056,-0.2885688245296478,-0.012512650340795517 -1769682025,411104000,0.0,0.0,0.0,1.0,-0.001594405504874885,0.00034548970870673656,-0.002471220912411809,0.5220345854759216,0.31641191244125366,-0.002832903992384672 -1769682025,459264000,0.0,0.0,0.0,1.0,-0.0020803557708859444,0.00028704863507300615,-0.0026500513777136803,-0.157963365316391,0.2611583471298218,-0.02333899214863777 -1769682025,468748032,0.0,0.0,0.0,1.0,-0.0002451996551826596,-0.0006064838380552828,-0.0027955700643360615,0.783129870891571,0.4748624563217163,-0.019112585112452507 -1769682025,502334464,0.0,0.0,0.0,1.0,0.0012498389696702361,-0.0018436142709106207,-0.003050104482099414,0.601231575012207,0.18621297180652618,-0.018594717606902122 -1769682025,548987136,0.0,0.0,0.0,1.0,0.002436462789773941,-0.0028003216721117496,-0.0032208331394940615,0.5220992565155029,0.3167746067047119,-0.0219978466629982 -1769682025,579428352,0.0,0.0,0.0,1.0,0.0032764466013759375,-0.0032581426203250885,-0.0033160201273858547,0.15856173634529114,-0.2607029974460602,-0.025518739596009254 -1769682025,614193152,0.0,0.0,0.0,1.0,0.003763077314943075,-0.0036298225168138742,-0.003384624607861042,0.18169951438903809,0.28876346349716187,0.004054335877299309 -1769682025,650633472,0.0,0.0,0.0,1.0,0.004252694547176361,-0.0037581808865070343,-0.0034867103677242994,0.41924431920051575,-0.10248805582523346,0.0009149415418505669 -1769682025,677529088,0.0,0.0,0.0,1.0,0.004414575640112162,-0.0036374470219016075,-0.0035492933820933104,0.6006901264190674,0.18621298670768738,0.025069374591112137 -1769682025,710178560,0.0,0.0,0.0,1.0,0.004530878737568855,-0.0034961188212037086,-0.0036152522079646587,0.26092755794525146,0.15850232541561127,-0.008264802396297455 -1769682025,762567680,0.0,0.0,0.0,1.0,0.004167797509580851,-0.003338838228955865,-0.003688489319756627,-0.1584007441997528,0.260858416557312,-0.006754905916750431 -1769682025,769988352,0.0,0.0,0.0,1.0,0.004475228022783995,-0.0033268413972109556,-0.0037303967401385307,0.4422382414340973,0.44728341698646545,0.015656860545277596 -1769682025,811881472,0.0,0.0,0.0,1.0,0.004304883535951376,-0.0031583255622535944,-0.0037905126810073853,0.41931572556495667,-0.10223355889320374,-0.00043644243851304054 -1769682025,845780224,0.0,0.0,0.0,1.0,0.0042936489917337894,-0.003148099174723029,-0.003855051239952445,0.3399401605129242,0.028123129159212112,0.01161525771021843 -1769682025,896609024,0.0,0.0,0.0,1.0,0.003913823049515486,-0.003003304358571768,-0.0038817645981907845,0.6007592082023621,0.18682751059532166,0.0030550933443009853 -1769682025,916404224,0.0,0.0,0.0,1.0,0.0036527893971651793,-0.0030826893635094166,-0.003897880669683218,-0.10222767293453217,-0.4194420278072357,0.014226112514734268 -1769682025,950042112,0.0,0.0,0.0,1.0,0.003778030164539814,-0.002933284966275096,-0.0039000592660158873,0.5215418338775635,0.3174569010734558,-0.01605476811528206 -1769682025,966524160,0.0,0.0,0.0,1.0,0.004928953479975462,-0.0034393328242003918,-0.003910656552761793,0.44173723459243774,0.4475165903568268,0.034080855548381805 -1769682026,10418176,0.0,0.0,0.0,1.0,0.005291566252708435,-0.004043112508952618,-0.00392820592969656,0.8613107204437256,0.3458597958087921,0.004695627838373184 -1769682026,60415232,0.0,0.0,0.0,1.0,0.004800995346158743,-0.004275918006896973,-0.003913785330951214,0.10177116096019745,0.41933342814445496,0.011682724580168724 -1769682026,68340224,0.0,0.0,0.0,1.0,0.004547751974314451,-0.004372790921479464,-0.003921557683497667,0.6798791289329529,0.056873567402362823,0.019070561975240707 -1769682026,112941056,0.0,0.0,0.0,1.0,0.0048365285620093346,-0.004243018571287394,-0.0039020779076963663,-0.15889866650104523,0.26053887605667114,0.008528498001396656 -1769682026,152789504,0.0,0.0,0.0,1.0,0.004517365247011185,-0.004235259257256985,-0.0039180270396173,0.07958721369504929,-0.13017648458480835,-0.019153432920575142 -1769682026,179586560,0.0,0.0,0.0,1.0,0.004926342982798815,-0.004091713111847639,-0.003941504284739494,0.3400851786136627,0.028692997992038727,-0.010306349024176598 -1769682026,211516416,0.0,0.0,0.0,1.0,0.0041700974106788635,-0.003941432107239962,-0.004002852365374565,0.057440150529146194,-0.6799221038818359,-0.013814771547913551 -1769682026,248396288,0.0,0.0,0.0,1.0,0.004078778438270092,-0.0033001548144966364,-0.004061430227011442,-0.07920920103788376,0.13043397665023804,-0.03690038621425629 -1769682026,277673984,0.0,0.0,0.0,1.0,0.004546398762613535,-0.002788727870211005,-0.0040591093711555,-0.1808403730392456,-0.2891584038734436,-0.0194469653069973 -1769682026,312977664,0.0,0.0,0.0,1.0,0.0046007512137293816,-0.0023847869597375393,-0.004077659919857979,0.2385677993297577,-0.39068278670310974,-0.0012839487753808498 -1769682026,361124608,0.0,0.0,0.0,1.0,0.004725880455225706,-0.0022392922546714544,-0.0040890551172196865,-0.18094338476657867,-0.28933030366897583,0.005707928910851479 -1769682026,372091648,0.0,0.0,0.0,1.0,0.004352065734565258,-0.0022790462244302034,-0.004084046930074692,0.15909452736377716,-0.260425329208374,0.0011801805812865496 -1769682026,411293952,0.0,0.0,0.0,1.0,0.0045715924352407455,-0.002361821476370096,-0.004095620010048151,0.18076924979686737,0.28931179642677307,0.008494540117681026 -1769682026,456879360,0.0,0.0,0.0,1.0,0.004474163521081209,-0.0023764180950820446,-0.0040992251597344875,0.6002437472343445,0.1881137192249298,0.01576092280447483 -1769682026,474326272,0.0,0.0,0.0,1.0,0.0045755296014249325,-0.0025278788525611162,-0.004107434768229723,-4.160061871516518e-05,-2.373063216509763e-05,0.005960275884717703 -1769682026,511446016,0.0,0.0,0.0,1.0,0.004587067291140556,-0.0026058463845402002,-0.004124761559069157,0.41958102583885193,-0.10107540339231491,0.0013156314380466938 -1769682026,547110912,0.0,0.0,0.0,1.0,0.004261404275894165,-0.002524235285818577,-0.004139703232795,0.15925534069538116,-0.26032403111457825,0.00608702190220356 -1769682026,568729344,0.0,0.0,0.0,1.0,0.004099278710782528,-0.0026053215842694044,-0.004155838396400213,0.6001076102256775,0.18842321634292603,0.021416708827018738 -1769682026,611441920,0.0,0.0,0.0,1.0,0.004563738591969013,-0.0025993145536631346,-0.004171489737927914,0.34005364775657654,0.029287714511156082,-0.015523443929851055 -1769682026,661702912,0.0,0.0,0.0,1.0,0.004222643095999956,-0.002647108631208539,-0.004209639970213175,-0.26018884778022766,-0.1593824326992035,-0.008179815486073494 -1769682026,668305408,0.0,0.0,0.0,1.0,0.00429471954703331,-0.0028175089973956347,-0.00422512786462903,0.07958216965198517,-0.13017535209655762,0.020367801189422607 -1769682026,710523392,0.0,0.0,0.0,1.0,0.004032873548567295,-0.002708113519474864,-0.004271684214472771,0.15947872400283813,-0.2601911127567291,-0.0009592385031282902 -1769682026,752803584,0.0,0.0,0.0,1.0,0.004001556430011988,-0.002670817542821169,-0.004292170982807875,0.5202762484550476,0.31900686025619507,0.011313572525978088 -1769682026,778111488,0.0,0.0,0.0,1.0,0.003988491836935282,-0.0025673620402812958,-0.0043272231705486774,-0.2601473927497864,-0.1595507264137268,-0.0008487708400934935 -1769682026,812201984,0.0,0.0,0.0,1.0,0.003906992729753256,-0.002594483783468604,-0.004343975801020861,-0.18035681545734406,-0.2896569073200226,0.0029157684184610844 -1769682026,856098048,0.0,0.0,0.0,1.0,0.0038348319940268993,-0.002652144758030772,-0.00439015356823802,0.6000049114227295,0.1892087608575821,0.0028650141321122646 -1769682026,877694976,0.0,0.0,0.0,1.0,0.004351044539362192,-0.002560434164479375,-0.004400715231895447,0.6798117160797119,0.059249863028526306,0.002965171355754137 -1769682026,910620928,0.0,0.0,0.0,1.0,0.0030726243276149035,-0.0024682150688022375,-0.004783426411449909,-0.1802416741847992,-0.2897408902645111,0.005462369415909052 -1769682026,961139200,0.0,0.0,0.0,1.0,0.0006256558699533343,-0.0034284167923033237,-0.005971415434032679,0.3399057388305664,0.029750879853963852,-0.00037750881165266037 -1769682026,968531968,0.0,0.0,0.0,1.0,0.0003218948550056666,-0.0038807366508990526,-0.006413183640688658,0.33998262882232666,0.02982444129884243,-0.01470866333693266 -1769682027,12419328,0.0,0.0,0.0,1.0,0.00045956537360325456,-0.004702828824520111,-0.007032681722193956,0.5199126601219177,0.31972432136535645,0.002334066666662693 -1769682027,45026048,0.0,0.0,0.0,1.0,-0.0001292507949983701,-0.004933634772896767,-0.007453761529177427,0.339834600687027,0.02996557205915451,0.009008334949612617 -1769682027,80266496,0.0,0.0,0.0,1.0,-0.0005584704922512174,-0.00496777193620801,-0.007692338433116674,0.5997273325920105,0.1900508552789688,0.004676359705626965 -1769682027,111076864,0.0,0.0,0.0,1.0,-0.0004215130757074803,-0.005014221183955669,-0.00784516055136919,0.2401265949010849,-0.3897341191768646,-0.008002640679478645 -1769682027,152194816,0.0,0.0,0.0,1.0,-0.0007850199472159147,-0.005139875691384077,-0.007984570227563381,0.17955707013607025,0.28995898365974426,0.033682771027088165 -1769682027,178457600,0.0,0.0,0.0,1.0,-0.0005446779541671276,-0.005050865467637777,-0.008046045899391174,0.25968676805496216,0.16017384827136993,0.013475869782269001 -1769682027,214256640,0.0,0.0,0.0,1.0,-0.0001347070501651615,-0.005003886763006449,-0.008061482571065426,0.4198295772075653,-0.09951283037662506,0.032645948231220245 -1769682027,262811648,0.0,0.0,0.0,1.0,-0.00014108663890510798,-0.0028657938819378614,-0.008027960546314716,0.2591448724269867,0.1600804328918457,0.11949342489242554 -1769682027,275598336,0.0,0.0,0.0,1.0,-0.000158715556608513,-0.000665105355437845,-0.008123776875436306,-0.08054016530513763,0.12963108718395233,0.07862843573093414 -1769682027,311012096,0.0,0.0,0.0,1.0,7.252313662320375e-05,0.000887672184035182,-0.008199324831366539,0.4197884798049927,-0.09924241900444031,0.06236690282821655 -1769682027,365179648,0.0,0.0,0.0,1.0,8.74282413860783e-05,0.0025726635940372944,-0.008232568390667439,-0.00014550978085026145,-7.546236156485975e-05,0.0333782434463501 -1769682027,374592512,0.0,0.0,0.0,1.0,0.00015543668996542692,0.003520405385643244,-0.008225616998970509,0.6796130537986755,0.06177244707942009,-0.0027927402406930923 -1769682027,412386560,0.0,0.0,0.0,1.0,5.242385668680072e-06,0.0037504069041460752,-0.008217495866119862,0.5188997387886047,0.321380078792572,-0.0004830462858080864 -1769682027,445976320,0.0,0.0,0.0,1.0,0.00034818239510059357,0.003929989878088236,-0.008175578899681568,0.33985939621925354,0.03111487254500389,-0.016207195818424225 -1769682027,477207296,0.0,0.0,0.0,1.0,0.00028954300796613097,0.0038615369703620672,-0.008158594369888306,0.00016153781325556338,7.474260200979188e-05,-0.03337817266583443 -1769682027,511096832,0.0,0.0,0.0,1.0,0.00025449437089264393,0.0037359714042395353,-0.008127691224217415,-4.724450991488993e-05,-2.1299814761732705e-05,0.00953662022948265 -1769682027,549043200,0.0,0.0,0.0,1.0,0.00038543855771422386,0.003523502266034484,-0.008109590969979763,-0.08053421229124069,0.12961232662200928,0.00822281651198864 -1769682027,567848448,0.0,0.0,0.0,1.0,0.0003280571836512536,0.003293144516646862,-0.00806086789816618,0.08059262484312057,-0.129583477973938,-0.015369178727269173 -1769682027,644677376,0.0,0.0,0.0,1.0,1.218502438860014e-05,0.0032394416630268097,-0.008021627552807331,0.2591286301612854,0.16108621656894684,0.011266455054283142 -1769682027,657280256,0.0,0.0,0.0,1.0,0.00035539170494303107,0.002974833594635129,-0.007951408624649048,-0.08062143623828888,0.12955573201179504,0.004618329927325249 -1769682027,685291008,0.0,0.0,0.0,1.0,0.0004901747452095151,0.00294070434756577,-0.00789621938019991,0.35685956478118896,0.5815713405609131,0.01516962330788374 -1769682027,698618624,0.0,0.0,0.0,1.0,3.425265458645299e-05,0.0031575793400406837,-0.007862850092351437,8.632887329440564e-05,3.417849802644923e-05,-0.015496963635087013 -1769682027,752586240,0.0,0.0,0.0,1.0,0.0003084804047830403,0.003104948904365301,-0.0077286832965910435,0.25897306203842163,0.16138285398483276,0.006605618167668581 -1769682027,768605440,0.0,0.0,0.0,1.0,0.0003736128855962306,0.0031775981187820435,-0.007664551492780447,0.3395683169364929,0.03189561143517494,0.023493807762861252 -1769682027,814326016,0.0,0.0,0.0,1.0,0.00011793569137807935,0.003115937579423189,-0.007561386097222567,0.3396472930908203,0.03203295171260834,0.008038920350372791 -1769682027,867164928,0.0,0.0,0.0,1.0,0.00033669197000563145,0.0030914924573153257,-0.007439594715833664,0.5984638333320618,0.19370609521865845,0.018339253962039948 -1769682027,876033792,0.0,0.0,0.0,1.0,0.0003471581148914993,0.0030860917177051306,-0.007366688456386328,-0.17797374725341797,-0.2910553812980652,-0.008873858489096165 -1769682027,911251200,0.0,0.0,0.0,1.0,0.00044372337288223207,0.003152557648718357,-0.007288537919521332,0.6792864203453064,0.06458485126495361,0.00913647934794426 -1769682027,963968768,0.0,0.0,0.0,1.0,7.696660759393126e-06,0.003078578505665064,-0.00719173438847065,-9.841246355790645e-05,-3.344086871948093e-05,0.015496891923248768 -1769682027,970380032,0.0,0.0,0.0,1.0,0.00012385322770569474,0.0030121139716356993,-0.007165239192545414,0.08083940297365189,-0.1293942630290985,0.010969089344143867 -1769682028,10911744,0.0,0.0,0.0,1.0,-2.8468850359786302e-05,0.003013220615684986,-0.0070879640989005566,-0.015776455402374268,-0.5499082207679749,-0.013206406496465206 -1769682028,49575680,0.0,0.0,0.0,1.0,0.0011768231634050608,0.0044905198737978935,-0.0057405102998018265,0.258800208568573,0.16200168430805206,-0.020574145019054413 -1769682028,81022720,0.0,0.0,0.0,1.0,0.0019652927294373512,0.005112511105835438,-0.005039618816226721,0.3398320972919464,0.03274349495768547,-0.02860325202345848 -1769682028,111458048,0.0,0.0,0.0,1.0,0.002964996499940753,0.005504020489752293,-0.004486400168389082,-0.16178883612155914,0.25867703557014465,-0.0351865291595459 -1769682028,146592768,0.0,0.0,0.0,1.0,0.003131832927465439,0.005559518933296204,-0.003996967803686857,0.1773977279663086,0.29132866859436035,0.02090313471853733 -1769682028,177469952,0.0,0.0,0.0,1.0,0.0037684114649891853,0.005534959491342306,-0.0036925000604242086,0.5982290506362915,0.19494318962097168,-0.004770857281982899 -1769682028,212163328,0.0,0.0,0.0,1.0,0.003968323115259409,0.005089656449854374,-0.0034703039564192295,0.33932220935821533,0.03279770910739899,0.03957150876522064 -1769682028,254877440,0.0,0.0,0.0,1.0,0.004027035553008318,0.005070093087852001,-0.0032416668254882097,0.33952227234840393,0.032890163362026215,0.012218605726957321 -1769682028,277649152,0.0,0.0,0.0,1.0,0.004031319636851549,0.004758841823786497,-0.003111709840595722,0.16227352619171143,-0.2584930956363678,-0.00980349536985159 -1769682028,310662912,0.0,0.0,0.0,1.0,0.004262862727046013,0.004477494861930609,-0.0030037029646337032,-0.08116361498832703,0.12923748791217804,0.006663087289780378 -1769682028,361385728,0.0,0.0,0.0,1.0,0.003932512830942869,0.004337050952017307,-0.0029330833349376917,0.5980093479156494,0.19524957239627838,0.009889932349324226 -1769682028,369136896,0.0,0.0,0.0,1.0,0.0037609946448355913,0.00408543273806572,-0.0028962676879018545,0.25845393538475037,0.1622609794139862,0.002307528629899025 -1769682028,413135616,0.0,0.0,0.0,1.0,0.0034690112806856632,0.003922650590538979,-0.0028508752584457397,0.33948788046836853,0.03305886685848236,0.013626793399453163 -1769682028,446268672,0.0,0.0,0.0,1.0,0.003503011306747794,0.0040520369075238705,-0.002831061603501439,0.33962562680244446,0.03311152011156082,-0.0030122888274490833 -1769682028,481980928,0.0,0.0,0.0,1.0,0.0031020469032227993,0.0037271250039339066,-0.0028009761590510607,0.6791008114814758,0.06626883894205093,0.010734781622886658 -1769682028,510642944,0.0,0.0,0.0,1.0,0.0031395484693348408,0.003780998755246401,-0.0027836065273731947,0.17716121673583984,0.29156380891799927,0.007686781696975231 -1769682028,561065216,0.0,0.0,0.0,1.0,0.003052219282835722,0.0035414325539022684,-0.0027496907860040665,0.5019837021827698,-0.22517715394496918,0.0008382401429116726 -1769682028,567333888,0.0,0.0,0.0,1.0,0.0029665541369467974,0.003624201053753495,-0.0027410276234149933,0.5980309247970581,0.19563323259353638,-0.006432804279029369 -1769682028,615123200,0.0,0.0,0.0,1.0,0.002913279691711068,0.0035609565675258636,-0.0027069139759987593,0.6790608167648315,0.06651587039232254,0.012226186692714691 -1769682028,661559552,0.0,0.0,0.0,1.0,0.0028754095546901226,0.0036435346119105816,-0.002677565673366189,-0.2583363652229309,-0.16246414184570312,-0.00124498107470572 -1769682028,674843904,0.0,0.0,0.0,1.0,0.0025771940127015114,0.003642346942797303,-0.0026642000302672386,-3.381857095519081e-05,-2.2637163965555374e-07,0.003576121060177684 -1769682028,710533376,0.0,0.0,0.0,1.0,0.0026347681414335966,0.0036114153917878866,-0.002641022438183427,0.5978578925132751,0.1958557814359665,0.0045239911414682865 -1769682028,761024768,0.0,0.0,0.0,1.0,0.002344178268685937,0.003403309965506196,-0.0026195039972662926,0.1625133603811264,-0.2582932114601135,0.002799683017656207 -1769682028,769295104,0.0,0.0,0.0,1.0,0.0026736094150692225,0.00315260561183095,-0.0025916765443980694,0.42075276374816895,-0.09573731571435928,0.01008899137377739 -1769682028,812236032,0.0,0.0,0.0,1.0,0.002435983158648014,0.0031091717537492514,-0.002566616516560316,0.5165348052978516,0.32514622807502747,0.002644972875714302 -1769682028,846302720,0.0,0.0,0.0,1.0,0.0025112233124673367,0.003001660108566284,-0.0025514562148600817,0.8560616374015808,0.3586747646331787,0.0036880625411868095 -1769682028,883245312,0.0,0.0,0.0,1.0,0.0026263254694640636,0.0029834031593054533,-0.0025427204091101885,-0.08151035010814667,0.12912802398204803,0.019385764375329018 -1769682028,911951360,0.0,0.0,0.0,1.0,0.002547742333263159,0.002835798542946577,-0.002537349471822381,0.16271521151065826,-0.25823017954826355,-0.006553865969181061 -1769682028,945649152,0.0,0.0,0.0,1.0,0.0020425072871148586,0.002710652071982622,-0.002510388381779194,0.679233729839325,0.0671120136976242,-0.010915498249232769 -1769682028,979298048,0.0,0.0,0.0,1.0,0.0023948540911078453,0.002810936886817217,-0.0024881071876734495,0.5976317524909973,0.19627729058265686,0.013239312916994095 -1769682029,13224704,0.0,0.0,0.0,1.0,0.0025468093808740377,0.002714455360546708,-0.0024586464278399944,0.8559280633926392,0.3590196669101715,0.0027489159256219864 -1769682029,56903424,0.0,0.0,0.0,1.0,0.002350759692490101,0.002894311212003231,-0.0024482838343828917,0.16293400526046753,-0.25818535685539246,-0.018327699974179268 -1769682029,77354240,0.0,0.0,0.0,1.0,0.002226946409791708,0.002821381203830242,-0.0024317277129739523,0.1627507209777832,-0.25815773010253906,0.0007756651611998677 -1769682029,111149056,0.0,0.0,0.0,1.0,0.002344390144571662,0.003059073118492961,-0.0023878118954598904,0.6789683103561401,0.06739674508571625,0.012017679400742054 -1769682029,158210304,0.0,0.0,0.0,1.0,0.0019790565129369497,0.0029621149878948927,-0.0023668401408940554,0.5974791646003723,0.19653554260730743,0.019416091963648796 -1769682029,167836672,0.0,0.0,0.0,1.0,0.0023430429864674807,0.002877251710742712,-0.002332872012630105,0.5975210666656494,0.19655922055244446,0.014673631638288498 -1769682029,210779904,0.0,0.0,0.0,1.0,0.002317659556865692,0.0027939025312662125,-0.002274799859151244,0.7603306770324707,-0.06149204447865486,0.015637429431080818 -1769682029,247722240,0.0,0.0,0.0,1.0,0.0021778352092951536,0.0028087443206459284,-0.002224049298092723,-0.1765541434288025,-0.2919122278690338,-0.011141980066895485 -1769682029,283359744,0.0,0.0,0.0,1.0,0.0021708118729293346,0.0027858978137373924,-0.0021830901969224215,0.3395233154296875,0.033824242651462555,0.0013927756808698177 -1769682029,311098624,0.0,0.0,0.0,1.0,0.0021004150621593,0.0027468129992485046,-0.0021376507356762886,-0.2581506669521332,-0.16287541389465332,0.005642644129693508 -1769682029,348210944,0.0,0.0,0.0,1.0,0.002101142657920718,0.0026878314092755318,-0.0020761305931955576,0.08128320425748825,-0.12900710105895996,0.015425466932356358 -1769682029,377788416,0.0,0.0,0.0,1.0,0.0022401446476578712,0.0025904865469783545,-0.0020155846141278744,0.5161876082420349,0.3258330821990967,-0.005275443196296692 -1769682029,411589632,0.0,0.0,0.0,1.0,0.00219173775985837,0.0025507002137601376,-0.0019576719496399164,0.5975341200828552,0.1968584954738617,0.004238024353981018 -1769682029,449197312,0.0,0.0,0.0,1.0,0.001824679085984826,0.0024699545465409756,-0.0018982645124197006,0.16311165690422058,-0.2580472230911255,-0.01196865364909172 -1769682029,477979648,0.0,0.0,0.0,1.0,0.0017975919181481004,0.002567259594798088,-0.0018331152386963367,0.8556198477745056,0.35989630222320557,-0.0024580340832471848 -1769682029,512004096,0.0,0.0,0.0,1.0,0.0018171236151829362,0.0023380948696285486,-0.0017827858682721853,0.5976377129554749,0.1969495266675949,-0.007572201080620289 -1769682029,561514752,0.0,0.0,0.0,1.0,0.0020619945134967566,0.006576817948371172,-0.0015633365837857127,0.8554909825325012,0.36001190543174744,0.004885315895080566 -1769682029,588624640,0.0,0.0,0.0,1.0,0.0018259972566738725,0.009962248615920544,-0.0013919544871896505,-0.09435582906007767,-0.4210999608039856,-0.05043204501271248 -1769682029,600660224,0.0,0.0,0.0,1.0,0.0023661653976887465,0.011270301416516304,-0.0012744419509544969,2.989718268509023e-05,-4.644700311473571e-06,-0.002383995335549116 -1769682029,650961152,0.0,0.0,0.0,1.0,0.002026936272159219,0.01140604354441166,-0.0010105855762958527,0.420833557844162,-0.09491249173879623,0.01644972525537014 -1769682029,678506496,0.0,0.0,0.0,1.0,0.0016711630159989,0.009354624897241592,-0.0009411810315214097,0.7599417567253113,-0.06078238785266876,0.04729915037751198 -1769682029,713577728,0.0,0.0,0.0,1.0,0.0017290336545556784,0.006063555367290974,-0.0007751936209388077,0.2571669816970825,0.16317768394947052,0.06038690730929375 -1769682029,750017280,0.0,0.0,0.0,1.0,0.0011621149023994803,0.002217184752225876,-0.0005718221073038876,0.5022513270378113,-0.2238416075706482,0.02529590204358101 -1769682029,779745024,0.0,0.0,0.0,1.0,0.0011121006682515144,0.0018973505357280374,-0.00038828703691251576,0.5969191193580627,0.19722580909729004,0.04239461198449135 -1769682029,810792448,0.0,0.0,0.0,1.0,0.0010718185221776366,-0.00011294515570625663,-0.0002937907993327826,0.6782066226005554,0.06829258799552917,0.06050979346036911 -1769682029,861618176,0.0,0.0,0.0,1.0,0.00030215512379072607,0.0005465361755341291,-0.00015161058399826288,0.33942511677742004,0.03409650921821594,0.007013453170657158 -1769682029,871611136,0.0,0.0,0.0,1.0,0.00020607640908565372,0.0004017199680674821,-9.15414493647404e-05,0.42081546783447266,-0.0948580726981163,0.017977330833673477 -1769682029,911834112,0.0,0.0,0.0,1.0,8.125551539706066e-05,-0.0010219610994681716,-3.352707062731497e-05,0.17636162042617798,0.2920559048652649,0.005352981388568878 -1769682029,954703872,0.0,0.0,0.0,1.0,6.64159597363323e-05,-0.00018001103308051825,5.55094302399084e-05,0.5031962990760803,-0.2239762544631958,-0.04260484129190445 -1769682029,979652864,0.0,0.0,0.0,1.0,-2.6590037123241927e-06,0.00031921613845042884,0.000115031267341692,0.4207513928413391,-0.09484697878360748,0.022727081552147865 -1769682030,11193088,0.0,0.0,0.0,1.0,-0.00017305805522482842,0.00014482012193184346,0.00013695363304577768,0.33954086899757385,0.03407636657357216,-0.0013413340784609318 -1769682030,50846208,0.0,0.0,0.0,1.0,1.0784365258587059e-05,-0.0017454870976507664,0.00014128483599051833,0.6921440362930298,0.6182015538215637,0.018865425139665604 -1769682030,77498368,0.0,0.0,0.0,1.0,0.00016447810048703104,-0.0027438115794211626,0.0001491958973929286,0.0815214291214943,-0.12897902727127075,0.0014115269295871258 -1769682030,113682432,0.0,0.0,0.0,1.0,0.00012547991354949772,-0.002851474331691861,0.00014662924513686448,0.5974165201187134,0.19714723527431488,0.006505382712930441 -1769682030,155673600,0.0,0.0,0.0,1.0,-0.00024176471924874932,-0.002044274006038904,0.00016371106903534383,-0.1763559877872467,-0.29205238819122314,-0.00649432884529233 -1769682030,177664256,0.0,0.0,0.0,1.0,-8.40743159642443e-05,-0.0012411115458235145,0.0001810417597880587,0.2447672039270401,-0.386974036693573,-0.01132049411535263 -1769682030,210632448,0.0,0.0,0.0,1.0,-3.601967546273954e-05,-0.0005167574854567647,0.0001968193391803652,0.3397030532360077,0.034038592129945755,-0.013383833691477776 -1769682030,257307136,0.0,0.0,0.0,1.0,-4.441969849722227e-06,0.003312939079478383,0.0003081048489548266,0.2579439878463745,0.16305680572986603,0.0031242016702890396 -1769682030,265699328,0.0,0.0,0.0,1.0,0.00032731436658650637,0.003943128511309624,0.0003497162542771548,0.2583026885986328,0.16299587488174438,-0.02308060973882675 -1769682030,312763136,0.0,0.0,0.0,1.0,0.00015109271043911576,0.003111510304734111,0.00036663160426542163,0.5973918437957764,0.19712300598621368,0.008967540226876736 -1769682030,347392256,0.0,0.0,0.0,1.0,-0.00010172859765589237,0.000862687302287668,0.00035359468893148005,0.855029821395874,0.3602139949798584,0.03484754264354706 -1769682030,380841984,0.0,0.0,0.0,1.0,-1.8449236449669115e-05,-0.0002205822238465771,0.0003563151112757623,-0.0003628005215432495,6.008385025779717e-05,0.026223501190543175 -1769682030,411250944,0.0,0.0,0.0,1.0,0.0001467241527279839,-0.0005673383711837232,0.00036357968929223716,0.5974146127700806,0.19709880650043488,0.007803100626915693 -1769682030,450874368,0.0,0.0,0.0,1.0,-0.00023089657770469785,-0.0011151904473081231,0.0003640132490545511,0.2578074634075165,0.1630631536245346,0.013908260501921177 -1769682030,478796288,0.0,0.0,0.0,1.0,0.0005009474698454142,-0.000950092391576618,0.0003803119179792702,0.5976334810256958,0.1970476359128952,-0.00773357879370451 -1769682030,515211008,0.0,0.0,0.0,1.0,9.88454048638232e-05,-0.0007242556312121451,0.00038964292616583407,0.2580079436302185,0.16302426159381866,-0.0004099926445633173 -1769682030,558183424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,3.6327757835388184,-0.045523352921009064,0.5105931162834167 -1769682030,571731200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682030,611339264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682030,663609856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682030,670123008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682030,712016384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682030,750270464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682030,778947072,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682030,810851328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682030,850557440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682030,878174720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682030,917642240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682030,949836800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682030,977879808,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,10845184,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,58234112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,78320384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,111869952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,144519168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,185522688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,211424256,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,251529472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,277553920,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.6502453945577145e-05,-2.7473738555272575e-06,-0.0011919771786779165 -1769682031,311709696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,350011648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,378861824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,410696704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,462021632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,471788544,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,500995840,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,547059712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,581390848,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,611162624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,648738304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,678070528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,715066880,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,750628608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,777578240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,811026688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,854071552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,878556672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,913678592,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,946924544,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682031,979210496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,11377152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,49400832,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,82734848,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,108392192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,155360512,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,179929088,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,213450752,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,262922496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,276468992,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,311689984,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,346452224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,377740032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,411197440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,445129984,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,477652480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,502947840,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,546707712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,577845760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,611078400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,648402176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,681295616,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,710871808,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,746621952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,777797632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,811848448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,845209600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,877726464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,912600064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,946242816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682032,978406400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,12372480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,61505024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,70274816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,111634688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,159100416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,166728704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,211319040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,245384960,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,282350592,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,311781376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,347533568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,377772800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,414825216,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,450795776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,479134464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,511519488,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,557248512,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,577633536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,612048384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,645363200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,681189888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,711333888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,747664384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,777905920,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,812289024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,848697088,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,877864448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,911946752,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,964591616,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682033,973344000,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,13382656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,51960832,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,77891328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,112025856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,147638016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,179844864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,211773184,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,252028672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,280393728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,311640064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,346922496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,378348032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,411443712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,445796608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,479119104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,500278528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,559286528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,566961152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,611458560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,650323200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,679268608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,711802368,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,745378304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,771014144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,811464192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,844611328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,878637312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,911930112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,948014080,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682034,977696000,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,11129344,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,49461760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,78797824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,111402240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,144793600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,181099008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,212116992,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,246288128,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,278978560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,313133056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,351391488,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,378870016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,411292928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,450381056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,479203584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,511301120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,561080576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,569321728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,613810688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,647053824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,679617280,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,711772160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,746349824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,778652160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,814568960,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,862341888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,870393600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,911488768,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,958452992,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682035,965532160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,12424192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,46929408,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,80359936,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,113310208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,148203520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,178740480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,214591744,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,260915712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,268467456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,311744768,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,358122496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,368203776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,411479808,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,448038144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,479938560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,512060160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,545702656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,565383680,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,612162816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,665920768,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,667873536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,711476480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,754042112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,778427904,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,811377664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,847370240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,879692032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,914024704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,949178112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682036,978002944,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,14582528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,57843968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,79708160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,112044288,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,163064320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,171528704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,212333568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,245576960,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,279631872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,311670272,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,345665792,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,378479616,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,416046080,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,450149888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,478817024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,511467008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,559165952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,569948928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,613846784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,645503232,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,682215424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,714024192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,755554304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,778846976,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,799450112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,850049536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,878531584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,912243712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,965666304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682037,976624640,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,13554688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,47470336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,67068928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,112064000,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,147207424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,178462208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,211831808,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,247365888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,278778112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,311895296,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,351762176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,379607552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,412187136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,463856128,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,471176192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,512236032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,546020864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,582853632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,613069568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,652952320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,678461952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,714208000,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,760796672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,770784512,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,813428224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,861756672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,869817856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,913715712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,946550784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682038,980776704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682039,12069120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682039,47049216,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682039,78833408,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682039,114717696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682039,149966592,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682039,180276736,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682039,212010240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682039,259262464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682039,268079360,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682039,314959872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682039,346130432,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682039,381626112,0.0,0.0,0.0,1.0,0.00026938109658658504,-0.00809188187122345,-0.0001024187877192162,0.3375019133090973,0.034369416534900665,0.14761614799499512 -1769682039,412721920,0.0,0.0,0.0,1.0,-0.00035969173768535256,-0.016518445685505867,-0.00025394049589522183,0.3379439413547516,0.03430526703596115,0.11886721104383469 -1769682039,447689728,0.0,0.0,0.0,1.0,-0.0005818635108880699,-0.02194395288825035,-0.000404674734454602,-0.17742310464382172,-0.2918454110622406,0.07594113051891327 -1769682039,478940416,0.0,0.0,0.0,1.0,-0.0006081858882680535,-0.023035304620862007,-0.0005132384249009192,-0.5163168907165527,-0.32599982619285583,0.028021538630127907 -1769682039,515946240,0.0,0.0,0.0,1.0,-0.0009474008693359792,-0.0208891611546278,-0.000608638278208673,-0.2444590926170349,0.38694119453430176,-0.010750520043075085 -1769682039,556187904,0.0,0.0,0.0,1.0,-0.0002921606646850705,-0.01575901173055172,-0.0006755596841685474,-0.5018238425254822,0.22375616431236267,-0.07131313532590866 -1769682039,578546176,0.0,0.0,0.0,1.0,-0.0005627862992696464,-0.01145839411765337,-0.0007374855922535062,-0.4204076826572418,0.09478022903203964,-0.06285697966814041 -1769682039,611490048,0.0,0.0,0.0,1.0,-0.0005657674046233296,-0.007538528181612492,-0.0007942421943880618,-0.5153895020484924,-0.3262360394001007,-0.05678831785917282 -1769682039,659447296,0.0,0.0,0.0,1.0,-9.850550122791901e-05,-0.0031791427172720432,-0.000838636769913137,-0.6783886551856995,-0.06831113249063492,-0.06478775292634964 -1769682039,668338176,0.0,0.0,0.0,1.0,0.00013132741150911897,-0.0016921334899961948,-0.0008711065747775137,-0.08115394413471222,0.1288900375366211,-0.040400128811597824 -1769682039,712194560,0.0,0.0,0.0,1.0,0.00018191267736256123,0.0005855263443663716,-0.000911933311726898,-0.502087414264679,0.22373177111148834,-0.052982695400714874 -1769682039,747727872,0.0,0.0,0.0,1.0,9.971555846277624e-05,0.0016063605435192585,-0.0009363461867906153,-0.678679883480072,-0.06830386072397232,-0.033799491822719574 -1769682039,783837440,0.0,0.0,0.0,1.0,0.0003128133830614388,0.0018264034297317266,-0.0009641830110922456,-0.33930903673171997,-0.03416863828897476,-0.019896946847438812 -1769682039,812576256,0.0,0.0,0.0,1.0,7.016367453616112e-05,0.001840367098338902,-0.0009940004674717784,-0.33923739194869995,-0.034194499254226685,-0.027067089453339577 -1769682039,849977088,0.0,0.0,0.0,1.0,0.0002884371788240969,0.0015900031430646777,-0.000998383853584528,-0.855323076248169,-0.3603861927986145,-0.005199396517127752 -1769682039,878766336,0.0,0.0,0.0,1.0,-2.1464140445459634e-05,0.001632452942430973,-0.0010123117826879025,-0.6789568662643433,-0.06832601130008698,-0.0041499980725348 -1769682039,914870528,0.0,0.0,0.0,1.0,0.0002813593891914934,0.0012187075335532427,-0.0010184957645833492,-0.6789554357528687,-0.06834826618432999,-0.004177185706794262 -1769682039,962689280,0.0,0.0,0.0,1.0,0.00021778490918222815,0.00024773101904429495,-0.0010611237958073616,-0.32640373706817627,0.5158461332321167,0.009919306263327599 -1769682039,970454272,0.0,0.0,0.0,1.0,0.0001323339674854651,-0.0003337480593472719,-0.001078074797987938,-0.8551831245422363,-0.3605138659477234,-0.014827065169811249 -1769682040,11732224,0.0,0.0,0.0,1.0,0.0003549540415406227,-0.0008469423046335578,-0.0010911674471572042,-0.5842890739440918,0.3526555001735687,0.0041639842092990875 -1769682040,69177856,0.0,0.0,0.0,1.0,0.00034832401433959603,-0.001418404863215983,-0.0011363574303686619,-0.08170859515666962,0.12897399067878723,0.012019244022667408 -1769682040,71721984,0.0,0.0,0.0,1.0,0.0003232717572245747,-0.0013625110732391477,-0.0011537193786352873,-0.0815359354019165,0.12893173098564148,-0.0058597382158041 -1769682040,112058112,0.0,0.0,0.0,1.0,0.0003759331302717328,-0.001081707770936191,-0.0011800017673522234,-0.8550586104393005,-0.3606662452220917,-0.021831147372722626 -1769682040,146454016,0.0,0.0,0.0,1.0,0.0003905893536284566,-0.0016885095974430442,-0.0012102695181965828,-0.6790058612823486,-0.06851477921009064,0.0031108781695365906 -1769682040,178842368,0.0,0.0,0.0,1.0,0.00048505133599974215,-0.0011416904162615538,-0.00123997638002038,-0.3393404185771942,-0.03430832549929619,-0.015119414776563644 -1769682040,212729344,0.0,0.0,0.0,1.0,0.0006080810562707484,-0.0007123039104044437,-0.0012431970098987222,-0.16303719580173492,0.2578158676624298,-0.020049061626195908 -1769682040,254289408,0.0,0.0,0.0,1.0,0.00031325058080255985,-0.0006703257095068693,-0.001299506169743836,-0.24486836791038513,0.38678163290023804,0.00032285554334521294 -1769682040,280650496,0.0,0.0,0.0,1.0,0.000682951183989644,-0.0005390279111452401,-0.001295479480177164,-0.24476909637451172,0.38674411177635193,-0.01160041056573391 -1769682040,311553024,0.0,0.0,0.0,1.0,0.0005352983134798706,-0.000362930673873052,-0.0013226141454651952,-0.2449101358652115,0.38676518201828003,0.0015102922916412354 -1769682040,366385664,0.0,0.0,0.0,1.0,0.0007594042108394206,-0.000299489387543872,-0.0013445165241137147,-0.5026733875274658,0.223460853099823,-0.00891678687185049 -1769682040,375312384,0.0,0.0,0.0,1.0,0.000754808948840946,-4.833695129491389e-05,-0.0013505641836673021,-1.2761310338974,-0.26639601588249207,-0.013940555974841118 -1769682040,412107520,0.0,0.0,0.0,1.0,0.00042632565600797534,0.0007807661895640194,-0.001350732403807342,-0.5027117729187012,0.22342711687088013,-0.006546205375343561 -1769682040,463079424,0.0,0.0,0.0,1.0,0.0009242973173968494,0.0014235057169571519,-0.0013400816824287176,-0.8420636653900146,0.18897132575511932,-0.020490160211920738 -1769682040,474602496,0.0,0.0,0.0,1.0,0.0006884371978230774,0.001594819943420589,-0.0013504758244380355,-0.760419487953186,0.060037676244974136,-0.019422363489866257 -1769682040,513824000,0.0,0.0,0.0,1.0,0.0009233758901245892,0.0017683780752122402,-0.0013495590537786484,-0.5028218626976013,0.22337990999221802,0.0017053843475878239 -1769682040,547593472,0.0,0.0,0.0,1.0,0.0004314800025895238,0.0015929453074932098,-0.0013484138762578368,-0.9365468621253967,-0.23226279020309448,-0.019308313727378845 -1769682040,578507008,0.0,0.0,0.0,1.0,0.0005760341882705688,0.0022949171252548695,-0.0013371609384194016,-0.5971701741218567,-0.1978207528591156,-0.008950884453952312 -1769682040,601486080,0.0,0.0,0.0,1.0,0.001076420652680099,0.0028309293556958437,-0.0012919943546876311,-0.7604363560676575,0.05991695821285248,-0.018414607271552086 -1769682040,664126976,0.0,0.0,0.0,1.0,0.0010342084569856524,0.005190538242459297,-0.0012265845434740186,-1.2756956815719604,-0.26694709062576294,-0.04795278608798981 -1769682040,671759616,0.0,0.0,0.0,1.0,0.0010028784163296223,0.007140820380300283,-0.0011401382507756352,-0.6781987547874451,-0.06918002665042877,-0.07117870450019836 -1769682040,700733440,0.0,0.0,0.0,1.0,0.0016273317160084844,0.007977897301316261,-0.0010855825385078788,-0.5845004320144653,0.352119505405426,-0.005868951324373484 -1769682040,757932544,0.0,0.0,0.0,1.0,0.001288138679228723,0.008662889711558819,-0.0009957668371498585,-1.0184217691421509,-0.1035521924495697,0.002303890883922577 -1769682040,769073408,0.0,0.0,0.0,1.0,0.0011063090059906244,0.00749201187863946,-0.0009894256945699453,-1.1128143072128296,-0.5247052907943726,0.007045680657029152 -1769682040,815112960,0.0,0.0,0.0,1.0,0.0010565012926235795,0.005886301398277283,-0.0009121369803324342,-0.8423380851745605,0.1886594593524933,-0.0017127329483628273 -1769682040,869888000,0.0,0.0,0.0,1.0,0.0012060124427080154,0.003923699259757996,-0.0008584587485529482,-0.9365319609642029,-0.23255470395088196,-0.012474246323108673 -1769682040,873987328,0.0,0.0,0.0,1.0,0.0012694321339949965,0.0037122436333447695,-0.0008234422421082854,-0.32694563269615173,0.5154818296432495,0.005452635232359171 -1769682040,912297472,0.0,0.0,0.0,1.0,0.0010591032914817333,0.0036800154484808445,-0.0007263976149260998,-0.8421714305877686,0.18854406476020813,-0.01757156290113926 -1769682040,949785600,0.0,0.0,0.0,1.0,0.001053106738254428,0.00422301609069109,-0.0006266169366426766,-1.100132703781128,0.025141075253486633,0.0011714864522218704 -1769682040,978572032,0.0,0.0,0.0,1.0,-0.00011821977386716753,0.0055561307817697525,-0.00046209667925722897,-0.9359028935432434,-0.23279234766960144,-0.06299804151058197 -1769682041,14001664,0.0,0.0,0.0,1.0,-0.0017592593794688582,0.007861296646296978,-0.0002847244613803923,-0.5019409656524658,0.2228948324918747,-0.08072234690189362 -1769682041,53171456,0.0,0.0,0.0,1.0,-0.002079625613987446,0.010242070071399212,-9.373789362143725e-05,-0.7596244812011719,0.05944867432117462,-0.08247292041778564 -1769682041,78659072,0.0,0.0,0.0,1.0,-0.0022834015544503927,0.011881958693265915,5.232020703260787e-05,-0.42063233256340027,0.09414955973625183,-0.04386637732386589 -1769682041,112680704,0.0,0.0,0.0,1.0,-0.002093879273161292,0.013447415083646774,0.00019299615814816207,-1.0176090002059937,-0.10391603410243988,-0.0597851537168026 -1769682041,150612480,0.0,0.0,0.0,1.0,-0.00234384648501873,0.013499977067112923,0.0003238021454308182,-0.33958983421325684,-0.03455611318349838,0.008489077910780907 -1769682041,171299584,0.0,0.0,0.0,1.0,-0.002272090408951044,0.012669498100876808,0.0003883840108755976,-0.08208145946264267,0.1289268136024475,0.024726679548621178 -1769682041,200558336,0.0,0.0,0.0,1.0,-0.002236292464658618,0.011723940260708332,0.00047759065637364984,-1.1004433631896973,0.025199629366397858,0.019730418920516968 -1769682041,266690048,0.0,0.0,0.0,1.0,-0.0028775206301361322,0.009722525253891945,0.0002765190147329122,-1.0188387632369995,-0.10362236201763153,0.02664749138057232 -1769682041,279589120,0.0,0.0,0.0,1.0,-0.0044122240506112576,0.005133772734552622,8.065062866080552e-05,-0.3429676294326782,-0.03403691202402115,0.22852300107479095 -1769682041,312080384,0.0,0.0,0.0,1.0,-0.004127432592213154,0.0009926698403432965,0.00023578126274514943,-1.1971454620361328,-0.39559033513069153,0.17446330189704895 -1769682041,354259456,0.0,0.0,0.0,1.0,-0.003654219675809145,-0.00238171243108809,0.0004298637213651091,-0.8568647503852844,-0.36115023493766785,0.12236663699150085 -1769682041,378787072,0.0,0.0,0.0,1.0,-0.0038007975090295076,-0.003295416245236993,0.0005312150460667908,-0.8434193134307861,0.18876251578330994,0.06671621650457382 -1769682041,414512640,0.0,0.0,0.0,1.0,-0.0037552257999777794,-0.003315775189548731,0.0006503126351162791,-1.0188812017440796,-0.10357965528964996,0.028933430090546608 -1769682041,451037440,0.0,0.0,0.0,1.0,-0.003400266170501709,-0.0023738311138004065,0.0007585170096717775,-0.8423613905906677,0.1886705607175827,-0.002194228582084179 -1769682041,478709760,0.0,0.0,0.0,1.0,-0.0034047355875372887,-0.0018830070039257407,0.0008276950102299452,-0.7603676319122314,0.05979364737868309,-0.02096867375075817 -1769682041,512204288,0.0,0.0,0.0,1.0,-0.003698502667248249,-0.0010559215443208814,0.0008878515800461173,-0.7600800395011902,0.05978316068649292,-0.04000402241945267 -1769682041,552282368,0.0,0.0,0.0,1.0,-0.0037776301614940166,0.0003323942655697465,0.0009673641761764884,-1.1811885833740234,0.15418481826782227,-0.04517846554517746 -1769682041,579981824,0.0,0.0,0.0,1.0,-0.0036319680511951447,0.0011199235450476408,0.0010285094613209367,-1.099433183670044,0.025340262800455093,-0.04859244078397751 -1769682041,612225792,0.0,0.0,0.0,1.0,-0.0038047032430768013,0.0018420073902234435,0.0010701949940994382,-1.0992522239685059,0.02536754310131073,-0.060562267899513245 -1769682041,657598720,0.0,0.0,0.0,1.0,-0.0037922263145446777,0.0023367032408714294,0.0011305951047688723,-0.40795114636421204,0.6444094181060791,-0.03296497091650963 -1769682041,682868224,0.0,0.0,0.0,1.0,-0.00397592643275857,0.002787070581689477,0.001169068505987525,-0.7601320147514343,0.05994774401187897,-0.03537491336464882 -1769682041,698441216,0.0,0.0,0.0,1.0,-0.0031888787634670734,0.003058764385059476,0.0011920906836166978,-1.0182439088821411,-0.10335659980773926,-0.015360753983259201 -1769682041,749657600,0.0,0.0,0.0,1.0,-0.0014334018342196941,0.004002212546765804,0.002052552532404661,-1.1823537349700928,0.1545577198266983,0.03422647342085838 -1769682041,779604480,0.0,0.0,0.0,1.0,-0.00043517202720977366,0.004940292797982693,0.0025176883209496737,-1.4399040937423706,-0.008670799434185028,0.015868816524744034 -1769682041,814586112,0.0,0.0,0.0,1.0,-0.0002991810324601829,0.005717388819903135,0.002823739079758525,-0.5030525922775269,0.22346337139606476,0.015840191394090652 -1769682041,859165952,0.0,0.0,0.0,1.0,8.781484211795032e-05,0.006367875728756189,0.0031041037291288376,-0.7606493234634399,0.06026593595743179,-0.00020028091967105865 -1769682041,870967296,0.0,0.0,0.0,1.0,-0.00010846026270883158,0.006632473319768906,0.00315488432534039,-0.4214310646057129,0.09463133662939072,0.01822792924940586 -1769682041,912493824,0.0,0.0,0.0,1.0,0.00048486102605238557,0.008098815567791462,0.0032917996868491173,-0.6663256883621216,0.481498658657074,0.022204970940947533 -1769682041,959129088,0.0,0.0,0.0,1.0,0.00045398963266052306,0.009245418012142181,0.003359869820997119,-0.8424186110496521,0.18946906924247742,0.010870948433876038 -1769682041,970955520,0.0,0.0,0.0,1.0,0.0007107359706424177,0.009624644182622433,0.0033757355995476246,-0.7611074447631836,0.06058431416749954,0.027663197368383408 -1769682042,14436864,0.0,0.0,0.0,1.0,0.0006521929753944278,0.009949381463229656,0.0033955934923142195,-0.9236832857131958,0.3185936510562897,-0.005433843471109867 -1769682042,95924736,0.0,0.0,0.0,1.0,0.0007878769538365304,0.010154248215258121,0.0033704896923154593,-0.8418806791305542,0.18973445892333984,-0.01739322766661644 -1769682042,98007552,0.0,0.0,0.0,1.0,0.0008536081295460463,0.010170763358473778,0.0033367243595421314,-1.3578135967254639,-0.13628560304641724,-0.020713940262794495 -1769682042,117401088,0.0,0.0,0.0,1.0,0.0006924096378497779,0.010037146508693695,0.003296742681413889,-0.9236575365066528,0.3189060688018799,-0.0016257800161838531 -1769682042,146598400,0.0,0.0,0.0,1.0,0.0008136892574839294,0.010268384590744972,0.0032462456729263067,-1.0047849416732788,0.4480139911174774,-0.02032734453678131 -1769682042,166163968,0.0,0.0,0.0,1.0,0.00046490764361806214,0.010169855318963528,0.0031848617363721132,-1.1813607215881348,0.1560981571674347,-0.01766655221581459 -1769682042,212120064,0.0,0.0,0.0,1.0,0.0006600644555874169,0.009888718836009502,0.0030771626625210047,-1.0189273357391357,-0.10176518559455872,0.01144273579120636 -1769682042,261508352,0.0,0.0,0.0,1.0,0.00043491640826687217,0.010288109071552753,0.0029446417465806007,-0.9368471503257751,-0.2306978404521942,-0.020623700693249702 -1769682042,270506752,0.0,0.0,0.0,1.0,0.00013742255396209657,0.010517796501517296,0.0028834345284849405,-0.6790802478790283,-0.06773227453231812,-0.0039104800671339035 -1769682042,315729152,0.0,0.0,0.0,1.0,0.00032129170722328126,0.010906916111707687,0.00276302732527256,-1.0183383226394653,-0.10149656236171722,-0.02060743421316147 -1769682042,348126208,0.0,0.0,0.0,1.0,-0.0021359645761549473,0.009320417419075966,0.0015906585613265634,-0.5852933526039124,0.35340210795402527,0.06626324355602264 -1769682042,379514112,0.0,0.0,0.0,1.0,-0.003234421368688345,0.008350210264325142,0.001113763777539134,-0.9386032223701477,-0.23037192225456238,0.06046391651034355 -1769682042,412504576,0.0,0.0,0.0,1.0,-0.00441170996055007,0.0073705376125872135,0.00037157273618504405,-1.1961175203323364,-0.39321187138557434,0.0285536777228117 -1769682042,450495232,0.0,0.0,0.0,1.0,-0.005465069320052862,0.007224510423839092,-0.00016361192683689296,-0.9377588033676147,-0.230394184589386,0.01810980960726738 -1769682042,467196672,0.0,0.0,0.0,1.0,-0.005932466592639685,0.007356821559369564,-0.00036364010884426534,-0.9373631477355957,-0.23040157556533813,6.879493594169617e-05 -1769682042,517232384,0.0,0.0,0.0,1.0,-0.0062245093286037445,0.0076059154234826565,-0.000659121316857636,-0.5979720950126648,-0.19663093984127045,0.009555891156196594 -1769682042,557021952,0.0,0.0,0.0,1.0,-0.006777750328183174,0.007966695353388786,-0.0008707264205440879,-0.5833562612533569,0.35334450006484985,-0.026020780205726624 -1769682042,578538496,0.0,0.0,0.0,1.0,-0.006915976293385029,0.008344719186425209,-0.0009942548349499702,-0.42100027203559875,0.09523409605026245,-0.0022734496742486954 -1769682042,611986176,0.0,0.0,0.0,1.0,-0.007152541074901819,0.008506895042955875,-0.0010951356962323189,-0.7604379057884216,0.06141361594200134,-0.010099625214934349 -1769682042,661170944,0.0,0.0,0.0,1.0,-0.007159385364502668,0.0087777990847826,-0.0011876651551574469,-0.5018450021743774,0.2242649644613266,-0.029270663857460022 -1769682042,673413632,0.0,0.0,0.0,1.0,-0.006804140284657478,0.00896378979086876,-0.0012392037315294147,-0.5019568800926208,0.22424724698066711,-0.02459079772233963 -1769682042,701107968,0.0,0.0,0.0,1.0,-0.0009009167551994324,0.005975453648716211,-0.0015252925222739577,-0.30631953477859497,1.066415786743164,-0.24681130051612854 -1769682042,746386688,0.0,0.0,0.0,1.0,0.012407698668539524,-0.004865741822868586,-0.001769709400832653,-0.7425401210784912,0.6113872528076172,-0.18984736502170563 -1769682042,782361856,0.0,0.0,0.0,1.0,0.01712026633322239,-0.009534835815429688,-0.0019360706210136414,-0.5000063180923462,0.22416779398918152,-0.1105109453201294 -1769682042,812984320,0.0,0.0,0.0,1.0,0.020386207848787308,-0.012390854768455029,-0.002135084243491292,-0.40567806363105774,0.645060122013092,-0.07861734926700592 -1769682042,848213504,0.0,0.0,0.0,1.0,0.024201001971960068,-0.01411316730082035,-0.0024794992059469223,-0.8414735794067383,0.19005568325519562,-0.03212796896696091 -1769682042,879065856,0.0,0.0,0.0,1.0,0.025842195376753807,-0.014287249185144901,-0.002785429125651717,-0.9239702224731445,0.31905078887939453,0.011340170167386532 -1769682042,918121984,0.0,0.0,0.0,1.0,0.02743050828576088,-0.013777795247733593,-0.003101971233263612,-1.100563406944275,0.026974769309163094,0.014445202425122261 -1769682042,966776320,0.0,0.0,0.0,1.0,0.02849261462688446,-0.01311273593455553,-0.003550398861989379,-0.5030561089515686,0.22397381067276,0.01840302348136902 -1769682042,969018624,0.0,0.0,0.0,1.0,0.02883300743997097,-0.012527101673185825,-0.0037764583248645067,-0.679253101348877,-0.06815614551305771,0.006522379815578461 -1769682043,11999488,0.0,0.0,0.0,1.0,0.029072705656290054,-0.01202415581792593,-0.004184754099696875,-0.4218449592590332,0.09501461684703827,0.03506132960319519 -1769682043,68529152,0.0,0.0,0.0,1.0,0.032873183488845825,-0.013789480552077293,-0.004523620940744877,-0.16587218642234802,0.2588290274143219,0.13446055352687836 -1769682043,70641152,0.0,0.0,0.0,1.0,0.03374062478542328,-0.014799782074987888,-0.004641740117222071,-0.5994186401367188,-0.196660116314888,0.1019386500120163 -1769682043,112501504,0.0,0.0,0.0,1.0,0.034379031509160995,-0.01674557849764824,-0.004898052662611008,-0.7621399760246277,0.06099871173501015,0.0769726037979126 -1769682043,148651776,0.0,0.0,0.0,1.0,0.034426163882017136,-0.020090533420443535,-0.004998228047043085,-0.34165874123573303,-0.03315107896924019,0.11938727647066116 -1769682043,195656192,0.0,0.0,0.0,1.0,0.03466359153389931,-0.021999439224600792,-0.00504649942740798,-0.08320341259241104,0.1298840045928955,0.08651059120893478 -1769682043,216336896,0.0,0.0,0.0,1.0,0.034300945699214935,-0.02315700426697731,-0.005144429858773947,-1.1010937690734863,0.02609393559396267,0.05403999611735344 -1769682043,249314560,0.0,0.0,0.0,1.0,0.03441901132464409,-0.023972153663635254,-0.0052864630706608295,-0.5032747983932495,0.22344745695590973,0.018820246681571007 -1769682043,278817280,0.0,0.0,0.0,1.0,0.034298498183488846,-0.02397025376558304,-0.005410392303019762,-0.5970343351364136,-0.19823546707630157,-0.00842639897018671 -1769682043,313944064,0.0,0.0,0.0,1.0,0.032286178320646286,-0.02374717779457569,-0.006314204540103674,-0.6778183579444885,-0.07057933509349823,-0.0765494629740715 -1769682043,362656000,0.0,0.0,0.0,1.0,0.011599941179156303,-0.034241706132888794,-0.009583726525306702,-0.34798526763916016,-0.5893890857696533,-0.27148929238319397 -1769682043,372835840,0.0,0.0,0.0,1.0,0.003084193216636777,-0.03937715291976929,-0.011774932965636253,0.16487017273902893,-0.2591342031955719,-0.09267989546060562 -1769682043,402473472,0.0,0.0,0.0,1.0,-0.00033129664370790124,-0.03138050064444542,-0.01331030111759901,-0.8567053079605103,-0.3591372072696686,0.21480681002140045 -1769682043,445948416,0.0,0.0,0.0,1.0,-0.0025100745260715485,-0.02056029997766018,-0.014577101916074753,-0.9381565451622009,-0.2311473786830902,0.2019454538822174 -1769682043,483740672,0.0,0.0,0.0,1.0,-0.004398165736347437,-0.014487141743302345,-0.01516970805823803,-0.9375008344650269,-0.23237690329551697,0.1547059565782547 -1769682043,500572416,0.0,0.0,0.0,1.0,-0.00447291461750865,-0.01156783476471901,-0.015417689457535744,-0.16556403040885925,0.2597256302833557,0.14802654087543488 -1769682043,552570368,0.0,0.0,0.0,1.0,-0.0051895370706915855,-0.006983380299061537,-0.015699148178100586,-0.9362066388130188,-0.23516015708446503,0.049177780747413635 -1769682043,565238784,0.0,0.0,0.0,1.0,-0.005796246696263552,-0.005501755513250828,-0.01569990999996662,-0.6786863803863525,-0.07167685776948929,0.007155942730605602 -1769682043,612154112,0.0,0.0,0.0,1.0,-0.0053075277246534824,-0.0034282421693205833,-0.015587467700242996,-0.3390445411205292,-0.03655815124511719,-0.028558077290654182 -1769682043,658463488,0.0,0.0,0.0,1.0,-0.004842557944357395,-0.004851440899074078,-0.015429454855620861,-0.25688210129737854,-0.16475093364715576,0.0015854928642511368 -1769682043,675653632,0.0,0.0,0.0,1.0,-0.00413181446492672,-0.008050528354942799,-0.015101291239261627,-0.6784715056419373,-0.07300151884555817,-0.0032645324245095253 -1769682043,712623872,0.0,0.0,0.0,1.0,0.008375382982194424,-0.004356165416538715,-0.012511327862739563,-0.9032288789749146,1.4038101434707642,-0.5440205931663513 -1769682043,748436736,0.0,0.0,0.0,1.0,0.022571509703993797,0.004527695011347532,-0.008568769320845604,-0.4090571701526642,0.6342720985412598,-0.46306219696998596 -1769682043,769977600,0.0,0.0,0.0,1.0,0.027186043560504913,0.008230683393776417,-0.007048598490655422,-0.24437075853347778,0.37819838523864746,-0.4089401960372925 -1769682043,812493824,0.0,0.0,0.0,1.0,0.03464248403906822,0.013280688785016537,-0.00476027000695467,-0.667415976524353,0.47182631492614746,-0.25633442401885986 -1769682043,850071552,0.0,0.0,0.0,1.0,0.03973208740353584,0.01588299311697483,-0.0032376155722886324,-0.24683836102485657,0.38274601101875305,-0.11349183320999146 -1769682043,879690496,0.0,0.0,0.0,1.0,0.04232413321733475,0.016265233978629112,-0.0024624248035252094,-0.33032411336898804,0.512730598449707,-0.02578648179769516 -1769682043,913712896,0.0,0.0,0.0,1.0,0.04389994591474533,0.01588083617389202,-0.0019488749094307423,-0.0743773803114891,0.6791952848434448,0.029592974111437798 -1769682043,949588224,0.0,0.0,0.0,1.0,0.04498798027634621,0.014558946713805199,-0.001536308554932475,-1.018450379371643,-0.10908801853656769,0.07855410873889923 -1769682043,966529280,0.0,0.0,0.0,1.0,0.04576031491160393,0.013534543104469776,-0.001460220548324287,-0.5880541205406189,0.3498213291168213,0.07541533559560776 -1769682044,13090304,0.0,0.0,0.0,1.0,0.04617849364876747,0.011481409892439842,-0.0015057820128276944,-0.6793386936187744,-0.0718717873096466,0.08104485273361206 -1769682044,50744320,0.0,0.0,0.0,1.0,0.04558455944061279,0.009930710308253765,-0.0017849182477220893,-0.9355717897415161,-0.23782137036323547,0.056271303445100784 -1769682044,68443136,0.0,0.0,0.0,1.0,0.04548210650682449,0.009344291873276234,-0.0019803389441221952,-0.5964316725730896,-0.2006363421678543,0.06057710573077202 -1769682044,102892288,0.0,0.0,0.0,1.0,0.04480283707380295,0.008802901022136211,-0.0024548883084207773,-0.42225518822669983,0.09210638701915741,0.027581673115491867 -1769682044,145985280,0.0,0.0,0.0,1.0,0.044114112854003906,0.00839245319366455,-0.002997476141899824,-0.9349967837333679,-0.23929527401924133,0.011237205937504768 -1769682044,180992768,0.0,0.0,0.0,1.0,0.04370160028338432,0.008352411910891533,-0.003394391853362322,-0.8523440361022949,-0.36732861399650574,0.02155476063489914 -1769682044,213332480,0.0,0.0,0.0,1.0,0.043068673461675644,0.008534306660294533,-0.003764789318665862,-0.3392980694770813,-0.0368705615401268,0.00865820050239563 -1769682044,248295680,0.0,0.0,0.0,1.0,0.01896626502275467,0.022700056433677673,-0.004452027380466461,-0.5870365500450134,-0.22475063800811768,-0.6013877987861633 -1769682044,295713280,0.0,0.0,0.0,1.0,0.004598565399646759,0.026578370481729507,-0.005566941574215889,-0.5304561257362366,-1.4275448322296143,0.12341952323913574 -1769682044,316119808,0.0,0.0,0.0,1.0,0.003968176897615194,0.017214076593518257,-0.005997879896312952,-0.18006663024425507,-0.27834904193878174,0.42028599977493286 -1769682044,371316992,0.0,0.0,0.0,1.0,0.00041475327452644706,0.006980790290981531,-0.006357864011079073,-0.08880741894245148,0.14199434220790863,0.3703218102455139 -1769682044,381223424,0.0,0.0,0.0,1.0,-0.0019970741122961044,0.001248016720637679,-0.006584553513675928,-0.5177707076072693,-0.3194326162338257,0.32440295815467834 -1769682044,400929536,0.0,0.0,0.0,1.0,-0.0026489384472370148,-0.0016326520126312971,-0.006729624234139919,-0.5167035460472107,-0.3218514621257782,0.2612679600715637 -1769682044,466486272,0.0,0.0,0.0,1.0,-0.0037473649717867374,-0.005852805450558662,-0.0070754108019173145,-0.16821527481079102,0.2617645561695099,0.14517714083194733 -1769682044,476774912,0.0,0.0,0.0,1.0,-0.0046583907678723335,-0.006531291641294956,-0.007340980228036642,-0.24929232895374298,0.3854048550128937,0.022517690435051918 -1769682044,513973760,0.0,0.0,0.0,1.0,-0.005608824547380209,-0.0058998363092541695,-0.00760216498747468,-0.5964095592498779,-0.20098981261253357,0.07560111582279205 -1769682044,547636992,0.0,0.0,0.0,1.0,-0.004850372672080994,-0.0030587748624384403,-0.0077573820017278194,-0.16543389856815338,0.25473958253860474,-0.04280655086040497 -1769682044,579086080,0.0,0.0,0.0,1.0,-0.004098329693078995,-0.0009952634572982788,-0.007840175181627274,-0.42118436098098755,0.08782055974006653,-0.06452172994613647 -1769682044,602490368,0.0,0.0,0.0,1.0,-0.0036981089506298304,0.0003155340673401952,-0.007860766723752022,-0.5944952964782715,-0.2055615782737732,-0.03870445489883423 -1769682044,652424704,0.0,0.0,0.0,1.0,-0.0026262153405696154,0.0025766727048903704,-0.007897640578448772,-0.6769692897796631,-0.07907651364803314,-0.07682421803474426 -1769682044,681627904,0.0,0.0,0.0,1.0,-0.0021665345411747694,0.0033852877095341682,-0.007973574101924896,-0.6773696541786194,-0.07825078815221786,-0.049496181309223175 -1769682044,712697856,0.0,0.0,0.0,1.0,-0.0015665395185351372,0.00408877432346344,-0.0080306027084589,-0.7672781348228455,-0.4997193515300751,-0.018021566793322563 -1769682044,758744064,0.0,0.0,0.0,1.0,-0.0010049301199615002,0.004061270970851183,-0.008166056126356125,-0.7610159516334534,0.05040838569402695,-0.021032294258475304 -1769682044,771433472,0.0,0.0,0.0,1.0,-0.0011107644531875849,0.0041134716011583805,-0.008230708539485931,-0.08321473002433777,0.12787412106990814,-0.0035070618614554405 -1769682044,812482304,0.0,0.0,0.0,1.0,0.00043029856169596314,0.004471151623874903,-0.008240636438131332,-0.3321990966796875,0.5095584392547607,-0.06530175358057022 -1769682044,846908160,0.0,0.0,0.0,1.0,0.0010405578650534153,0.004767398815602064,-0.00825920607894659,-0.5942381620407104,-0.20632591843605042,-0.027387138456106186 -1769682044,867213824,0.0,0.0,0.0,1.0,0.0014336199965327978,0.0046767923049628735,-0.008292063139379025,-0.5054466128349304,0.21640659868717194,-0.019619803875684738 -1769682044,912427008,0.0,0.0,0.0,1.0,0.0020081358961760998,0.0046705398708581924,-0.008351154625415802,-0.08367764204740524,0.12845967710018158,0.015482046641409397 -1769682044,952273152,0.0,0.0,0.0,1.0,0.0024931838270276785,0.004295472055673599,-0.008436297997832298,-0.42230135202407837,0.08857300877571106,-0.00908932276070118 -1769682044,981229568,0.0,0.0,0.0,1.0,0.0024927554186433554,0.004314782097935677,-0.00851772353053093,-0.16684992611408234,0.25541162490844727,-0.008437370881438255 -1769682045,12488448,0.0,0.0,0.0,1.0,0.0026513587217777967,0.004100817255675793,-0.00860843900591135,-0.3394263684749603,-0.03819088637828827,0.02659541927278042 -1769682045,51590144,0.0,0.0,0.0,1.0,0.0025138866622000933,0.004100722726434469,-0.008670155890285969,-0.42282581329345703,0.08915495127439499,0.016918303444981575 -1769682045,80544768,0.0,0.0,0.0,1.0,-0.003914522472769022,0.008075904101133347,-0.00870407372713089,-0.3456501364707947,-0.5853482484817505,0.12483371794223785 -1769682045,112524800,0.0,0.0,0.0,1.0,-0.006802773103117943,0.011119646020233631,-0.008818513713777065,-0.17336051166057587,-0.29153361916542053,0.09566420316696167 -1769682045,165629952,0.0,0.0,0.0,1.0,-0.008948172442615032,0.013419950380921364,-0.00887211225926876,-0.5948227047920227,-0.20554929971694946,0.03468829765915871 -1769682045,176739072,0.0,0.0,0.0,1.0,-0.010985098779201508,0.015044140629470348,-0.008907150477170944,-0.9330185055732727,-0.24667522311210632,-0.0016669351607561111 -1769682045,213086208,0.0,0.0,0.0,1.0,-0.011689763516187668,0.015290874056518078,-0.008904422633349895,-0.3390009105205536,-0.039565619081258774,0.004402040969580412 -1769682045,262163712,0.0,0.0,0.0,1.0,-0.01316765695810318,0.015309715643525124,-0.008945389650762081,-0.16731347143650055,0.2548234164714813,-0.014467254281044006 -1769682045,285475072,0.0,0.0,0.0,1.0,-0.01569599285721779,0.014905297197401524,-0.00906321220099926,-0.3393196165561676,-0.039216913282871246,0.020676741376519203 -1769682045,301684736,0.0,0.0,0.0,1.0,-0.01559152640402317,0.01363416388630867,-0.009137739427387714,-0.8465458750724792,0.17698848247528076,0.05056603252887726 -1769682045,346559744,0.0,0.0,0.0,1.0,-0.016533134505152702,0.010945114307105541,-0.009327803738415241,-0.17218941450119019,-0.29352667927742004,0.05368547886610031 -1769682045,379405824,0.0,0.0,0.0,1.0,-0.01672499068081379,0.01012877095490694,-0.009469619952142239,-0.5938673615455627,-0.20787768065929413,0.0034560877829790115 -1769682045,418441984,0.0,0.0,0.0,1.0,-0.016551963984966278,0.00945114903151989,-0.009592779912054539,-0.5937047004699707,-0.20820096135139465,-0.0015817619860172272 -1769682045,458506752,0.0,0.0,0.0,1.0,-0.015970664098858833,0.009235158562660217,-0.009755418635904789,-0.5068392753601074,0.21444277465343475,-0.003625893034040928 -1769682045,480585472,0.0,0.0,0.0,1.0,-0.01574096269905567,0.009305956773459911,-0.009806475602090359,-0.33880484104156494,-0.04058220237493515,-0.001613069325685501 -1769682045,513985280,0.0,0.0,0.0,1.0,-0.017709892243146896,0.010029797442257404,-0.012168225832283497,-0.1682104766368866,0.2548570930957794,-0.0007739751599729061 -1769682045,558905600,0.0,0.0,0.0,1.0,-0.006333354394882917,0.0036242548376321793,-0.011761708185076714,0.0074094124138355255,0.5436043739318848,-0.22946198284626007 -1769682045,571543296,0.0,0.0,0.0,1.0,-0.0031669633463025093,-0.0004026693932246417,-0.01055779680609703,-0.16445152461528778,0.24970583617687225,-0.17103251814842224 -1769682045,614188288,0.0,0.0,0.0,1.0,-0.0004115944029763341,-0.006270089186728001,-0.008729798719286919,-0.08141088485717773,0.12370187044143677,-0.1236175149679184 -1769682045,646834688,0.0,0.0,0.0,1.0,0.001059725065715611,-0.009318866766989231,-0.007544280961155891,-0.08251702785491943,0.12500827014446259,-0.07832521945238113 -1769682045,682696704,0.0,0.0,0.0,1.0,0.0019412680994719267,-0.010269910097122192,-0.006977915298193693,-0.2520976662635803,0.380767285823822,-0.03835786506533623 -1769682045,712591872,0.0,0.0,0.0,1.0,0.0022936430759727955,-0.010358097031712532,-0.006643788889050484,0.08566281944513321,0.4231931269168854,0.002487808931618929 -1769682045,753290240,0.0,0.0,0.0,1.0,0.002498228568583727,-0.009470665827393532,-0.00644235173240304,-0.42347806692123413,0.08639691025018692,0.016888609156012535 -1769682045,779184640,0.0,0.0,0.0,1.0,0.0025322139263153076,-0.008641545660793781,-0.006418908946216106,-0.3396424949169159,-0.04015842825174332,0.042832400649785995 -1769682045,854785280,0.0,0.0,0.0,1.0,-0.003057517111301422,-0.010963156819343567,-0.007702221628278494,-0.09088991582393646,-0.41549623012542725,0.25855115056037903 -1769682045,870551808,0.0,0.0,0.0,1.0,-0.008517423644661903,-0.014697746373713017,-0.009054840542376041,-0.34282201528549194,-0.03573068231344223,0.20035888254642487 -1769682045,878705408,0.0,0.0,0.0,1.0,-0.011340383440256119,-0.016568008810281754,-0.00979275070130825,-0.8496600985527039,-0.3757268190383911,0.12983578443527222 -1769682045,899479808,0.0,0.0,0.0,1.0,-0.012877140194177628,-0.01747516356408596,-0.010184308513998985,-0.5947747230529785,-0.20788981020450592,0.09920887649059296 -1769682045,946252032,0.0,0.0,0.0,1.0,-0.015531686134636402,-0.01840122416615486,-0.010957368649542332,-0.339557409286499,-0.040630318224430084,0.04840574041008949 -1769682045,976464640,0.0,0.0,0.0,1.0,-0.016465984284877777,-0.01851610839366913,-0.011192960664629936,-0.5084632039070129,-0.3376322388648987,0.02382561005651951 -1769682046,13157632,0.0,0.0,0.0,1.0,-0.017530661076307297,-0.018166977912187576,-0.011536285281181335,-0.7612924575805664,0.041654594242572784,-0.03376275300979614 -1769682046,61526528,0.0,0.0,0.0,1.0,-0.02013825811445713,-0.017676346004009247,-0.010946578346192837,0.5078948736190796,0.33847755193710327,-0.010974064469337463 -1769682046,69278976,0.0,0.0,0.0,1.0,-0.02107791043817997,-0.01772712916135788,-0.009649734012782574,7.981507224030793e-05,-0.00012361930566839874,-0.004766103811562061 -1769682046,114405888,0.0,0.0,0.0,1.0,-0.01906486786901951,-0.018008360639214516,-0.007689529564231634,-0.08458889275789261,0.1266150325536728,-0.01288729626685381 -1769682046,150141440,0.0,0.0,0.0,1.0,-0.017415395006537437,-0.017672793939709663,-0.006255496758967638,-0.5504459738731384,-0.0002142135053873062,0.014228842221200466 -1769682046,179814912,0.0,0.0,0.0,1.0,-0.01681523211300373,-0.016665905714035034,-0.005427278112620115,-0.6352578997612,0.12653428316116333,0.012604955583810806 -1769682046,212658432,0.0,0.0,0.0,1.0,-0.015920715406537056,-0.016080858185887337,-0.004768869373947382,0.08465132117271423,-0.12653087079524994,0.014909610152244568 -1769682046,258580480,0.0,0.0,0.0,1.0,-0.015657013282179832,-0.006320989690721035,-0.004002251662313938,-0.7479875087738037,-0.5304917693138123,-0.9331483840942383 -1769682046,267818240,0.0,0.0,0.0,1.0,-0.0072839530184865,-0.00042109392234124243,-0.005400886293500662,-0.5877519845962524,0.32872140407562256,-0.39478859305381775 -1769682046,314642688,0.0,0.0,0.0,1.0,-0.0012584271607920527,0.006008808966726065,-0.006805035751312971,-0.6731858849525452,-0.09211187064647675,-0.27325332164764404 -1769682046,347116288,0.0,0.0,0.0,1.0,-0.0010806104401126504,0.009339611977338791,-0.007728532422333956,-0.0828968808054924,0.12354855984449387,-0.14468657970428467 -1769682046,381208064,0.0,0.0,0.0,1.0,-0.001246239640749991,0.01001538522541523,-0.008286776021122932,-0.04077679663896561,-0.21324467658996582,-0.06615862250328064 -1769682046,412968192,0.0,0.0,0.0,1.0,-0.0015357688535004854,0.009663049131631851,-0.008750849403440952,-0.08496981859207153,0.1266741156578064,-0.004110403824597597 -1769682046,451868416,0.0,0.0,0.0,1.0,-0.0018439809791743755,0.00805803295224905,-0.009215953759849072,-0.0008551346254535019,0.0012529826490208507,0.056007884442806244 -1769682046,479519232,0.0,0.0,0.0,1.0,-0.0019887860398739576,0.006586150731891394,-0.009471118450164795,0.16697163879871368,0.29867106676101685,0.0805932879447937 -1769682046,516469504,0.0,0.0,0.0,1.0,-0.0020228151697665453,0.005016669165343046,-0.009618275798857212,-0.086577869951725,0.12871593236923218,0.09118414670228958 -1769682046,557797632,0.0,0.0,0.0,1.0,-0.002408920554444194,0.0034613017924129963,-0.009705431759357452,-0.29817625880241394,0.16977980732917786,0.07380391657352448 -1769682046,579449856,0.0,0.0,0.0,1.0,-0.0022909753024578094,0.0025089059490710497,-0.00970787275582552,0.12563447654247284,0.08651924133300781,0.059717874974012375 -1769682046,612569600,0.0,0.0,0.0,1.0,-0.0006945792702026665,-0.0002353734744247049,-0.009563238359987736,0.16874811053276062,0.29583948850631714,-0.056301042437553406 -1769682046,661017856,0.0,0.0,0.0,1.0,-0.0023386997636407614,-0.0045256055891513824,-0.009566491469740868,0.08627430349588394,-0.12789508700370789,-0.060221124440431595 -1769682046,670382336,0.0,0.0,0.0,1.0,-0.001578735071234405,-0.00575944222509861,-0.009450986050069332,0.16819046437740326,0.29646506905555725,-0.03247256204485893 -1769682046,732853760,0.0,0.0,0.0,1.0,-0.0002665573265403509,-0.006530363578349352,-0.009039533324539661,-0.21115945279598236,0.040161941200494766,-0.04588824883103371 -1769682046,745804544,0.0,0.0,0.0,1.0,1.818475720938295e-05,-0.0065312995575368404,-0.008782690390944481,-0.1263829916715622,-0.08549748361110687,-0.0048323748633265495 -1769682046,783858944,0.0,0.0,0.0,1.0,0.00043653647298924625,-0.0059580388478934765,-0.00847635604441166,0.04075165465474129,0.21221043169498444,0.013855486176908016 -1769682046,815229952,0.0,0.0,0.0,1.0,0.0009185961680486798,-0.005510371644049883,-0.008220799267292023,-0.3386034667491913,-0.04405297711491585,0.019772592931985855 -1769682046,848610816,0.0,0.0,0.0,1.0,-8.277107554022223e-05,-0.005439789034426212,-0.008176393806934357,0.2518619894981384,0.17235109210014343,0.060739289969205856 -1769682046,879282688,0.0,0.0,0.0,1.0,-0.001153328688815236,-0.0056084515526890755,-0.0081937862560153,-0.0005020800163038075,0.0007565675769001245,0.03455884009599686 -1769682046,915500800,0.0,0.0,0.0,1.0,-0.0018396144732832909,-0.005864973645657301,-0.008240241557359695,-0.4243395924568176,0.08232440799474716,0.032652348279953 -1769682046,956880896,0.0,0.0,0.0,1.0,-0.0027517976704984903,-0.005825096741318703,-0.008482521399855614,-0.000387523730751127,0.0005958908586762846,0.027408940717577934 -1769682046,981132800,0.0,0.0,0.0,1.0,-0.003211495466530323,-0.005690309219062328,-0.008872020989656448,-0.0002164464385714382,0.0003352973726578057,0.015492125414311886 -1769682047,12931072,0.0,0.0,0.0,1.0,-0.00394235597923398,-0.005730911158025265,-0.009389429353177547,-0.2977043390274048,0.16695864498615265,0.0018362877890467644 -1769682047,64286208,0.0,0.0,0.0,1.0,-0.0042170509696006775,-0.00573074771091342,-0.010128903202712536,0.12638843059539795,0.08547724783420563,-0.012033620849251747 -1769682047,71650560,0.0,0.0,0.0,1.0,-0.0046245944686234,-0.005737206898629665,-0.010514184832572937,-0.25710421800613403,0.3783491849899292,-0.01866433396935463 -1769682047,112809472,0.0,0.0,0.0,1.0,-0.004327458795160055,-0.005707764998078346,-0.011178193613886833,-0.21185018122196198,0.040140971541404724,-0.01200135052204132 -1769682047,149410304,0.0,0.0,0.0,1.0,-0.003854733658954501,-0.0057245478965342045,-0.0116534773260355,0.08601926267147064,-0.12636566162109375,-0.009351608343422413 -1769682047,180968192,0.0,0.0,0.0,1.0,-0.0033412750344723463,-0.005683044902980328,-0.011859632097184658,-0.16615548729896545,-0.2981412410736084,-0.007857004180550575 -1769682047,214180352,0.0,0.0,0.0,1.0,-0.00323736690916121,-0.005716943182051182,-0.011899827979505062,-0.126010000705719,-0.08605962246656418,-0.004588721785694361 -1769682047,247298304,0.0,0.0,0.0,1.0,-0.0026716331485658884,-0.005647934507578611,-0.011719896458089352,0.040164198726415634,0.2117905467748642,-0.014591449871659279 -1769682047,279141376,0.0,0.0,0.0,1.0,-0.0008441485115326941,-0.0033853754866868258,-0.011173957027494907,-0.12471865862607956,-0.08819426596164703,-0.10347145050764084 -1769682047,317534976,0.0,0.0,0.0,1.0,-0.0029716866556555033,0.0006814716034568846,-0.010793638415634632,-0.4620875418186188,-0.1355520635843277,-0.15794965624809265 -1769682047,355675904,0.0,0.0,0.0,1.0,-0.002848717151209712,0.004347043111920357,-0.010237806476652622,-0.25123265385627747,-0.1733568161725998,-0.05088762938976288 -1769682047,379195392,0.0,0.0,0.0,1.0,-0.0019195745699107647,0.005287694279104471,-0.009836161509156227,-0.2513088285923004,-0.17321136593818665,-0.04021043702960014 -1769682047,412718336,0.0,0.0,0.0,1.0,-0.002134912647306919,0.00552163552492857,-0.009494980797171593,0.12613028287887573,0.08584597706794739,-0.019196730107069016 -1769682047,461868032,0.0,0.0,0.0,1.0,-0.002493535866960883,0.0051908306777477264,-0.009178878739476204,0.12571394443511963,0.08649381250143051,0.01063158642500639 -1769682047,469157120,0.0,0.0,0.0,1.0,-0.0021272727753967047,0.00481471698731184,-0.00905747339129448,-0.03990500792860985,-0.2115757167339325,0.02995505928993225 -1769682047,514745600,0.0,0.0,0.0,1.0,-0.0023139650002121925,0.004116037394851446,-0.008825545199215412,-0.04726514592766762,0.3385292589664459,0.02480710856616497 -1769682047,548134400,0.0,0.0,0.0,1.0,-0.0026152394711971283,0.0032146144658327103,-0.008667810820043087,-0.3777490556240082,-0.25855401158332825,0.031048323959112167 -1769682047,581364480,0.0,0.0,0.0,1.0,-0.0022259210236370564,0.0026139223482459784,-0.00849922839552164,0.2512513995170593,0.17322136461734772,0.019060416147112846 -1769682047,613623808,0.0,0.0,0.0,1.0,-0.002245228737592697,0.002202418865635991,-0.008308209478855133,-0.00032515142811462283,0.00046970456605777144,0.02383505180478096 -1769682047,650556928,0.0,0.0,0.0,1.0,-0.0010736332042142749,0.001329431775957346,-0.007926068268716335,-0.08583135157823563,0.12475761771202087,-0.050130702555179596 -1769682047,679687168,0.0,0.0,0.0,1.0,0.0006555491709150374,-0.0022698440589010715,-0.00756949232891202,0.5518479347229004,0.0056945085525512695,-0.12372098863124847 -1769682047,716227840,0.0,0.0,0.0,1.0,-0.0003180234634783119,-0.0061892191879451275,-0.007361353375017643,0.12707141041755676,0.08451531827449799,-0.10367901623249054 -1769682047,753724928,0.0,0.0,0.0,1.0,-0.0008676145225763321,-0.009662630967795849,-0.007139013614505529,0.1659153699874878,0.29700589179992676,-0.09425125271081924 -1769682047,780526080,0.0,0.0,0.0,1.0,-0.0012462702579796314,-0.011064746417105198,-0.006941451691091061,-0.047006845474243164,0.33694979548454285,-0.05012401193380356 -1769682047,813103104,0.0,0.0,0.0,1.0,-0.000265141308773309,-0.011330009438097477,-0.006634608376771212,0.12574003636837006,0.08642994612455368,-0.010840295813977718 -1769682047,854576384,0.0,0.0,0.0,1.0,-0.00010444257350172848,-0.010681577026844025,-0.00625515216961503,0.0863339751958847,-0.12503573298454285,0.029722273349761963 -1769682047,879515392,0.0,0.0,0.0,1.0,0.0003430734504945576,-0.009884601458907127,-0.006043287459760904,-0.2990884482860565,0.1646486073732376,0.007553237024694681 -1769682047,914082816,0.0,0.0,0.0,1.0,0.0003523963678162545,-0.009069767780601978,-0.005883354227989912,-0.039072416722774506,-0.21186059713363647,0.022768761962652206 -1769682047,947035904,0.0,0.0,0.0,1.0,-0.00042196258436888456,-0.008875411935150623,-0.005966423079371452,-0.000707741011865437,0.0012349854223430157,0.06316493451595306 -1769682047,983950336,0.0,0.0,0.0,1.0,-0.0011911365436390042,-0.0092110401019454,-0.0060150823555886745,0.12496788799762726,0.08774644881486893,0.049734219908714294 -1769682048,15117312,0.0,0.0,0.0,1.0,-0.0015494480030611157,-0.00951224472373724,-0.006000582594424486,-0.04861404746770859,0.33874285221099854,0.04535054787993431 -1769682048,50893312,0.0,0.0,0.0,1.0,-0.0021953529212623835,-0.00972192082554102,-0.005881773307919502,0.0383029468357563,0.21295951306819916,0.03203582763671875 -1769682048,79179520,0.0,0.0,0.0,1.0,-0.0021637254394590855,-0.009853377006947994,-0.005703261587768793,-0.29930442571640015,0.16436143219470978,0.011722439900040627 -1769682048,115536128,0.0,0.0,0.0,1.0,-0.0024059091228991747,-0.009773089550435543,-0.0055182212963700294,0.12552981078624725,0.08670397102832794,-0.008798506110906601 -1769682048,157581824,0.0,0.0,0.0,1.0,-0.002976605435833335,-0.009671500883996487,-0.005286520346999168,0.00016638585657346994,-0.0003419874410610646,-0.017877358943223953 -1769682048,182011904,0.0,0.0,0.0,1.0,-0.0031673945486545563,-0.009563050232827663,-0.005122724454849958,-0.125265970826149,-0.08722861111164093,-0.01616278663277626 -1769682048,212926720,0.0,0.0,0.0,1.0,-0.0031980739440768957,-0.00949935708194971,-0.004996865522116423,0.00017706991638988256,-0.0003837646800093353,-0.020261183381080627 -1769682048,263594752,0.0,0.0,0.0,1.0,-0.003166157053783536,-0.009332550689578056,-0.0048361485823988914,0.12553556263446808,0.08661825209856033,-0.018464671447873116 -1769682048,272795648,0.0,0.0,0.0,1.0,-0.002903869142755866,-0.009311058558523655,-0.004735011141747236,2.8917609597556293e-05,-6.692696479149163e-05,-0.003575537819415331 -1769682048,313358848,0.0,0.0,0.0,1.0,-0.0020861169323325157,-0.008914854377508163,-0.004520726390182972,0.038945119827985764,0.2109660506248474,-0.07635888457298279 -1769682048,347725824,0.0,0.0,0.0,1.0,-0.0003434991231188178,-0.0038512784522026777,-0.004169900435954332,-0.33588331937789917,-0.05317171663045883,-0.24121376872062683 -1769682048,381629696,0.0,0.0,0.0,1.0,-0.0011256884317845106,1.5161134797381237e-05,-0.004058096557855606,-0.33620190620422363,-0.05248833820223808,-0.2018716186285019 -1769682048,413614848,0.0,0.0,0.0,1.0,-0.0012428418267518282,0.0030249394476413727,-0.003959945868700743,-0.2111918181180954,0.03539739549160004,-0.1560756266117096 -1769682048,447243520,0.0,0.0,0.0,1.0,-0.0014679167652502656,0.005338422954082489,-0.003804492764174938,-0.38576236367225647,0.2870844900608063,-0.10013265162706375 -1769682048,479675392,0.0,0.0,0.0,1.0,-0.00032122674747370183,0.005464629270136356,-0.003671014681458473,0.0383947491645813,0.2119724005460739,-0.023883694782853127 -1769682048,515773184,0.0,0.0,0.0,1.0,-6.577942258445546e-06,0.004877825733274221,-0.0035554911009967327,-0.00024194778234232217,0.0005508069880306721,0.029796268790960312 -1769682048,552247296,0.0,0.0,0.0,1.0,-2.2373027604771778e-05,0.0038089517038315535,-0.0033984759356826544,0.17371277511119843,-0.2494214028120041,0.06447665393352509 -1769682048,579719424,0.0,0.0,0.0,1.0,-0.0003110886609647423,0.0028801513835787773,-0.0033192832488566637,0.0867207944393158,-0.12438254803419113,0.04952850192785263 -1769682048,612779008,0.0,0.0,0.0,1.0,5.3730913350591436e-05,0.0019793289247900248,-0.0032902436796575785,-0.1257680058479309,-0.08602921664714813,0.06014314666390419 -1769682048,666255872,0.0,0.0,0.0,1.0,-7.21076867193915e-05,0.0011136147659271955,-0.0032436372712254524,-0.00037580414209514856,0.0008151526562869549,0.04409833252429962 -1769682048,675630592,0.0,0.0,0.0,1.0,-0.0001760259474394843,0.0008838421781547368,-0.0032327028457075357,0.08694743365049362,-0.12477279454469681,0.02689650095999241 -1769682048,713865472,0.0,0.0,0.0,1.0,-0.0015818008687347174,0.0003796683740802109,-0.003349258564412594,0.21241940557956696,-0.038076967000961304,0.00013782666064798832 -1769682048,747872000,0.0,0.0,0.0,1.0,-0.002377444878220558,-0.00014885648852214217,-0.0033932970836758614,0.12516221404075623,0.08732011169195175,0.006623637862503529 -1769682048,780532224,0.0,0.0,0.0,1.0,-0.0029672530945390463,-0.00047684682067483664,-0.003394933184608817,-0.12535741925239563,-0.08689676225185394,0.017207486554980278 -1769682048,815930112,0.0,0.0,0.0,1.0,-0.0032937023788690567,-0.0006694020703434944,-0.0033469584304839373,0.3375769555568695,0.049339305609464645,0.006756337359547615 -1769682048,858105088,0.0,0.0,0.0,1.0,-0.0035667407792061567,-0.0004480522475205362,-0.0032334753777831793,0.1253669708967209,0.08686543256044388,-0.020768040791153908 -1769682048,879495168,0.0,0.0,0.0,1.0,-0.0037037371657788754,-0.0005010571330785751,-0.0031617656350135803,0.12504398822784424,0.08754201978445053,0.016187181696295738 -1769682048,919402240,0.0,0.0,0.0,1.0,-0.0014381872024387121,0.0004913210868835449,-0.0027328936848789454,-0.212687686085701,0.03844954073429108,0.02850312553346157 -1769682048,957943040,0.0,0.0,0.0,1.0,-0.000423324090661481,0.0017616106197237968,-0.002300403779372573,0.16304154694080353,0.29975825548171997,0.0008243530755862594 -1769682048,967055104,0.0,0.0,0.0,1.0,-0.0004969009896740317,0.002265537390485406,-0.002145172795280814,-0.03803673014044762,-0.21213306486606598,0.018950628116726875 -1769682049,12908544,0.0,0.0,0.0,1.0,0.0004649737384170294,0.0027611972764134407,-0.0018979753367602825,-0.1745138168334961,0.2501975893974304,-0.009553862735629082 -1769682049,57871360,0.0,0.0,0.0,1.0,0.0003151193377561867,0.002787723671644926,-0.0018462209263816476,-0.04952583089470863,0.33777251839637756,0.0066593424417078495 -1769682049,71392768,0.0,0.0,0.0,1.0,0.00014450632443185896,0.002669622888788581,-0.0018459203420206904,0.33755338191986084,0.04953339695930481,0.005693784914910793 -1769682049,113104384,0.0,0.0,0.0,1.0,0.00020291260443627834,0.0023930727038532495,-0.001854565809480846,-6.425708124879748e-05,0.00012746930588036776,0.007151137106120586 -1769682049,148845568,0.0,0.0,0.0,1.0,0.00012913576210848987,0.0019544237293303013,-0.0018737342907115817,0.12492049485445023,0.08773898333311081,0.02341526746749878 -1769682049,183933952,0.0,0.0,0.0,1.0,0.00019457025337032974,0.0017090006731450558,-0.0018826195737347007,0.12519705295562744,0.08719349652528763,-0.007566394284367561 -1769682049,213902336,0.0,0.0,0.0,1.0,0.00023295448045246303,0.001661414047703147,-0.001887702033855021,-2.187191421398893e-05,4.2512448999332264e-05,0.0023837080225348473 -1769682049,248982016,0.0,0.0,0.0,1.0,-0.0002432269393466413,0.001381654990836978,-0.0019023478962481022,3.3024916774593294e-05,-6.376562669174746e-05,-0.0035755597054958344 -1769682049,279448064,0.0,0.0,0.0,1.0,-0.0002466622681822628,0.00123108911793679,-0.0019180836388841271,0.2124052345752716,-0.03765663504600525,0.007411088794469833 -1769682049,316302592,0.0,0.0,0.0,1.0,-0.00013464876974467188,0.0011734487488865852,-0.0019397949799895287,0.12511025369167328,0.0873519703745842,-0.0003922387259081006 -1769682049,355079424,0.0,0.0,0.0,1.0,-0.0005482463166117668,0.0008960868581198156,-0.002003271132707596,-8.920896652853116e-05,0.0001698869455140084,0.009534819051623344 -1769682049,367723264,0.0,0.0,0.0,1.0,-0.0014680895255878568,0.0011678561568260193,-0.002109596272930503,-0.21225471794605255,0.037322185933589935,-0.02411654219031334 -1769682049,413149440,0.0,0.0,0.0,1.0,-0.0027272962033748627,0.0018155076541006565,-0.0023025753907859325,0.2126167118549347,-0.037980347871780396,-0.014012688770890236 -1769682049,467838464,0.0,0.0,0.0,1.0,-0.0033607662189751863,0.002179419621825218,-0.0024168225936591625,-0.12486789375543594,-0.08778806775808334,-0.02230207808315754 -1769682049,478321920,0.0,0.0,0.0,1.0,-0.004186644684523344,0.002843882655724883,-0.002452912973240018,0.08735333383083344,-0.12498701363801956,0.006597629748284817 -1769682049,513776640,0.0,0.0,0.0,1.0,-0.004760566633194685,0.003333891974762082,-0.0024934234097599983,6.941251922398806e-05,-0.0001237928809132427,-0.007151153404265642 -1769682049,547899648,0.0,0.0,0.0,1.0,-0.005278883036226034,0.0036251803394407034,-0.0025062449276447296,0.03758295625448227,0.21257884800434113,0.003887401893734932 -1769682049,583193344,0.0,0.0,0.0,1.0,-0.0034746499732136726,0.0026328249368816614,-0.0025379417929798365,-0.08786801993846893,0.12579834461212158,0.042298175394535065 -1769682049,613524736,0.0,0.0,0.0,1.0,-0.002571867546066642,0.001678181579336524,-0.0025403096806257963,-0.0006672546151094139,0.0011283603962510824,0.06674455851316452 -1769682049,651232768,0.0,0.0,0.0,1.0,-0.002386349020525813,0.0006491245003417134,-0.002549236873164773,-0.00026325020007789135,0.0004407480591908097,0.026221035048365593 -1769682049,666341120,0.0,0.0,0.0,1.0,-0.0019047276582568884,0.00023664627224206924,-0.0025604115799069405,-0.12535881996154785,-0.08692001551389694,0.03239072486758232 -1769682049,717778688,0.0,0.0,0.0,1.0,-0.0012182332575321198,-0.0003210660070180893,-0.002555878134444356,-0.00011971704952884465,0.00019906804664060473,0.011918674223124981 -1769682049,759984896,0.0,0.0,0.0,1.0,-0.0008221714524552226,-0.0005314364680089056,-0.002562023466452956,-0.212680846452713,0.03782437741756439,0.0163146760314703 -1769682049,771245824,0.0,0.0,0.0,1.0,-0.0005802276427857578,-0.00048751680878922343,-0.002588982693850994,3.58109173248522e-05,-5.953048457740806e-05,-0.003575606271624565 -1769682049,813595904,0.0,0.0,0.0,1.0,-0.0002955766976810992,-0.0005152568337507546,-0.0026328079402446747,-0.08743209391832352,0.12487922608852386,-0.008912485092878342 -1769682049,859547648,0.0,0.0,0.0,1.0,-5.7152126828441396e-05,-0.0004153694899287075,-0.0026737269945442677,-0.04980133846402168,0.337099552154541,-0.0275613684207201 -1769682049,870165248,0.0,0.0,0.0,1.0,0.00019456389418337494,-0.0003079746966250241,-0.002698203781619668,-0.13743843138217926,0.46223950386047363,-0.01978343352675438 -1769682049,913644032,0.0,0.0,0.0,1.0,8.622936729807407e-05,-0.0001714501267997548,-0.0027504281606525183,0.037490468472242355,0.21243378520011902,-0.00673338770866394 -1769682049,949422336,0.0,0.0,0.0,1.0,9.92763671092689e-06,-0.00010390098032075912,-0.002811802551150322,0.12502993643283844,0.08745332062244415,-0.006169082596898079 -1769682049,982635520,0.0,0.0,0.0,1.0,6.553063576575369e-05,0.00010987679706886411,-0.0028076174203306437,-0.30000364780426025,0.16221323609352112,-0.01164831779897213 -1769682050,13639424,0.0,0.0,0.0,1.0,0.00046549830585718155,0.000228428456466645,-0.0027916538529098034,-0.12499149143695831,-0.08751386404037476,0.0037865499034523964 -1769682050,48580096,0.0,0.0,0.0,1.0,0.0006348887109197676,0.0004991197492927313,-0.0027909644413739443,-0.037276528775691986,-0.21266652643680573,-0.006368191912770271 -1769682050,81010944,0.0,0.0,0.0,1.0,0.0004705706378445029,0.0005532598006539047,-0.0028164659161120653,0.00011929706670343876,-0.00019873687415383756,-0.011918683536350727 -1769682050,117970688,0.0,0.0,0.0,1.0,0.00033999717561528087,0.0005692074191756546,-0.0028477704618126154,0.037276167422533035,0.21261334419250488,0.0027880240231752396 -1769682050,151896576,0.0,0.0,0.0,1.0,-0.000249994162004441,0.00018994453421328217,-0.003011808032169938,-0.03745468333363533,-0.2122795581817627,0.01747490093111992 -1769682050,168070400,0.0,0.0,0.0,1.0,-0.0001297907583648339,7.042653305688873e-05,-0.003098458983004093,0.03708234801888466,0.21287864446640015,0.018281402066349983 -1769682050,213036288,0.0,0.0,0.0,1.0,-0.0007172154146246612,-0.0003755705838557333,-0.0032221416477113962,0.12497623264789581,0.08752749115228653,-0.007357658818364143 -1769682050,261969408,0.0,0.0,0.0,1.0,-0.0007487966795451939,-0.00044581954716704786,-0.0033012907952070236,1.1952481145272031e-05,-1.9824563423753716e-05,-0.0011918689124286175 -1769682050,283305728,0.0,0.0,0.0,1.0,-0.0011200432199984789,-0.0005569419590756297,-0.003364156698808074,-0.1248602569103241,-0.08771516382694244,-0.0021787635050714016 -1769682050,299518976,0.0,0.0,0.0,1.0,-0.0010236029047518969,-0.0005271381814964116,-0.0033809731248766184,-0.12485436350107193,-0.08772352337837219,-0.0021792154293507338 -1769682050,347144960,0.0,0.0,0.0,1.0,-0.0012405990855768323,-0.0004502591327764094,-0.0034147053956985474,-0.4250873327255249,0.07422620803117752,-0.007854225113987923 -1769682050,386021632,0.0,0.0,0.0,1.0,-0.000779231486376375,-0.00010489493433851749,-0.0034080669283866882,0.00019029001123271883,-0.00031445379136130214,-0.019069956615567207 -1769682050,413124352,0.0,0.0,0.0,1.0,-0.0006525904755108058,7.821850886102766e-05,-0.0033954866230487823,0.16216321289539337,0.29996785521507263,-0.02239750511944294 -1769682050,449825536,0.0,0.0,0.0,1.0,-0.0008071373449638486,0.0003266959683969617,-0.003428225638344884,7.145789277274162e-05,-0.00011753793660318479,-0.007151239085942507 -1769682050,480102912,0.0,0.0,0.0,1.0,-0.00025054728030227125,0.0003333714557811618,-0.003431183286011219,-0.161960631608963,-0.30022287368774414,0.009272577241063118 -1769682050,514117120,0.0,0.0,0.0,1.0,-0.0002704146027099341,0.00043320725671947,-0.0034377845004200935,0.21263547241687775,-0.037114545702934265,-0.003222367260605097 -1769682050,565619968,0.0,0.0,0.0,1.0,-0.0005117395194247365,0.0005367855192162097,-0.0034775398671627045,-0.12480315566062927,-0.08779086172580719,0.00018653844017535448 -1769682050,574864384,0.0,0.0,0.0,1.0,-0.0005599195719696581,0.000721067248377949,-0.00349634001031518,0.08782666176557541,-0.12482764571905136,-0.0006487423088401556 -1769682050,601031424,0.0,0.0,0.0,1.0,-0.0005635607521981001,0.0006835149833932519,-0.0035280624870210886,0.05065498873591423,-0.3370850086212158,0.02152736485004425 -1769682050,655711744,0.0,0.0,0.0,1.0,-0.0003850462380796671,0.0006286694551818073,-0.003577857743948698,0.12472392618656158,0.0879128947854042,0.004593655467033386 -1769682050,665691648,0.0,0.0,0.0,1.0,-0.00012497084389906377,0.0005546158645302057,-0.0036115495022386312,-0.30059584975242615,0.1619107574224472,0.011003161780536175 -1769682050,704380928,0.0,0.0,0.0,1.0,-0.0005402110400609672,0.0001655461237533018,-0.003644570242613554,0.1248134970664978,0.08776473253965378,-0.006129146087914705 -1769682050,746630912,0.0,0.0,0.0,1.0,-0.0009017789852805436,-0.0002104664163198322,-0.003705278504639864,-0.3374922573566437,-0.05081231892108917,0.01171373762190342 -1769682050,813801472,0.0,0.0,0.0,1.0,-0.0007851985283195972,-0.0005317730247043073,-0.003728399286046624,-0.03680100664496422,-0.21267767250537872,-0.0016785621410235763 -1769682050,815830272,0.0,0.0,0.0,1.0,-0.0008098644902929664,-0.0006434055976569653,-0.0037601867225021124,0.08794330060482025,-0.12477332353591919,-0.001851043663918972 -1769682050,856601088,0.0,0.0,0.0,1.0,-0.0010543897515162826,-0.0005341885262168944,-0.0037901627365499735,0.12481532990932465,0.08775333315134048,-0.010894550010561943 -1769682050,867826944,0.0,0.0,0.0,1.0,-0.0009199813939630985,-0.0006971778930164874,-0.003790240501984954,0.12461631745100021,0.08807194232940674,0.008175335824489594 -1769682050,913074432,0.0,0.0,0.0,1.0,-0.0013636794174090028,-0.0005621794844046235,-0.003778597805649042,-0.2126295119524002,0.03670724108815193,-0.002731612417846918 -1769682050,961755136,0.0,0.0,0.0,1.0,-0.0010874932631850243,-0.0005183013272471726,-0.0037527570966631174,-0.08803301304578781,0.12476499378681183,0.004259271547198296 -1769682050,972520704,0.0,0.0,0.0,1.0,-0.001134630641900003,-0.00048083701403811574,-0.00375121901743114,-0.2125900685787201,0.03658273071050644,-0.007489623036235571 -1769682051,13717760,0.0,0.0,0.0,1.0,-0.0013145571574568748,-0.0004472786094993353,-0.0037508581299334764,-0.0880608856678009,0.1247449517250061,0.004270025994628668 -1769682051,50011392,0.0,0.0,0.0,1.0,-0.0008075676742009819,-0.0003133787540718913,-0.0036853658966720104,-0.00013103391393087804,0.00020990974735468626,0.013110695406794548 -1769682051,83005952,0.0,0.0,0.0,1.0,-0.0003008721978403628,-2.9216631446615793e-05,-0.0036190066020935774,-0.16136033833026886,-0.3004860281944275,0.0151186753064394 -1769682051,113906176,0.0,0.0,0.0,1.0,-8.590488869231194e-05,0.0002179963339585811,-0.0035723885521292686,0.0363963283598423,0.2129511535167694,0.016034340485930443 -1769682051,150282496,0.0,0.0,0.0,1.0,5.0259350246051326e-05,0.00044883761438541114,-0.0035849171690642834,0.21259038150310516,-0.03640526905655861,0.009865515865385532 -1769682051,179867904,0.0,0.0,0.0,1.0,3.131869016215205e-05,0.000565685739275068,-0.003644295735284686,-4.7837769670877606e-05,7.627726154169068e-05,0.0047675250098109245 -1769682051,219624960,0.0,0.0,0.0,1.0,0.00014626991469413042,0.00046859600115567446,-0.0037431276869028807,0.3373318314552307,0.05150582268834114,-0.0045877303928136826 -1769682051,259592704,0.0,0.0,0.0,1.0,8.745735976845026e-05,0.00026985263684764504,-0.0038797094020992517,0.036465395241975784,0.2126840204000473,-0.0018451064825057983 -1769682051,272496384,0.0,0.0,0.0,1.0,0.00013290741480886936,0.00024347232829313725,-0.003952591214329004,-0.21270237863063812,0.03646170347929001,-0.0003419418353587389 -1769682051,314373120,0.0,0.0,0.0,1.0,5.1943614380434155e-05,0.00015024458116386086,-0.004091672599315643,6.01020255999174e-05,-9.540297469357029e-05,-0.0059594023041427135 -1769682051,366801408,0.0,0.0,0.0,1.0,7.744885078864172e-05,7.409342651953921e-05,-0.004192659631371498,-0.08808955550193787,0.1244213730096817,-0.008841775357723236 -1769682051,376104704,0.0,0.0,0.0,1.0,0.0001222965947818011,0.00016414659330621362,-0.00425150478258729,0.12468581646680832,0.08793080598115921,-0.015648791566491127 -1769682051,413108480,0.0,0.0,0.0,1.0,-0.0003775650402531028,0.0004281705478206277,-0.004305196460336447,-0.12442167848348618,-0.08834732323884964,-0.00938313826918602 -1769682051,447313408,0.0,0.0,0.0,1.0,-0.0005588686908595264,0.000800976762548089,-0.004341105930507183,-0.12438192218542099,-0.08840670436620712,-0.011772653087973595 -1769682051,483056128,0.0,0.0,0.0,1.0,-0.0006690745940431952,0.0009183203219436109,-0.004361703991889954,0.0362812764942646,0.21269863843917847,-0.0030241303611546755 -1769682051,514812672,0.0,0.0,0.0,1.0,-0.0011623486643657088,0.0010005882941186428,-0.004391204100102186,-0.3370610475540161,-0.05225071310997009,-0.015721069648861885 -1769682051,549228544,0.0,0.0,0.0,1.0,-0.0010611442849040031,0.0012303589610382915,-0.004416791722178459,0.00024424970615655184,-0.0003782764251809567,-0.0238376222550869 -1769682051,579906304,0.0,0.0,0.0,1.0,-0.001271162647753954,0.001205941429361701,-0.00448014959692955,-0.3371293544769287,-0.05222182720899582,-0.00740942545235157 -1769682051,614728192,0.0,0.0,0.0,1.0,-0.0014294879510998726,0.001380787929520011,-0.004506625700742006,-0.21290311217308044,0.03637625277042389,0.013919666409492493 -1769682051,656379392,0.0,0.0,0.0,1.0,-0.0022027846425771713,0.0016178588848561049,-0.004546568728983402,0.12436249852180481,0.08842058479785919,0.0058646732941269875 -1769682051,667546880,0.0,0.0,0.0,1.0,0.0003465178597252816,0.0007101750234141946,-0.004437379539012909,-0.051623065024614334,0.3362087309360504,-0.06423594057559967 -1769682051,713800448,0.0,0.0,0.0,1.0,0.0018668785924091935,-0.00395518634468317,-0.004229058511555195,0.3023119866847992,-0.16225871443748474,-0.1123528778553009 -1769682051,765276928,0.0,0.0,0.0,1.0,0.002497732173651457,-0.008864525705575943,-0.00415502255782485,0.03670283034443855,0.211665540933609,-0.0709502175450325 -1769682051,775452416,0.0,0.0,0.0,1.0,0.0024830298498272896,-0.011033953167498112,-0.004136295989155769,-0.08801155537366867,0.12374408543109894,-0.040983639657497406 -1769682051,813892096,0.0,0.0,0.0,1.0,0.00250478507950902,-0.01240650936961174,-0.004093199502676725,0.036278266459703445,0.2122172862291336,-0.03644246980547905 -1769682051,847602432,0.0,0.0,0.0,1.0,0.0027371689211577177,-0.013019231148064137,-0.004070150665938854,0.12425479292869568,0.08860412985086441,0.010404800064861774 -1769682051,896965376,0.0,0.0,0.0,1.0,0.0030101966112852097,-0.012902508489787579,-0.00402858154848218,-0.12442004680633545,-0.08829165995121002,0.009913839399814606 -1769682051,905440256,0.0,0.0,0.0,1.0,0.002945070154964924,-0.012612242251634598,-0.004044132772833109,-0.08876287937164307,0.12492584437131882,0.03539741039276123 -1769682051,950418688,0.0,0.0,0.0,1.0,0.002939588390290737,-0.011810177937150002,-0.004054342862218618,-0.12437736243009567,-0.08834429830312729,0.008848002180457115 -1769682051,980636160,0.0,0.0,0.0,1.0,0.0026415041647851467,-0.011227995157241821,-0.004114980343729258,0.03580278158187866,0.21279461681842804,-0.0020573895890265703 -1769682052,18264576,0.0,0.0,0.0,1.0,0.0028722223360091448,-0.01092575117945671,-0.004195652436465025,-0.017047781497240067,0.5500823259353638,0.0062592471949756145 -1769682052,58144768,0.0,0.0,0.0,1.0,0.002565186470746994,-0.010450680740177631,-0.004338480532169342,0.08842107653617859,-0.12397319823503494,0.01933886483311653 -1769682052,69092864,0.0,0.0,0.0,1.0,0.002630722476169467,-0.010441841557621956,-0.004434401169419289,0.03565104305744171,0.21298742294311523,0.008582918904721737 -1769682052,114415616,0.0,0.0,0.0,1.0,0.0020155685488134623,-0.010470219887793064,-0.004682862665504217,7.752105011604726e-05,-0.00022074744629207999,-0.013110943138599396 -1769682052,167725568,0.0,0.0,0.0,1.0,0.0011463164119049907,-0.01096212025731802,-0.00496217655017972,-0.12413842976093292,-0.0888865739107132,-0.01707838848233223 -1769682052,176651776,0.0,0.0,0.0,1.0,0.0006674713222309947,-0.011606400832533836,-0.005271001718938351,-0.12410334497690201,-0.08899326622486115,-0.021786915138363838 -1769682052,214003712,0.0,0.0,0.0,1.0,0.00045171749661676586,-0.011955136433243752,-0.0054121180437505245,0.24846720695495605,0.17705953121185303,-0.013728484511375427 -1769682052,247762432,0.0,0.0,0.0,1.0,0.00020175593090243638,-0.01236746460199356,-0.005533698946237564,0.21285606920719147,-0.03554457053542137,-0.000867912545800209 -1769682052,268187648,0.0,0.0,0.0,1.0,-0.0002738015027716756,-0.0124539565294981,-0.00560934841632843,-0.33712664246559143,-0.05276796966791153,0.024563174694776535 -1769682052,313898496,0.0,0.0,0.0,1.0,-0.0012057648273184896,-0.01289868913590908,-0.005763832945376635,0.12410761415958405,0.08892156183719635,0.012054329738020897 -1769682052,356923648,0.0,0.0,0.0,1.0,0.003695983672514558,-0.010872023180127144,-0.005402715411037207,0.07120658457279205,0.4234393537044525,-0.13929365575313568 -1769682052,380355072,0.0,0.0,0.0,1.0,0.0030257608741521835,-0.00650895107537508,-0.0052976468577980995,-0.08819902688264847,0.12076815217733383,-0.19783996045589447 -1769682052,414478336,0.0,0.0,0.0,1.0,0.003258239012211561,-0.0029767765663564205,-0.005244352389127016,-0.21234093606472015,0.03192802891135216,-0.1990417242050171 -1769682052,451327488,0.0,0.0,0.0,1.0,0.003567703301087022,-0.00010074293095385656,-0.0051514701917767525,0.00030987279023975134,-0.0019950219430029392,-0.11561545729637146 -1769682052,479774208,0.0,0.0,0.0,1.0,0.0033217419404536486,0.0009560594917275012,-0.0051459358073771,-0.21271473169326782,0.03410082310438156,-0.06674239039421082 -1769682052,513377536,0.0,0.0,0.0,1.0,0.003383347298949957,0.0014838875504210591,-0.005158145911991596,-0.1423535943031311,0.4602954089641571,-0.045389313250780106 -1769682052,544295936,0.0,0.0,0.0,1.0,0.003209856338799,0.0014579580165445805,-0.0052542248740792274,-1.9980441720690578e-05,0.00012558864546008408,0.007151431404054165 -1769682052,582632192,0.0,0.0,0.0,1.0,0.002995643997564912,0.0009116504224948585,-0.005583304446190596,0.17764681577682495,-0.24724699556827545,0.047798123210668564 -1769682052,613608960,0.0,0.0,0.0,1.0,0.002721767872571945,0.00046476873103529215,-0.0057832179591059685,-0.12412695586681366,-0.08817871659994125,0.041747868061065674 -1769682052,648284416,0.0,0.0,0.0,1.0,0.0030238195322453976,-0.00042849197052419186,-0.0059783183969557285,-0.03511966019868851,-0.21248896420001984,0.026348628103733063 -1769682052,681986560,0.0,0.0,0.0,1.0,0.004659936763346195,-0.002281083958223462,-0.006072487682104111,0.42585232853889465,-0.06993499398231506,0.006036118604242802 -1769682052,707896832,0.0,0.0,0.0,1.0,0.004816789645701647,-0.004221535753458738,-0.006186909042298794,0.2479238063097,0.17788031697273254,-0.006129333283752203 -1769682052,747514112,0.0,0.0,0.0,1.0,0.005113794934004545,-0.006048159208148718,-0.006273272912949324,-0.2670278549194336,0.371664434671402,-0.01105847954750061 -1769682052,780491776,0.0,0.0,0.0,1.0,0.004569062497466803,-0.006628280505537987,-0.006272614933550358,0.05421530082821846,-0.33729687333106995,-0.019870666787028313 -1769682052,817535488,0.0,0.0,0.0,1.0,0.0039495560340583324,-0.0063271853141486645,-0.006227047182619572,0.034916527569293976,0.21225976943969727,-0.03964586555957794 -1769682052,864080896,0.0,0.0,0.0,1.0,0.0038678785786032677,-0.005765003617852926,-0.006153320427983999,-0.2128995954990387,0.03407992050051689,-0.038002386689186096 -1769682052,871236096,0.0,0.0,0.0,1.0,0.0038151098415255547,-0.005404303781688213,-0.00610570190474391,-0.12383319437503815,-0.08945436775684357,-0.01761108636856079 -1769682052,913735680,0.0,0.0,0.0,1.0,0.0035919388756155968,-0.004825611133128405,-0.006016937550157309,2.4445107555948198e-05,-0.0002942777646239847,-0.01549440436065197 -1769682052,963251200,0.0,0.0,0.0,1.0,0.0034963423386216164,-0.004417855758219957,-0.005928858648985624,0.24764584004878998,0.17833071947097778,-0.0018718186765909195 -1769682052,970182912,0.0,0.0,0.0,1.0,0.0032390051055699587,-0.004239344969391823,-0.005919403396546841,-1.885714300442487e-05,0.00027444944134913385,0.014302479103207588 -1769682053,13470976,0.0,0.0,0.0,1.0,0.002877984195947647,-0.004031057003885508,-0.005893264897167683,0.03457073122262955,0.21312545239925385,0.004270520061254501 -1769682053,48062720,0.0,0.0,0.0,1.0,0.002743830904364586,-0.004006430506706238,-0.005874537397176027,-0.08924684673547745,0.12386126816272736,0.003465439658612013 -1769682053,85405952,0.0,0.0,0.0,1.0,0.0029464743565768003,-0.004051324911415577,-0.005834643263369799,-0.03449809551239014,-0.2128380686044693,0.011277788318693638 -1769682053,114077952,0.0,0.0,0.0,1.0,0.002945146057754755,-0.0040737660601735115,-0.005787390749901533,0.21302549540996552,-0.034491054713726044,-0.0015446408651769161 -1769682053,153005312,0.0,0.0,0.0,1.0,0.002745454665273428,-0.004115986172109842,-0.005664255004376173,0.0,-0.0,0.0 -1769682053,180358144,0.0,0.0,0.0,1.0,0.0014346904354169965,-0.0046349880285561085,-0.005484344437718391,0.24740540981292725,0.17868287861347198,-0.001032671658322215 -1769682053,216071936,0.0,0.0,0.0,1.0,0.000560771964956075,-0.005387214943766594,-0.005407373420894146,-0.03433067351579666,-0.2131904810667038,-0.005326245911419392 -1769682053,255607296,0.0,0.0,0.0,1.0,0.00020940459216944873,-0.006089157424867153,-0.005193283781409264,1.6669509932398796e-06,-0.00033084943424910307,-0.016686031594872475 -1769682053,280912640,0.0,0.0,0.0,1.0,9.917710849549621e-05,-0.0064018419943749905,-0.005016706418246031,0.08939933776855469,-0.12391478568315506,-0.011858150362968445 -1769682053,314231296,0.0,0.0,0.0,1.0,-5.266985681373626e-05,-0.006527474615722895,-0.004817286040633917,-0.15786509215831757,-0.3024671673774719,0.003658855566754937 -1769682053,368527872,0.0,0.0,0.0,1.0,0.0019278193358331919,-0.005491460207849741,-0.004473288077861071,0.034166380763053894,0.2118866890668869,-0.06145784631371498 -1769682053,376118272,0.0,0.0,0.0,1.0,0.0017854656325653195,-0.0032141206320375204,-0.004154966212809086,0.12355943769216537,0.08768043667078018,-0.09005653113126755 -1769682053,399266048,0.0,0.0,0.0,1.0,0.0021405392326414585,-0.002372896997258067,-0.004059717059135437,-0.0341838113963604,-0.21441270411014557,-0.06484893709421158 -1769682053,447159808,0.0,0.0,0.0,1.0,0.0023712378460913897,-0.0010441674385219812,-0.003973336890339851,-0.0554269440472126,0.33581259846687317,-0.046052027493715286 -1769682053,470721792,0.0,0.0,0.0,1.0,0.0025582413654774427,-0.0006197342881932855,-0.003932307008653879,-0.12358912825584412,-0.08969900012016296,-0.008832830004394054 -1769682053,513666816,0.0,0.0,0.0,1.0,0.0028320075944066048,-0.00038320390740409493,-0.0038764108903706074,-0.08951961994171143,0.12361561506986618,0.0011426707496866584 -1769682053,548939776,0.0,0.0,0.0,1.0,0.002945384243503213,-0.0005879865493625402,-0.0037536185700446367,-0.15756309032440186,-0.30249786376953125,0.009858932346105576 -1769682053,580294144,0.0,0.0,0.0,1.0,0.0032109010498970747,-0.0008524364675395191,-0.003573874244466424,0.30267202854156494,-0.1570170372724533,0.026817981153726578 -1769682053,614168576,0.0,0.0,0.0,1.0,0.003211777191609144,-0.0010584697593003511,-0.003409632947295904,9.838724508881569e-06,0.0002449959865771234,0.011918415315449238 -1769682053,656985856,0.0,0.0,0.0,1.0,0.0038571960758417845,-0.0017904604319483042,-0.0031064501963555813,0.12353742122650146,0.08990763872861862,0.014722548425197601 -1769682053,682085376,0.0,0.0,0.0,1.0,0.003631558269262314,-0.002435416914522648,-0.0028998316265642643,-0.33662956953048706,-0.05578039586544037,-0.004481317475438118 -1769682053,746948352,0.0,0.0,0.0,1.0,0.003211663570255041,-0.003059983951970935,-0.0026689202059060335,0.03389444574713707,0.21291546523571014,-0.011641757562756538 -1769682053,757750016,0.0,0.0,0.0,1.0,0.0032092288602143526,-0.003275135299190879,-0.002372436923906207,6.930989911779761e-06,0.00012540574243757874,0.00595914525911212 -1769682053,790865408,0.0,0.0,0.0,1.0,0.0029476042836904526,-0.003504473250359297,-0.0021813856437802315,2.4130713427439332e-05,0.0004029081610497087,0.019069228321313858 -1769682053,803402496,0.0,0.0,0.0,1.0,0.002719985553994775,-0.003461109474301338,-0.0020195720717310905,0.12348418682813644,0.08958534896373749,-0.0032613519579172134 -1769682053,854890496,0.0,0.0,0.0,1.0,0.001599014620296657,-0.0029745951760560274,-0.001824108068831265,-0.12353593856096268,-0.0904320478439331,-0.03604452684521675 -1769682053,871082496,0.0,0.0,0.0,1.0,0.0006484006298705935,-0.0024646499659866095,-0.0017800781643018126,-6.284797564148903e-05,-0.000863663328345865,-0.040521930903196335 -1769682053,914370304,0.0,0.0,0.0,1.0,-0.00021518062567338347,-0.0014522894052788615,-0.0017317908350378275,0.08961666375398636,-0.12397798895835876,-0.022541223093867302 -1769682053,958818560,0.0,0.0,0.0,1.0,-0.00023232058447320014,-0.0009430958307348192,-0.0017295503057539463,0.1234031394124031,0.08887926489114761,-0.037871405482292175 -1769682053,981193728,0.0,0.0,0.0,1.0,-0.0004736889386549592,-0.0008429668960161507,-0.0016910210251808167,-3.023789031431079e-05,-0.00038077979115769267,-0.017877323552966118 -1769682054,13901824,0.0,0.0,0.0,1.0,-0.0006102306069806218,-0.0005991312209516764,-0.0016368108335882425,0.12342918664216995,0.08934950828552246,-0.016420530155301094 -1769682054,66970112,0.0,0.0,0.0,1.0,-0.0006509993690997362,-0.0005712476558983326,-0.0015503381146118045,-1.2315060303080827e-05,-0.00015204530791379511,-0.007150935009121895 -1769682054,77933312,0.0,0.0,0.0,1.0,-0.0005373473977670074,-0.0005838823853991926,-0.0013204284477978945,0.12346707284450531,0.0899452418088913,0.010990253649652004 -1769682054,99044608,0.0,0.0,0.0,1.0,-0.0004599678504746407,-0.0006438401760533452,-0.0011427056742832065,-0.12344202399253845,-0.08966977149248123,0.002120549790561199 -1769682054,148752384,0.0,0.0,0.0,1.0,-0.0002948673500213772,-0.0008941906853578985,-0.0005990934441797435,0.08970601856708527,-0.1233382448554039,0.006032585632055998 -1769682054,173427968,0.0,0.0,0.0,1.0,-0.0003577921015676111,-0.0010630866745486856,-0.0003747384180314839,-0.03371072933077812,-0.21278588473796844,0.018883561715483665 -1769682054,214278656,0.0,0.0,0.0,1.0,-0.00027255865279585123,-0.00101754954084754,4.873746001976542e-05,-0.2131449431180954,0.0336606465280056,-0.0038952906616032124 -1769682054,248122880,0.0,0.0,0.0,1.0,-1.3046648746239953e-05,-0.0010240987176075578,0.0004332025127951056,0.21314698457717896,-0.033637892454862595,0.005077717825770378 -1769682054,280194560,0.0,0.0,0.0,1.0,-3.998220927314833e-05,-0.0010185318533331156,0.0006687114364467561,0.08976233005523682,-0.12270824611186981,0.035813990980386734 -1769682054,301949184,0.0,0.0,0.0,1.0,0.0003051165258511901,-0.0008282744092866778,0.0008208384388126433,0.24688391387462616,0.17936719954013824,-0.0030910365749150515 -1769682054,355055616,0.0,0.0,0.0,1.0,0.0002429423329886049,-8.045144204515964e-05,0.0011542412685230374,-0.24696367979049683,-0.18011309206485748,-0.032653845846652985 -1769682054,382706432,0.0,0.0,0.0,1.0,0.00017895884229801595,0.00029209087369963527,0.00130114471539855,-0.1794380396604538,0.24611623585224152,-0.03945009410381317 -1769682054,413716736,0.0,0.0,0.0,1.0,0.0002631474344525486,0.0006185736274346709,0.0014106931630522013,-1.8621693016029894e-05,-0.00020242865139152855,-0.009534582495689392 -1769682054,473553920,0.0,0.0,0.0,1.0,-0.00024041387951001525,0.0007741947192698717,0.0015716616762802005,-0.21312347054481506,0.03386275842785835,0.003268875414505601 -1769682054,477318144,0.0,0.0,0.0,1.0,-9.887598571367562e-05,0.0006332453340291977,0.0016974544851109385,0.3365616202354431,0.05551483854651451,-0.017321504652500153 -1769682054,513253120,0.0,0.0,0.0,1.0,-0.0001978367508854717,0.0007360893068835139,0.0018115374259650707,0.21312010288238525,-0.0338846780359745,-0.003260249737650156 -1769682054,548129792,0.0,0.0,0.0,1.0,-6.55574694974348e-07,0.0005952249630354345,0.002022029599174857,0.0676712691783905,0.4264034926891327,0.0027474593371152878 -1769682054,577868288,0.0,0.0,0.0,1.0,-0.00021613632270600647,0.0005871891626156867,0.0022241331171244383,-0.33654943108558655,-0.055170804262161255,0.030408605933189392 -1769682054,615524608,0.0,0.0,0.0,1.0,-0.000504022988025099,0.0008307516691274941,0.0024496978148818016,0.033866774290800095,0.21322238445281982,0.0025697345845401287 -1769682054,652375040,0.0,0.0,0.0,1.0,6.064474655431695e-05,0.0013666143640875816,0.002880870131775737,-0.12345384061336517,-0.08908965438604355,0.025956004858016968 -1769682054,697037056,0.0,0.0,0.0,1.0,-7.775040285196155e-05,0.0018449067138135433,0.0032755890861153603,-0.12347806245088577,-0.08925490826368332,0.017606593668460846 -1769682054,717963264,0.0,0.0,0.0,1.0,4.4246822653803974e-05,0.0020382124930620193,0.0036994502879679203,-0.15739493072032928,-0.30212506651878357,0.03051607683300972 -1769682054,756093952,0.0,0.0,0.0,1.0,8.126627653837204e-05,0.002337019657716155,0.004195678047835827,0.30265894532203674,-0.15771180391311646,-0.009062772616744041 -1769682054,769201152,0.0,0.0,0.0,1.0,-0.00043579054181464016,0.0025903359055519104,0.004425257910043001,-0.08951549232006073,0.12416934967041016,0.028507892042398453 -1769682054,813349632,0.0,0.0,0.0,1.0,-0.00114694912917912,0.00303493975661695,0.004794389475136995,0.21314038336277008,-0.03333202376961708,0.03259329870343208 -1769682054,861101312,0.0,0.0,0.0,1.0,-0.0017802580259740353,0.003405787516385317,0.00503211934119463,0.12357679754495621,0.08956748247146606,0.0015258843777701259 -1769682054,882000640,0.0,0.0,0.0,1.0,-0.002178970957174897,0.003321028547361493,0.005110656376928091,0.0894932821393013,-0.12361115217208862,0.00010739022400230169 -1769682054,915626752,0.0,0.0,0.0,1.0,-0.002116624964401126,0.0032372577115893364,0.0051415241323411465,0.08948484063148499,-0.12342497706413269,0.009643475525081158 -1769682054,948027648,0.0,0.0,0.0,1.0,-0.0023932731710374355,0.0030620386824011803,0.005136151798069477,1.1834690667456016e-06,2.489845428499393e-05,0.0011918330565094948 -1769682054,981501952,0.0,0.0,0.0,1.0,-0.0021323072724044323,0.002861686749383807,0.005126448348164558,0.21307529509067535,-0.033949173986911774,0.01243721041828394 -1769682055,14120448,0.0,0.0,0.0,1.0,-0.0017341997008770704,0.0027371691539883614,0.005137245170772076,0.21305915713310242,-0.03423023223876953,0.0005347896367311478 -1769682055,66983424,0.0,0.0,0.0,1.0,-0.0019268807955086231,0.0025305424351245165,0.005273248068988323,-0.055102452635765076,0.3367941677570343,0.00022792734671384096 -1769682055,75242496,0.0,0.0,0.0,1.0,-0.0015264613321051002,0.002535047475248575,0.005557630676776171,0.2130478471517563,-0.034260399639606476,0.0029529021121561527 -1769682055,116718080,0.0,0.0,0.0,1.0,-0.0013125324621796608,0.002514504361897707,0.0058990586549043655,-0.21304857730865479,0.034052103757858276,-0.014885799027979374 -1769682055,156527104,0.0,0.0,0.0,1.0,-0.0012287453282624483,0.0024227353278547525,0.006540838163346052,0.08931023627519608,-0.12381568551063538,-0.0034615914337337017 -1769682055,168150016,0.0,0.0,0.0,1.0,-0.0011582038132473826,0.0025080598425120115,0.006849200464785099,0.08929364383220673,-0.12382771074771881,-0.003459736704826355 -1769682055,213348608,0.0,0.0,0.0,1.0,-0.0010102904634550214,0.0025744205340743065,0.007460991386324167,0.12375465780496597,0.08911856263875961,-0.007829055190086365 -1769682055,265400576,0.0,0.0,0.0,1.0,-0.0013857323210686445,0.002583960071206093,0.007915331982076168,-0.15834566950798035,-0.3019932806491852,0.014554583467543125 -1769682055,275572992,0.0,0.0,0.0,1.0,-0.0010895048035308719,0.0026830679271370173,0.008223552256822586,-0.12380053102970123,-0.0884673148393631,0.03640322387218475 -1769682055,316045824,0.0,0.0,0.0,1.0,-0.0009323335252702236,0.002602210035547614,0.008422184735536575,0.08916564285755157,-0.12259018421173096,0.06210436299443245 -1769682055,349820160,0.0,0.0,0.0,1.0,-0.0005230332026258111,0.002191648818552494,0.008532123640179634,0.08911792188882828,-0.12300992757081985,0.043040212243795395 -1769682055,386270720,0.0,0.0,0.0,1.0,-0.00047388969687744975,0.0018546951469033957,0.008541224524378777,-0.21296976506710052,0.035612769424915314,0.03980676084756851 -1769682055,414122240,0.0,0.0,0.0,1.0,-0.0002879306848626584,0.0017547656316310167,0.00855724886059761,-0.034852366894483566,-0.2127942144870758,0.010279026813805103 -1769682055,458215424,0.0,0.0,0.0,1.0,-0.0003892128588631749,0.0014379251515492797,0.008532088249921799,-5.139561835676432e-06,0.0006771145854145288,0.033371757715940475 -1769682055,480408064,0.0,0.0,0.0,1.0,-0.0009801844134926796,0.0010107076959684491,0.008495022542774677,-0.034986212849617004,-0.21214570105075836,0.04125555604696274 -1769682055,515834112,0.0,0.0,0.0,1.0,-0.0009568683453835547,0.0007460078340955079,0.008595796301960945,0.053910885006189346,-0.33660027384757996,0.018747031688690186 -1769682055,554648576,0.0,0.0,0.0,1.0,-0.000945927225984633,0.0004474168526940048,0.008834325708448887,-0.08890363574028015,0.12393885850906372,-0.004907466471195221 -1769682055,580162048,0.0,0.0,0.0,1.0,-0.0009260496008209884,0.0005233559058979154,0.009116494096815586,-0.07033178955316544,-0.42577651143074036,0.006186038255691528 -1769682055,613778432,0.0,0.0,0.0,1.0,-0.0027692890726029873,0.002235389780253172,0.009370225481688976,-0.035239361226558685,-0.21180137991905212,0.056707821786403656 -1769682055,665056000,0.0,0.0,0.0,1.0,-0.0016427922528237104,0.005296352319419384,0.009997586719691753,-2.540135756134987e-05,0.0011920833494514227,0.05959275737404823 -1769682055,675640320,0.0,0.0,0.0,1.0,-0.0016267253085970879,0.007207595743238926,0.010496914386749268,0.12411471456289291,0.0890413448214531,0.013799916952848434 -1769682055,714818304,0.0,0.0,0.0,1.0,-0.0016391478711739182,0.008252223022282124,0.01096153911203146,-0.2128790318965912,0.03586266562342644,0.02056710049510002 -1769682055,750262016,0.0,0.0,0.0,1.0,-0.0014551420463249087,0.00883547868579626,0.011487625539302826,0.12420681118965149,0.08842287212610245,-0.012339835986495018 -1769682055,780083456,0.0,0.0,0.0,1.0,-0.0015891711227595806,0.008970595896244049,0.011827506124973297,-0.24844104051589966,-0.1773262619972229,-0.003999472130089998 -1769682055,803663616,0.0,0.0,0.0,1.0,-0.0016111843287944794,0.008722878061234951,0.01199934259057045,0.12426063418388367,0.0883975476026535,-0.009894238784909248 -1769682055,849206016,0.0,0.0,0.0,1.0,-0.0025381946470588446,0.008835554122924805,0.01232939027249813,0.08852079510688782,-0.12448561191558838,-0.008099716156721115 -1769682055,881560064,0.0,0.0,0.0,1.0,-0.00284408638253808,0.00889401976019144,0.01248131413012743,0.052609559148550034,-0.3374064862728119,-0.01114999782294035 -1769682055,914262016,0.0,0.0,0.0,1.0,-0.003039818024262786,0.008961193263530731,0.01258939690887928,-0.21278850734233856,0.036063577979803085,0.004710999317467213 -1769682055,965416448,0.0,0.0,0.0,1.0,-0.0024908699560910463,0.008569247089326382,0.012778809294104576,-0.3011188805103302,0.1606038212776184,0.0043530636467039585 -1769682055,972596736,0.0,0.0,0.0,1.0,-0.001765857683494687,0.007929591462016106,0.012955959886312485,-0.12450504302978516,-0.08793691545724869,0.01919468864798546 -1769682056,14769408,0.0,0.0,0.0,1.0,-0.0017177100526168942,0.007545081432908773,0.013199344277381897,-0.0883060023188591,0.12482369691133499,0.016370467841625214 -1769682056,47250688,0.0,0.0,0.0,1.0,-0.0013299661222845316,0.007201101165264845,0.013553941622376442,-2.1761617972515523e-05,0.00011469861055957153,0.0059593250043690205 -1769682056,67680000,0.0,0.0,0.0,1.0,-0.0011900741374120116,0.007049776613712311,0.013761173002421856,0.08818026632070541,-0.12473355233669281,-0.007999076507985592 -1769682056,114263296,0.0,0.0,0.0,1.0,-0.0010184182319790125,0.007027802988886833,0.01417844370007515,0.08807870000600815,-0.12462259083986282,0.00036347040440887213 -1769682056,154793216,0.0,0.0,0.0,1.0,-0.0010160639649257064,0.0071298847906291485,0.014545135200023651,-0.2493443638086319,-0.17584611475467682,0.009437884204089642 -1769682056,180073984,0.0,0.0,0.0,1.0,-0.0008495349902659655,0.007189200725406408,0.014778872951865196,-0.08801131695508957,0.1249626949429512,0.012711982242763042 -1769682056,201247232,0.0,0.0,0.0,1.0,-0.0011574305826798081,0.0072720726020634174,0.014913193881511688,-0.21258628368377686,0.036634087562561035,-0.010041726753115654 -1769682056,251143936,0.0,0.0,0.0,1.0,-0.0011849808506667614,0.007506853900849819,0.015155612491071224,-0.1617327779531479,-0.30050644278526306,-0.0022480525076389313 -1769682056,280451584,0.0,0.0,0.0,1.0,-0.0032773830462247133,0.006120574194937944,0.015056627802550793,0.21208716928958893,-0.0352647490799427,0.09597239643335342 -1769682056,313719808,0.0,0.0,0.0,1.0,-0.0023192742373794317,0.0036719772033393383,0.01513079833239317,0.26238709688186646,-0.372062623500824,0.1383986920118332 -1769682056,359076352,0.0,0.0,0.0,1.0,-0.0011039169039577246,0.0015386452432721853,0.01538813952356577,-0.12555067241191864,-0.08543848246335983,0.11658217012882233 -1769682056,373337088,0.0,0.0,0.0,1.0,-0.0008587466436438262,0.0008868284057825804,0.015523586422204971,-0.2504834234714508,-0.1731364130973816,0.10920218378305435 -1769682056,414621952,0.0,0.0,0.0,1.0,-0.000296467769658193,0.00016464455984532833,0.015825685113668442,-0.12519928812980652,-0.08682676404714584,0.03671956807374954 -1769682056,452648704,0.0,0.0,0.0,1.0,0.00013495345774572343,0.00017485031276009977,0.01620790734887123,0.2124287337064743,-0.037433259189128876,0.011398745700716972 -1769682056,474314752,0.0,0.0,0.0,1.0,0.0003024832403752953,0.0002738355833571404,0.016531728208065033,-0.33763042092323303,-0.04941581189632416,0.011016100645065308 -1769682056,514769920,0.0,0.0,0.0,1.0,-0.00016778300050646067,0.000320804858347401,0.016737643629312515,0.21244314312934875,-0.0378233976662159,0.0018671909347176552 -1769682056,547510272,0.0,0.0,0.0,1.0,-0.0002914404321927577,0.0004898992483504117,0.01705789938569069,0.00018814468057826161,-0.000650097499601543,-0.03456409275531769 -1769682056,582110720,0.0,0.0,0.0,1.0,-0.0008746804087422788,0.0007029527914710343,0.017231401056051254,0.2615046501159668,-0.37589019536972046,-0.0034354091621935368 -1769682056,600484352,0.0,0.0,0.0,1.0,-0.0008750098058953881,0.0008059723768383265,0.017351321876049042,0.21248222887516022,-0.03848610445857048,-0.016002045944333076 -1769682056,649406720,0.0,0.0,0.0,1.0,-0.0016059016343206167,0.003190314630046487,0.017555277794599533,-0.00011244037887081504,0.00037875326233915985,0.020261740311980247 -1769682056,680296704,0.0,0.0,0.0,1.0,-0.0016484406078234315,0.00446052523329854,0.017639312893152237,-0.164001926779747,-0.2988273501396179,0.026105549186468124 -1769682056,715762176,0.0,0.0,0.0,1.0,-0.001991448225453496,0.005394017323851585,0.017675144597887993,-0.2895103394985199,-0.38593414425849915,0.009073360823094845 -1769682056,759163648,0.0,0.0,0.0,1.0,-0.0018831491470336914,0.005856143310666084,0.017691778019070625,0.173514723777771,-0.25071319937705994,0.017607592046260834 -1769682056,774487296,0.0,0.0,0.0,1.0,-0.0017089458415284753,0.006255302112549543,0.017699990421533585,0.13459676504135132,-0.463422954082489,0.0022422352340072393 -1769682056,815335680,0.0,0.0,0.0,1.0,-0.0017308053793385625,0.006172123830765486,0.017707131803035736,-0.42451798915863037,0.07798384130001068,0.001820241566747427 -1769682056,849694720,0.0,0.0,0.0,1.0,-0.0015404649311676621,0.005802363157272339,0.017768071964383125,0.17299818992614746,-0.25101059675216675,0.020058294758200645 -1769682056,869825536,0.0,0.0,0.0,1.0,-0.0014341744827106595,0.005909171421080828,0.017833609133958817,-0.12568844854831696,-0.08652588725090027,-0.0004494842141866684 -1769682056,915013888,0.0,0.0,0.0,1.0,-0.0017537862295284867,0.005802792496979237,0.01794445887207985,-0.12576168775558472,-0.0864710733294487,-0.0016769467620179057 -1769682056,950311424,0.0,0.0,0.0,1.0,-0.0018528526416048408,0.00569550646468997,0.01809586212038994,-0.3378334045410156,-0.04717952013015747,-0.019439920783042908 -1769682056,980088320,0.0,0.0,0.0,1.0,-0.0015623660292476416,0.005562669597566128,0.018223388120532036,-0.21201372146606445,0.03932541236281395,-0.0165688619017601 -1769682057,2164480,0.0,0.0,0.0,1.0,-0.0013074292801320553,0.005152685567736626,0.01829908788204193,-0.12604092061519623,-0.08586326986551285,0.01969991810619831 -1769682057,50532864,0.0,0.0,0.0,1.0,-0.0007838846649974585,0.004618651699274778,0.01851358264684677,0.2117937058210373,-0.03921185061335564,0.03809245675802231 -1769682057,83107328,0.0,0.0,0.0,1.0,-0.000906463828869164,0.004416930954903364,0.018639395013451576,-0.21218208968639374,0.04029905050992966,0.015514342114329338 -1769682057,114123520,0.0,0.0,0.0,1.0,-0.000995838432572782,0.004244474694132805,0.018740935251116753,-0.37824615836143494,-0.25781184434890747,0.004058151505887508 -1769682057,157167360,0.0,0.0,0.0,1.0,-0.0008129624184221029,0.004267110954970121,0.018801916390657425,-0.21211203932762146,0.04047263413667679,0.011885861866176128 -1769682057,174526464,0.0,0.0,0.0,1.0,-0.0007180061656981707,0.004120336379855871,0.018850507214665413,-0.2119864821434021,0.04041773080825806,-6.684986874461174e-05 -1769682057,214458112,0.0,0.0,0.0,1.0,-0.00044144035200588405,0.004180210642516613,0.018809910863637924,-0.21184565126895905,0.04028027504682541,-0.014395330101251602 -1769682057,249272832,0.0,0.0,0.0,1.0,-0.0009111297549679875,0.004335981793701649,0.018679911270737648,0.08562134951353073,-0.12629443407058716,0.0017943442799150944 -1769682057,270242304,0.0,0.0,0.0,1.0,-0.0010139874648302794,0.004394840449094772,0.018585175275802612,0.044996727257966995,-0.3386099934577942,-0.017392119392752647 -1769682057,314343936,0.0,0.0,0.0,1.0,-0.0011770258424803615,0.0026213533710688353,0.01833435148000717,0.04021815210580826,0.2133185863494873,0.07880152016878128 -1769682057,344763136,0.0,0.0,0.0,1.0,-0.000745354569517076,0.0014308338286355138,0.01821669563651085,0.12592792510986328,0.08647481352090836,0.059161487966775894 -1769682057,380600064,0.0,0.0,0.0,1.0,-0.0009488744544796646,0.00033787093707360327,0.0179994385689497,-0.04180514067411423,-0.21054163575172424,0.07373973727226257 -1769682057,400477184,0.0,0.0,0.0,1.0,-0.000677120522595942,0.00011228540824959055,0.017906665802001953,0.08505779504776001,-0.12608255445957184,0.026830827817320824 -1769682057,449866240,0.0,0.0,0.0,1.0,-0.0005733012221753597,-0.00013995886547490954,0.017664873972535133,0.21166060864925385,-0.0412098653614521,0.014486007392406464 -1769682057,480288256,0.0,0.0,0.0,1.0,-0.0002972037182189524,-0.00021251116413623095,0.01761762611567974,0.17021116614341736,-0.25334131717681885,0.0012086475035175681 -1769682057,513640960,0.0,0.0,0.0,1.0,-7.744230970274657e-05,-6.215247594809625e-06,0.017596159130334854,0.17002607882022858,-0.2533250153064728,0.007166936993598938 -1769682057,552159744,0.0,0.0,0.0,1.0,-0.00044186320155858994,0.0001921020884765312,0.01756877824664116,0.041873279958963394,0.21158617734909058,-0.008175746537744999 -1769682057,581444864,0.0,0.0,0.0,1.0,-0.0005100644193589687,0.00033120164880529046,0.017579885199666023,-0.12676502764225006,-0.08495617657899857,-0.004348458256572485 -1769682057,613709568,0.0,0.0,0.0,1.0,-0.00025838936562649906,0.0014405868714675307,0.017621206119656563,-0.42341548204421997,0.08429094403982162,0.009153894148766994 -1769682057,660426496,0.0,0.0,0.0,1.0,-0.0007370676612481475,0.0026899855583906174,0.017643461003899574,-0.08464960008859634,-0.4227070212364197,0.03420163691043854 -1769682057,668846592,0.0,0.0,0.0,1.0,-0.0007214259821921587,0.0031184684485197067,0.017630560323596,-0.21152792870998383,0.042094048112630844,-0.010947877541184425 -1769682057,715654144,0.0,0.0,0.0,1.0,-0.0008451623725704849,0.0037091702688485384,0.017517412081360817,-0.21177227795124054,0.04279289022088051,0.020012034103274345 -1769682057,750447360,0.0,0.0,0.0,1.0,-0.000898434198461473,0.003949496895074844,0.017239846289157867,-0.08515363931655884,-0.42304661870002747,0.006724540144205093 -1769682057,783156992,0.0,0.0,0.0,1.0,-0.0009978311136364937,0.0038876698818057775,0.01696927659213543,8.715147851034999e-05,-0.00016860890900716186,-0.009534860961139202 -1769682057,813944064,0.0,0.0,0.0,1.0,-0.0013618977973237634,0.003781951265409589,0.01665910892188549,0.04167039692401886,-0.3388071358203888,-0.005558636970818043 -1769682057,853365504,0.0,0.0,0.0,1.0,-0.0005630990490317345,0.00320503581315279,0.016297955065965652,0.00015636600437574089,-0.00029403751250356436,-0.016686175018548965 -1769682057,880767232,0.0,0.0,0.0,1.0,-0.0004254642117302865,0.002815943444147706,0.016096491366624832,-0.04292181879281998,-0.21164128184318542,-0.008601861074566841 -1769682057,917088768,0.0,0.0,0.0,1.0,4.3364838347770274e-05,0.002577900653705001,0.015937495976686478,-0.2955493628978729,0.17030726373195648,-0.00819764006882906 -1769682057,954927872,0.0,0.0,0.0,1.0,0.00046386459143832326,0.0023332941345870495,0.015953078866004944,-0.043088000267744064,-0.21171934902668,-0.015758642926812172 -1769682057,967955456,0.0,0.0,0.0,1.0,0.0008352013537660241,0.002211385639384389,0.016071267426013947,-0.12746550142765045,-0.0838460773229599,0.010981115512549877 -1769682058,14430976,0.0,0.0,0.0,1.0,0.001504047540947795,0.002091890899464488,0.016388431191444397,0.29516878724098206,-0.1705920249223709,0.019005054607987404 -1769682058,63295488,0.0,0.0,0.0,1.0,0.0017024963162839413,0.0018874058732762933,0.016697244718670845,-0.29859715700149536,-0.3789840042591095,0.007389415521174669 -1769682058,70527232,0.0,0.0,0.0,1.0,0.0012420008424669504,0.0018786274595186114,0.01677042618393898,4.680913843913004e-05,-8.486626029480249e-05,-0.004767389502376318 -1769682058,114053376,0.0,0.0,0.0,1.0,0.0013392185792326927,0.0018767775036394596,0.016816608607769012,-0.0437953844666481,-0.21133123338222504,-0.0002351836592424661 -1769682058,148743936,0.0,0.0,0.0,1.0,0.0008279446046799421,0.001941298833116889,0.01664564199745655,-0.171715646982193,-0.29465705156326294,0.01668545976281166 -1769682058,180868352,0.0,0.0,0.0,1.0,0.0007572102476842701,0.001896000001579523,0.016376225277781487,-0.00017866208509076387,0.00032067380379885435,0.01787782460451126 -1769682058,214981376,0.0,0.0,0.0,1.0,0.00045735284220427275,0.0019142216769978404,0.016007982194423676,-0.21113820374011993,0.044008102267980576,-0.010065159760415554 -1769682058,249071872,0.0,0.0,0.0,1.0,-0.0003939501475542784,0.0013694704975932837,0.015368036925792694,0.2944490611553192,-0.17168651521205902,0.022748978808522224 -1769682058,280862208,0.0,0.0,0.0,1.0,-0.0006666785920970142,7.426064985338598e-05,0.014910079538822174,0.29404598474502563,-0.1712426245212555,0.054929811507463455 -1769682058,315730176,0.0,0.0,0.0,1.0,-0.0008409741567447782,-0.0009659371571615338,0.014501743949949741,0.04418746009469032,0.21168296039104462,0.027652177959680557 -1769682058,354619136,0.0,0.0,0.0,1.0,-0.0010454908479005098,-0.0017522587440907955,0.013998478651046753,0.0828913077712059,-0.1271996647119522,0.03887612745165825 -1769682058,381903360,0.0,0.0,0.0,1.0,-0.0006985495565459132,-0.002126652980223298,0.013756955973803997,0.21099264919757843,-0.04447255656123161,0.013623163104057312 -1769682058,413780736,0.0,0.0,0.0,1.0,-0.000225231604417786,-0.0022411097306758165,0.013647293671965599,0.08319103717803955,-0.12799344956874847,-0.0016616464126855135 -1769682058,461575424,0.0,0.0,0.0,1.0,0.0002676042204257101,-0.002048788359388709,0.013784939423203468,0.0828530490398407,-0.1275491714477539,0.025742726400494576 -1769682058,470371840,0.0,0.0,0.0,1.0,0.0004226326127536595,-0.000916944001801312,0.013965246267616749,-0.04528048634529114,-0.21045319736003876,0.035514868795871735 -1769682058,513759744,0.0,0.0,0.0,1.0,0.0008970591006800532,0.0011860399972647429,0.014541435055434704,-0.1731996387243271,-0.29387396574020386,0.009539255872368813 -1769682058,553492480,0.0,0.0,0.0,1.0,0.0014587340410798788,0.0026796390302479267,0.01504240557551384,-0.04503845050930977,-0.2112969160079956,-0.014529149979352951 -1769682058,585112064,0.0,0.0,0.0,1.0,0.0014471916947513819,0.0032946583814918995,0.015288086608052254,0.12821140885353088,0.08271457254886627,-0.007375016342848539 -1769682058,614399232,0.0,0.0,0.0,1.0,0.0014101304113864899,0.003565039485692978,0.015453329309821129,0.1284172683954239,0.08235356956720352,-0.024050522595643997 -1769682058,652224768,0.0,0.0,0.0,1.0,0.0012370155891403556,0.003828194458037615,0.015612216666340828,0.0371863953769207,-0.3391706943511963,0.0029473700560629368 -1769682058,680232960,0.0,0.0,0.0,1.0,0.0020460220985114574,0.003219467820599675,0.015728145837783813,0.16547872126102448,-0.25686895847320557,-0.015098290517926216 -1769682058,719530240,0.0,0.0,0.0,1.0,0.0027616331353783607,0.0025080502964556217,0.01583080179989338,-0.08218758553266525,0.12760362029075623,-0.04014074429869652 -1769682058,758379520,0.0,0.0,0.0,1.0,0.0027813659980893135,0.0018801202531903982,0.015836643055081367,0.119272880256176,-0.4677996039390564,-0.006855648942291737 -1769682058,781555968,0.0,0.0,0.0,1.0,0.0027192342095077038,0.0013771469239145517,0.01568453200161457,-0.2107265591621399,0.045751769095659256,-0.012579260393977165 -1769682058,814852864,0.0,0.0,0.0,1.0,0.002765753073617816,0.0012280186638236046,0.015425785444676876,0.2107296735048294,-0.04589298740029335,0.010207547806203365 -1769682058,857315072,0.0,0.0,0.0,1.0,0.0028139157220721245,0.0011226818896830082,0.015099390409886837,0.08222011476755142,-0.1282888650894165,0.011599574238061905 -1769682058,874686976,0.0,0.0,0.0,1.0,0.0025665818247944117,0.0012323992559686303,0.014608283527195454,-0.2106180638074875,0.04600009322166443,-0.016191719099879265 -1769682058,914231808,0.0,0.0,0.0,1.0,0.0018314005574211478,0.0015329279704019427,0.014201980084180832,0.03587993234395981,-0.33940425515174866,-0.001580211566761136 -1769682058,948916992,0.0,0.0,0.0,1.0,0.0018988732481375337,0.0018854025984182954,0.013689721934497356,0.03562834486365318,-0.3393115997314453,0.004408061504364014 -1769682058,980824576,0.0,0.0,0.0,1.0,0.0015180469490587711,0.0022838287986814976,0.013203242793679237,-0.04649706557393074,-0.2108326107263565,-0.004844240844249725 -1769682059,1709568,0.0,0.0,0.0,1.0,0.0014880483504384756,0.002386012114584446,0.012915515340864658,-0.08177649229764938,0.12819704413414001,-0.025965964421629906 -1769682059,47930368,0.0,0.0,0.0,1.0,0.0003961628535762429,0.0017199880676344037,0.011979416012763977,0.00012864753080066293,-0.00022706150775775313,-0.011918080039322376 -1769682059,80668160,0.0,0.0,0.0,1.0,-0.00022263036225922406,0.001365813659504056,0.01142103597521782,-0.1637493073940277,0.2573445439338684,-0.01025392021983862 -1769682059,113809152,0.0,0.0,0.0,1.0,-0.00022840739984530956,0.000885175250004977,0.01093918364495039,0.30404630303382874,0.3750404417514801,0.03312312811613083 -1769682059,154386688,0.0,0.0,0.0,1.0,-0.0003334606590215117,-0.001273023197427392,0.010375462472438812,-0.04774010181427002,-0.20928813517093658,0.07143298536539078 -1769682059,181639168,0.0,0.0,0.0,1.0,-0.0006693886825814843,-0.0023949879687279463,0.010025708004832268,0.08103912323713303,-0.127523735165596,0.07007136195898056 -1769682059,214520576,0.0,0.0,0.0,1.0,-0.0008247633231803775,-0.0032414577435702085,0.009723425842821598,-0.09466658532619476,-0.4203823506832123,0.045131754130125046 -1769682059,248932608,0.0,0.0,0.0,1.0,-0.0008097885292954743,-0.003538548480719328,0.009361996315419674,0.37363186478614807,-0.30438369512557983,0.03474850952625275 -1769682059,270533888,0.0,0.0,0.0,1.0,-0.0004213284410070628,-0.0032391431741416454,0.009212914854288101,0.2574056088924408,0.16402697563171387,0.036545269191265106 -1769682059,314096640,0.0,0.0,0.0,1.0,-0.0008129141642712057,-0.0019597108475863934,0.008868766948580742,0.04715081304311752,0.21082593500614166,0.01318896934390068 -1769682059,348458496,0.0,0.0,0.0,1.0,0.0002168770442949608,-0.0004750463995151222,0.00867409072816372,-0.08138500154018402,0.1286056935787201,-0.01996707357466221 -1769682059,381685248,0.0,0.0,0.0,1.0,0.0009925743797793984,0.0003998007159680128,0.008530573919415474,-0.25770413875579834,-0.16352908313274384,-0.02340182662010193 -1769682059,400045824,0.0,0.0,0.0,1.0,0.00106512859929353,0.0009436281397938728,0.008436591364443302,-0.0812067911028862,0.1284133940935135,-0.0318920724093914 -1769682059,450987520,0.0,0.0,0.0,1.0,0.0015107940416783094,0.0017963267164304852,0.008160475641489029,0.08159680664539337,-0.1292622834444046,-0.0109979547560215 -1769682059,480444160,0.0,0.0,0.0,1.0,0.0026546332519501448,0.0015050959773361683,0.0079727154225111,-0.17631879448890686,-0.2925122380256653,-0.029629578813910484 -1769682059,513807616,0.0,0.0,0.0,1.0,0.003449380863457918,0.000997621682472527,0.0077728936448693275,-0.03336289897561073,0.3388162851333618,-0.04024993255734444 -1769682059,561808128,0.0,0.0,0.0,1.0,0.0037668661680072546,0.00040550241828896105,0.007474076934158802,0.25827157497406006,0.16254077851772308,-0.009980950504541397 -1769682059,573019392,0.0,0.0,0.0,1.0,0.0036575186531990767,0.0002630990347824991,0.007280812133103609,0.1292726695537567,0.0810193121433258,-0.016913866624236107 -1769682059,600102144,0.0,0.0,0.0,1.0,0.004064089618623257,-3.101408947259188e-05,0.006963970139622688,-0.08116364479064941,0.1288241446018219,-0.01648792438209057 -1769682059,660941056,0.0,0.0,0.0,1.0,0.004154169466346502,-0.00037787764449603856,0.006424191873520613,-0.08128314465284348,0.12915413081645966,-0.0010199191747233272 -1769682059,668027904,0.0,0.0,0.0,1.0,0.004262794740498066,-0.0004511668812483549,0.00619947724044323,0.08124209940433502,-0.12911687791347504,0.003413424827158451 -1769682059,714522624,0.0,0.0,0.0,1.0,0.003092473605647683,0.00018121357425116003,0.005722050555050373,0.09616830199956894,0.4202479124069214,-0.031249133870005608 -1769682059,748706048,0.0,0.0,0.0,1.0,0.0023955772630870342,0.0008693862473592162,0.005260375328361988,-0.21014806628227234,0.04752277210354805,-0.024617156013846397 -1769682059,784193024,0.0,0.0,0.0,1.0,0.0022129116114228964,0.0011254395358264446,0.004938317462801933,8.751475979806855e-05,-0.00016834892448969185,-0.008342497982084751 -1769682059,814369792,0.0,0.0,0.0,1.0,0.0023886235430836678,0.0014342612121254206,0.004663421772420406,0.12943871319293976,0.0807262659072876,-0.021735386922955513 -1769682059,849370880,0.0,0.0,0.0,1.0,0.0006039871950633824,0.0009021701407618821,0.004150988534092903,0.2916361093521118,-0.17755652964115143,-0.008814974687993526 -1769682059,880882688,0.0,0.0,0.0,1.0,0.00010754257527878508,0.00045347039122134447,0.0038328319787979126,-0.08113263547420502,0.12924808263778687,-0.0010988616850227118 -1769682059,918271232,0.0,0.0,0.0,1.0,0.00013777977437712252,0.00030604220228269696,0.0035569299943745136,-0.08109325915575027,0.1292085498571396,-0.003483280772343278 -1769682059,951097856,0.0,0.0,0.0,1.0,-0.0004823826893698424,-0.0010473837610334158,0.003294693771749735,0.5010849833488464,-0.22421793639659882,0.07185442000627518 -1769682059,982163200,0.0,0.0,0.0,1.0,-0.0005588184576481581,-0.002121306024491787,0.0031291835475713015,0.12883810698986053,0.08190140128135681,0.04023400694131851 -1769682060,14583040,0.0,0.0,0.0,1.0,-0.0007103110547177494,-0.0027366667054593563,0.0029438615310937166,0.3392467796802521,0.03357641026377678,0.03624722734093666 -1769682060,64837120,0.0,0.0,0.0,1.0,-0.0008805629331618547,-0.00319582037627697,0.0027429726906120777,0.08080455660820007,-0.12878552079200745,0.02609640173614025 -1769682060,73305344,0.0,0.0,0.0,1.0,-0.0006945420755073428,-0.0033223116770386696,0.0026060009840875864,0.3392855226993561,0.03346121683716774,0.03379061445593834 -1769682060,115079168,0.0,0.0,0.0,1.0,-0.0006959058227948844,-0.0030579897575080395,0.00245838169939816,0.12919653952121735,0.08122541010379791,0.009205072186887264 -1769682060,148312832,0.0,0.0,0.0,1.0,9.515765123069286e-05,-0.0020896559581160545,0.0023902871180325747,-0.04805540293455124,-0.21076621115207672,-0.020072583109140396 -1769682060,187371264,0.0,0.0,0.0,1.0,0.000545112940017134,-0.001339718233793974,0.0023538852110505104,-0.2583042085170746,-0.16264860332012177,-0.030288618057966232 -1769682060,214828032,0.0,0.0,0.0,1.0,0.0010216532973572612,-0.0008465350838378072,0.002296419581398368,0.08134382963180542,-0.12999960780143738,-0.032332055270671844 -1769682060,250360064,0.0,0.0,0.0,1.0,0.0017217485001310706,-0.00035258711432106793,0.002198218833655119,0.12956734001636505,0.08048243820667267,-0.025390611961483955 -1769682060,280790528,0.0,0.0,0.0,1.0,0.002644045278429985,-0.0005671128164976835,0.0021058605052530766,0.12950141727924347,0.08061815053224564,-0.018246661871671677 -1769682060,320055808,0.0,0.0,0.0,1.0,0.0026178418193012476,-0.0007178718806244433,0.0020041433162987232,0.03273402526974678,-0.3398514986038208,-0.007038073148578405 -1769682060,347613696,0.0,0.0,0.0,1.0,0.0031376592814922333,-0.0009758088272064924,0.0018873251974582672,0.12940452992916107,0.08081991970539093,-0.007540523540228605 -1769682060,381369600,0.0,0.0,0.0,1.0,0.003416679799556732,-0.0013738332781940699,0.0017167720943689346,-0.08087469637393951,0.12915432453155518,-0.010615982115268707 -1769682060,413751040,0.0,0.0,0.0,1.0,0.0037529950495809317,-0.0015266493428498507,0.0015668915584683418,-0.048393670469522476,-0.2102815955877304,0.002704667393118143 -1769682060,464611328,0.0,0.0,0.0,1.0,0.0035811131820082664,-0.0015891115181148052,0.0013316847616806626,0.04823241010308266,0.2106524109840393,0.015139021910727024 -1769682060,472744192,0.0,0.0,0.0,1.0,0.0032721126917749643,-0.0016080327332019806,0.0011224339250475168,-0.04842442274093628,-0.2102513462305069,0.0039541833102703094 -1769682060,514870528,0.0,0.0,0.0,1.0,0.002521154936403036,-0.0011255107820034027,0.0008959126425907016,0.4691215455532074,0.1131892204284668,-0.012196687050163746 -1769682060,548708608,0.0,0.0,0.0,1.0,0.002091745613142848,-0.0005218461155891418,0.0005960133858025074,0.2914234399795532,-0.1782063990831375,-0.01728513278067112 -1769682060,586947840,0.0,0.0,0.0,1.0,0.0019161226227879524,-0.0003160869237035513,0.00041368004167452455,-0.12917491793632507,-0.08133475482463837,-0.018584782257676125 -1769682060,615323136,0.0,0.0,0.0,1.0,0.0015445390017703176,-9.031474473886192e-05,0.00021958467550575733,0.2913053631782532,-0.17796102166175842,-0.005352922715246677 -1769682060,652421120,0.0,0.0,0.0,1.0,0.0004978313227184117,-0.0004253908118698746,-5.696468724636361e-05,-0.12922148406505585,-0.08123332262039185,-0.013809050433337688 -1769682060,680637952,0.0,0.0,0.0,1.0,0.00040468820952810347,-0.0007562488317489624,-0.00017833935271482915,0.12942557036876678,0.08077632635831833,-0.007646225392818451 -1769682060,717394944,0.0,0.0,0.0,1.0,-1.0120114893652499e-05,-0.0009353045024909079,-0.00025617374922148883,-0.08087313920259476,0.12921521067619324,-0.008294660598039627 -1769682060,762277120,0.0,0.0,0.0,1.0,-7.972696766955778e-05,-0.0013477711472660303,-0.00028074890724383295,-0.12958110868930817,-0.08042257279157639,0.024340834468603134 -1769682060,767685376,0.0,0.0,0.0,1.0,-0.0004195499059278518,-0.0015798198292031884,-0.00030608312226831913,0.21006321907043457,-0.04790046438574791,0.025655321776866913 -1769682060,815366656,0.0,0.0,0.0,1.0,-0.00034603537642396986,-0.0019069950794801116,-0.00033662255736999214,0.2587645351886749,0.16174031794071198,-0.006993877701461315 -1769682060,859237376,0.0,0.0,0.0,1.0,-0.00046857880079187453,-0.0021375096403062344,-0.000381422316422686,0.03251875936985016,-0.33961325883865356,0.005151825957000256 -1769682060,868052992,0.0,0.0,0.0,1.0,-0.0005867657600902021,-0.0021053545642644167,-0.00041095897904597223,-4.393140989122912e-05,0.00010150760499527678,0.004767091944813728 -1769682060,917038080,0.0,0.0,0.0,1.0,-0.0005936556844972074,-0.002675713738426566,-0.000520365487318486,0.12945960462093353,0.08068569004535675,-0.012459320947527885 -1769682060,950456832,0.0,0.0,0.0,1.0,-2.0251492969691753e-05,-0.003132438752800226,-0.0005505867302417755,-0.048073504120111465,-0.2110620141029358,-0.03410498425364494 -1769682060,980120064,0.0,0.0,0.0,1.0,0.00010271435166941956,-0.0030319951474666595,-0.000563410168979317,0.08127490431070328,-0.13011913001537323,-0.03466539829969406 -1769682061,14194688,0.0,0.0,0.0,1.0,0.00047630572225898504,-0.003077880246564746,-0.0006390282069332898,-2.1019095584051684e-05,5.06920441694092e-05,0.0023835559841245413 -1769682061,51581440,0.0,0.0,0.0,1.0,0.0009217383340001106,-0.0028476864099502563,-0.0007091188454069197,0.04847496375441551,0.21007674932479858,-0.012400186620652676 -1769682061,81461504,0.0,0.0,0.0,1.0,0.0015014938544481993,-0.0028687170706689358,-0.0007620920659974217,0.33973121643066406,0.03234916925430298,-0.00968707725405693 -1769682061,116055040,0.0,0.0,0.0,1.0,0.0016450159018859267,-0.002852728823199868,-0.0007993134786374867,-0.08080555498600006,0.12894359230995178,-0.020140619948506355 -1769682061,156891648,0.0,0.0,0.0,1.0,0.0017402784433215857,-0.002961917780339718,-0.0008616158156655729,-0.21032997965812683,0.04843951761722565,0.0019604077097028494 -1769682061,180825344,0.0,0.0,0.0,1.0,0.002000813838094473,-0.0029456026386469603,-0.0008893409394659102,0.339517205953598,0.032914113253355026,0.015236340463161469 -1769682061,215247872,0.0,0.0,0.0,1.0,0.0020457454957067966,-0.0029122987762093544,-0.0009525373461656272,-0.2104010432958603,0.04860824719071388,0.010333985090255737 -1769682061,263165184,0.0,0.0,0.0,1.0,0.0018726371927186847,-0.0029484762344509363,-0.0010077048791572452,-0.04834432899951935,-0.21031297743320465,0.0017761059571057558 -1769682061,270800896,0.0,0.0,0.0,1.0,0.002079316880553961,-0.002946802880614996,-0.001028218655847013,-0.04835915192961693,-0.21026217937469482,0.004170953296124935 -1769682061,314232576,0.0,0.0,0.0,1.0,0.0012976605212315917,-0.0024519406724721193,-0.0010973131284117699,-0.12920089066028595,-0.08131738007068634,-0.014760499820113182 -1769682061,349272320,0.0,0.0,0.0,1.0,0.0011106072925031185,-0.0021762242540717125,-0.0011550579220056534,-0.12921731173992157,-0.0812719464302063,-0.012361424043774605 -1769682061,384457472,0.0,0.0,0.0,1.0,0.0007243867730721831,-0.00200904393568635,-0.0011911875335499644,-0.08075295388698578,0.12862658500671387,-0.033248066902160645 -1769682061,415211776,0.0,0.0,0.0,1.0,0.0005640253075398505,-0.0019026591908186674,-0.0012093046680092812,-0.04823180288076401,-0.2105296105146408,-0.007699227426201105 -1769682061,448083712,0.0,0.0,0.0,1.0,0.00024207441310863942,-0.00199886504560709,-0.0012643506051972508,0.1619393676519394,-0.2583833336830139,0.014044279232621193 -1769682061,481067520,0.0,0.0,0.0,1.0,-7.568592263851315e-05,-0.0020745624788105488,-0.001299968222156167,-0.12906236946582794,-0.08171019703149796,-0.03139132633805275 -1769682061,516333312,0.0,0.0,0.0,1.0,0.00010063051013275981,-0.0020393042359501123,-0.0013078521005809307,0.048368435353040695,0.2100670039653778,-0.013765670359134674 -1769682061,556000512,0.0,0.0,0.0,1.0,-0.0005109055200591683,-0.00213174382224679,-0.0013410730753093958,-0.04821380600333214,-0.2104862928390503,-0.0052999272011220455 -1769682061,582216448,0.0,0.0,0.0,1.0,-0.0005157927516847849,-0.001514230971224606,-0.0013650222681462765,0.04842634126543999,0.2098376601934433,-0.024493539705872536 -1769682061,614109440,0.0,0.0,0.0,1.0,-0.00047303776955232024,-0.0010903187794610858,-0.0013899686746299267,0.12940724194049835,0.08069127798080444,-0.01630781590938568 -1769682061,665623040,0.0,0.0,0.0,1.0,-0.0002737698960117996,-0.0006020579021424055,-0.0014584368327632546,0.08111194521188736,-0.12948201596736908,-0.007312076166272163 -1769682061,673529600,0.0,0.0,0.0,1.0,-0.00024236160970758647,-0.00025269342586398125,-0.0015374644426628947,0.3397919535636902,0.03229513019323349,-0.02325146272778511 -1769682061,717522432,0.0,0.0,0.0,1.0,-0.0009363595745526254,-0.0006061416934244335,-0.0016687805764377117,0.00033181352773681283,-0.000986238126643002,-0.0452876091003418 -1769682061,764879104,0.0,0.0,0.0,1.0,-0.00047163551789708436,-0.0028279752004891634,-0.0017526170704513788,0.3398723006248474,0.032077107578516006,-0.03519976884126663 -1769682061,784994816,0.0,0.0,0.0,1.0,-0.00037021012394689023,-0.004101376049220562,-0.001821899670176208,0.00014455438940785825,-0.00044040154898539186,-0.020260289311408997 -1769682061,803153408,0.0,0.0,0.0,1.0,0.00013328046770766377,-0.005058190319687128,-0.0018916537519544363,0.2587151527404785,0.16157445311546326,-0.027934951707720757 -1769682061,848583168,0.0,0.0,0.0,1.0,0.00017203927563969046,-0.005614106543362141,-0.0019952075090259314,0.3396153450012207,0.03289277106523514,-0.0007980223745107651 -1769682061,881242112,0.0,0.0,0.0,1.0,-9.38472840061877e-06,-0.005686434451490641,-0.002023673616349697,-0.08115184307098389,0.1294221729040146,0.006190600339323282 -1769682061,915871488,0.0,0.0,0.0,1.0,-5.442504698294215e-05,-0.005667218007147312,-0.002075585536658764,-0.08112040907144547,0.12928767502307892,0.00024559651501476765 -1769682061,951442688,0.0,0.0,0.0,1.0,-1.419664840796031e-05,-0.00535236019641161,-0.0021026625763624907,-0.00011126237222924829,0.0003883764729835093,0.017876839265227318 -1769682061,980891904,0.0,0.0,0.0,1.0,5.8524779888102785e-05,-0.005114479921758175,-0.0021336665377020836,0.4687630832195282,0.11438620090484619,0.011091707274317741 -1769682062,15422720,0.0,0.0,0.0,1.0,4.082397936144844e-05,-0.004943062551319599,-0.002161799930036068,-0.0001622918643988669,0.000595437886659056,0.027411209419369698 -1769682062,47631360,0.0,0.0,0.0,1.0,-0.00013856809528078884,-0.004865480121225119,-0.0021664644591510296,0.08105966448783875,-0.12890280783176422,0.01638433337211609 -1769682062,82777856,0.0,0.0,0.0,1.0,3.818779805442318e-05,-0.004688176326453686,-0.002121174708008766,-0.17733724415302277,-0.2912890911102295,0.013684878125786781 -1769682062,114428416,0.0,0.0,0.0,1.0,-0.00018469311180524528,-0.004535980056971312,-0.002111992798745632,0.08111678808927536,-0.129020094871521,0.010398983024060726 -1769682062,147495680,0.0,0.0,0.0,1.0,-0.0004521500668488443,-0.004350882489234209,-0.002041808096691966,-0.12918151915073395,-0.081267349421978,-0.0036867123562842607 -1769682062,170418432,0.0,0.0,0.0,1.0,-0.00027051701908931136,-0.004313322715461254,-0.001995912054553628,-2.4738721549510956e-05,0.00010347097850171849,0.004767187405377626 -1769682062,214727424,0.0,0.0,0.0,1.0,-9.57758747972548e-05,-0.0042640650644898415,-0.0019100909121334553,-0.21035002171993256,0.047850705683231354,-0.008055860176682472 -1769682062,260874240,0.0,0.0,0.0,1.0,-0.0004897692706435919,-0.004249386489391327,-0.0018440485000610352,-0.08119921386241913,0.12917892634868622,-0.0020018049981445074 -1769682062,270494976,0.0,0.0,0.0,1.0,-0.0003419428539928049,-0.004216545727103949,-0.0018211358692497015,-0.03316967189311981,0.3393131494522095,-0.015857914462685585 -1769682062,306459904,0.0,0.0,0.0,1.0,-0.00023594064987264574,-0.004096328746527433,-0.0017697628354653716,0.04791844263672829,0.21060539782047272,0.007582669146358967 -1769682062,350722816,0.0,0.0,0.0,1.0,-0.00032450686558149755,-0.004113087896257639,-0.0017959977267310023,0.08125490695238113,-0.12931925058364868,-0.005186930298805237 -1769682062,381076992,0.0,0.0,0.0,1.0,-0.0010422051418572664,-0.003462578170001507,-0.0018742054235190153,-0.04762088879942894,-0.2119774967432022,-0.07074110954999924 -1769682062,420088320,0.0,0.0,0.0,1.0,-0.00037932663690298796,-0.0016415145946666598,-0.0019211015896871686,0.08166411519050598,-0.13131938874721527,-0.09816641360521317 -1769682062,458150912,0.0,0.0,0.0,1.0,9.187040996039286e-05,0.0002528869081288576,-0.0019881478510797024,0.2586175501346588,0.16095426678657532,-0.07273154705762863 -1769682062,481500672,0.0,0.0,0.0,1.0,-0.00017942997510544956,0.0010979862418025732,-0.002023184671998024,-0.25805529952049255,-0.1637764275074005,-0.05718258395791054 -1769682062,514173696,0.0,0.0,0.0,1.0,-1.9988867279607803e-05,0.0015551599208265543,-0.0020392362494021654,-0.17683550715446472,-0.29264816641807556,-0.04213649779558182 -1769682062,565570304,0.0,0.0,0.0,1.0,-6.538226443808526e-05,0.0017389842541888356,-0.0020699575543403625,-0.12907016277313232,-0.08162355422973633,-0.015496155247092247 -1769682062,576015616,0.0,0.0,0.0,1.0,-0.0006319154053926468,-0.00023371496354229748,-0.0021285463590174913,0.29195499420166016,-0.1782173365354538,-0.054489005357027054 -1769682062,614705664,0.0,0.0,0.0,1.0,-0.0005339134950190783,-0.002892144490033388,-0.002106931759044528,-0.08110467344522476,0.12819723784923553,-0.04484898969531059 -1769682062,651247360,0.0,0.0,0.0,1.0,-0.0005175728583708405,-0.005654257256537676,-0.0020722923800349236,0.4209694564342499,-0.09624025970697403,-0.02599007822573185 -1769682062,688560384,0.0,0.0,0.0,1.0,-0.0008927796152420342,-0.006883062422275543,-0.0020179764833301306,0.21048276126384735,-0.04809414595365524,-0.01244142185896635 -1769682062,714757120,0.0,0.0,0.0,1.0,-0.000686143699567765,-0.007642962504178286,-0.001978344516828656,0.12907099723815918,0.08156225085258484,0.010653024539351463 -1769682062,752143616,0.0,0.0,0.0,1.0,-0.0014082624111324549,-0.007564800791442394,-0.0018993940902873874,-0.00010635479702614248,0.0006647866684943438,0.030987124890089035 -1769682062,781166592,0.0,0.0,0.0,1.0,-0.0012318426743149757,-0.0071851215325295925,-0.0018401724519208074,-0.08137869834899902,0.12937574088573456,0.011276469565927982 -1769682062,817372416,0.0,0.0,0.0,1.0,-0.0016242752317339182,-0.006837255787104368,-0.0017740190960466862,0.033488236367702484,-0.33879876136779785,0.03834163397550583 -1769682062,854668032,0.0,0.0,0.0,1.0,-0.001699381391517818,-0.006322749424725771,-0.0016813596012070775,0.21042373776435852,-0.04756803438067436,0.008745616301894188 -1769682062,881362688,0.0,0.0,0.0,1.0,-0.001587543054483831,-0.0059942337684333324,-0.0016331642400473356,0.12906767427921295,0.08152320235967636,0.006944774650037289 -1769682062,914379264,0.0,0.0,0.0,1.0,-0.0018615989247336984,-0.005815146490931511,-0.001545313629321754,0.1627071052789688,-0.25792762637138367,0.014204446226358414 -1769682062,960131840,0.0,0.0,0.0,1.0,-0.0014949798351153731,-0.005789256654679775,-0.0014559444971382618,0.0813487321138382,-0.12882079184055328,0.013630674220621586 -1769682062,970407168,0.0,0.0,0.0,1.0,-0.0013841288164258003,-0.005675298627465963,-0.0014079082757234573,0.21045571565628052,-0.0477069690823555,0.0002459166571497917 -1769682063,14358528,0.0,0.0,0.0,1.0,-0.0010385969653725624,-0.0057938056997954845,-0.001304789213463664,-0.08138349652290344,0.12904112040996552,-0.0028655254282057285 -1769682063,54328320,0.0,0.0,0.0,1.0,-0.0014172886731103063,-0.005889187101274729,-0.0012083083856850863,-1.8902283045463264e-05,0.00025029698736034334,0.011918294243514538 -1769682063,83657472,0.0,0.0,0.0,1.0,-0.0012333136983215809,-0.005828579887747765,-0.0011629867367446423,0.047654278576374054,0.210641011595726,0.006382617633789778 -1769682063,115326208,0.0,0.0,0.0,1.0,-0.0012962346663698554,-0.005850664339959621,-0.0011194022372364998,-0.1290590763092041,-0.08143604546785355,-0.0008402204839512706 -1769682063,150501376,0.0,0.0,0.0,1.0,-0.0009619523189030588,-0.005815938115119934,-0.0010508728446438909,0.08141044527292252,-0.12910300493240356,-0.0008002594113349915 -1769682063,180758272,0.0,0.0,0.0,1.0,-0.000621666491497308,-0.00556657649576664,-0.0009737665532156825,-0.04764818772673607,-0.210322305560112,0.009116144850850105 -1769682063,217250304,0.0,0.0,0.0,1.0,-0.0005688997334800661,-0.0054891593754291534,-0.0009091407991945744,0.04761768877506256,0.2110441029071808,0.02544243447482586 -1769682063,254007808,0.0,0.0,0.0,1.0,-0.0006938702426850796,-0.003379658330231905,-0.000936869066208601,-0.08134584128856659,0.12584540247917175,-0.15528033673763275 -1769682063,283529728,0.0,0.0,0.0,1.0,-0.00018356683722231537,-0.0006859528948552907,-0.0009075103444047272,0.33957427740097046,0.031192749738693237,-0.12569519877433777 -1769682063,314435840,0.0,0.0,0.0,1.0,-1.324979166383855e-05,0.0011416046181693673,-0.0008912310586310923,-0.16280891001224518,0.2559497058391571,-0.10555881261825562 -1769682063,358909440,0.0,0.0,0.0,1.0,0.00011326731328153983,0.0023810239508748055,-0.0008754637674428523,0.04766150563955307,0.20846949517726898,-0.09850915521383286 -1769682063,368221184,0.0,0.0,0.0,1.0,0.00030848640017211437,0.0030823717825114727,-0.0008884347043931484,-0.047587230801582336,-0.21110005676746368,-0.027827883139252663 -1769682063,414724352,0.0,0.0,0.0,1.0,-0.00015582946070935577,0.003242019098252058,-0.0009598663891665637,0.08144021779298782,-0.12905867397785187,0.00036314886528998613 -1769682063,448334080,0.0,0.0,0.0,1.0,-0.0005901078693568707,0.002646882552653551,-0.0010520867072045803,-3.485253546386957e-05,0.0008430797606706619,0.04052240028977394 -1769682063,481045760,0.0,0.0,0.0,1.0,-0.0007210648036561906,0.0020228922367095947,-0.0010980915976688266,-0.17664411664009094,-0.2912732660770416,0.03450765833258629 -1769682063,501830144,0.0,0.0,0.0,1.0,-0.0008526078308932483,0.0014996356330811977,-0.001114723621867597,0.08141471445560455,-0.1282339245080948,0.03970479220151901 -1769682063,544813056,0.0,0.0,0.0,1.0,-0.0010856916196644306,0.0001867518585640937,-0.0011364687234163284,-3.1876348657533526e-05,0.0006672384915873408,0.03217959776520729 -1769682063,581277952,0.0,0.0,0.0,1.0,-0.00109388108830899,-0.0007873136200942099,-0.0011296954471617937,0.08145029842853546,-0.12874753773212433,0.014666961506009102 -1769682063,599037952,0.0,0.0,0.0,1.0,-0.000998354167677462,-0.0010801621247082949,-0.0010995051125064492,0.16290462017059326,-0.2574429214000702,0.03170841932296753 -1769682063,644664832,0.0,0.0,0.0,1.0,-0.0011972303036600351,-0.0014764845836907625,-0.0010267930338159204,-0.16294728219509125,0.2581257224082947,0.001683324109762907 -1769682063,681632256,0.0,0.0,0.0,1.0,-0.0015872225631028414,-0.001404628506861627,-0.0009400136768817902,0.16295522451400757,-0.2580702602863312,0.0006771606858819723 -1769682063,699901696,0.0,0.0,0.0,1.0,-0.001948406919836998,-0.0011492206249386072,-0.0008846304845064878,0.08146228641271591,-0.12859317660331726,0.021785041317343712 -1769682063,749128192,0.0,0.0,0.0,1.0,-0.0018323377007618546,-0.0006906449561938643,-0.0007862155907787383,0.0814833864569664,-0.12898163497447968,0.002700266893953085 -1769682063,777780480,0.0,0.0,0.0,1.0,-0.001970175886526704,-0.0005506653105840087,-0.0007409905665554106,-0.033961180597543716,0.33940714597702026,-0.008143371902406216 -1769682063,814932480,0.0,0.0,0.0,1.0,-0.0022825105115771294,-0.0003910787927452475,-0.0006845742464065552,-0.12900719046592712,-0.0814499706029892,0.0027504349127411842 -1769682063,848360960,0.0,0.0,0.0,1.0,-0.0015017901314422488,-0.0005749218398705125,-0.0006218444905243814,0.25801002979278564,0.16290700435638428,-0.005495460703969002 -1769682063,880963328,0.0,0.0,0.0,1.0,-0.0013012198032811284,-0.0006016368279233575,-0.000590460782404989,-7.65657750889659e-06,0.00021680774807464331,0.01072665024548769 -1769682063,915648256,0.0,0.0,0.0,1.0,-0.0012513877591118217,-0.0007610722677782178,-0.0005421246169134974,-9.907962521538138e-06,0.00028850746457464993,0.014302210882306099 -1769682063,949571840,0.0,0.0,0.0,1.0,-0.0009088314836844802,-0.0008705185609869659,-0.0004951009177602828,0.1289892941713333,0.0817968025803566,0.013939238153398037 -1769682063,981070592,0.0,0.0,0.0,1.0,-0.0011017958167940378,-0.0008810909348540008,-0.00048119682469405234,-0.16300329566001892,0.2579425573348999,-0.005285531282424927 -1769682064,14349824,0.0,0.0,0.0,1.0,-0.0012034527026116848,-0.0009721992537379265,-0.0004794101696461439,-7.210874173324555e-07,2.390308873145841e-05,0.00119185377843678 -1769682064,62610944,0.0,0.0,0.0,1.0,-0.000929835659917444,-0.0009449224453419447,-0.0004853280261158943,-0.09498081356287003,-0.4208485186100006,0.011946775019168854 -1769682064,72295680,0.0,0.0,0.0,1.0,-0.0010749647626653314,-0.0009013530216179788,-0.0004906264948658645,0.03400908783078194,-0.3390234410762787,0.02706744894385338 -1769682064,114809088,0.0,0.0,0.0,1.0,-0.0004904030356556177,-0.0007388204103335738,-0.0004667802422773093,-0.33950233459472656,-0.033785928040742874,0.012421783991158009 -1769682064,159883008,0.0,0.0,0.0,1.0,-0.0002568503259681165,-0.00043103579082526267,-0.00043543754145503044,0.3394932746887207,0.034123510122299194,0.004258804954588413 -1769682064,169710336,0.0,0.0,0.0,1.0,-0.00021512704552151263,-0.0002533493097871542,-0.0004338846483733505,0.08151880651712418,-0.12917837500572205,-0.008114092983305454 -1769682064,216145152,0.0,0.0,0.0,1.0,-2.301870335941203e-05,0.0006479122093878686,-0.0003970204561483115,-0.04745769500732422,-0.21110571920871735,-0.028005680069327354 -1769682064,248192512,0.0,0.0,0.0,1.0,0.00012157643504906446,0.001267240266315639,-0.0003449998330324888,0.12900088727474213,0.08105065673589706,-0.024200594052672386 -1769682064,281200640,0.0,0.0,0.0,1.0,0.0003128176904283464,0.0015444651944562793,-0.0002937716490123421,0.29203730821609497,-0.17684675753116608,-0.01775800809264183 -1769682064,315134464,0.0,0.0,0.0,1.0,0.00012823473662137985,0.0016620344249531627,-0.00025311383069492877,-0.21049879491329193,0.0472177155315876,-0.013001742772758007 -1769682064,353173504,0.0,0.0,0.0,1.0,3.541521437000483e-05,0.0015723651740700006,-0.0002474354696460068,0.08149836212396622,-0.1283404529094696,0.0336228646337986 -1769682064,381402368,0.0,0.0,0.0,1.0,-0.0003277529904153198,0.0012144556967541575,-0.00025544280651956797,0.1764524281024933,0.29192525148391724,-0.008083748631179333 -1769682064,415518976,0.0,0.0,0.0,1.0,-0.0004345700144767761,0.0010224571451544762,-0.0002502505376469344,0.08150532096624374,-0.12853018939495087,0.024091510102152824 -1769682064,454309120,0.0,0.0,0.0,1.0,-0.0005763124208897352,0.0006106776418164372,-0.00024047296028584242,0.21048657596111298,-0.04692564159631729,0.027338406071066856 -1769682064,467893760,0.0,0.0,0.0,1.0,-0.0007832420524209738,0.0006307254079729319,-0.00022599069052375853,-0.08152981102466583,0.12909983098506927,0.004514293745160103 -1769682064,514855424,0.0,0.0,0.0,1.0,-0.0007333831745199859,0.002660703146830201,-0.00020037377544213086,0.21047621965408325,-0.04673437029123306,0.036889463663101196 -1769682064,548548096,0.0,0.0,0.0,1.0,-0.0009603979997336864,0.003989215474575758,-0.00016697862884029746,0.04742560535669327,0.21108363568782806,0.026858016848564148 -1769682064,569998336,0.0,0.0,0.0,1.0,-0.0009328675805591047,0.004587937146425247,-0.00011234245175728574,-0.04748758673667908,-0.2099480926990509,0.03034350275993347 -1769682064,615154688,0.0,0.0,0.0,1.0,-0.0006331131444312632,0.0051405481062829494,-1.6982658053166233e-05,-0.04746929183602333,-0.21030336618423462,0.012449223548173904 -1769682064,652110336,0.0,0.0,0.0,1.0,-0.0009317376534454525,0.005479856394231319,0.00010149297304451466,-0.1289948970079422,-0.08137098699808121,0.00856372993439436 -1769682064,681381376,0.0,0.0,0.0,1.0,-0.0008848992874845862,0.005412200931459665,0.00021189305698499084,-0.08152728527784348,0.1290038377046585,-0.00030276726465672255 -1769682064,703337728,0.0,0.0,0.0,1.0,-0.0008841271046549082,0.005355700384825468,0.0002877872611861676,-4.334924597060308e-06,4.704171806224622e-05,0.0023837194312363863 -1769682064,748460544,0.0,0.0,0.0,1.0,-0.0010513665620237589,0.005144595168530941,0.00047231820644810796,1.4874596672598273e-05,-0.00014079792890697718,-0.007151160854846239 -1769682064,781901824,0.0,0.0,0.0,1.0,-0.0005454101483337581,0.00491768354550004,0.0005905131110921502,0.12896732985973358,0.08169399946928024,0.008219820447266102 -1769682064,814890240,0.0,0.0,0.0,1.0,-0.0003926142235286534,0.004550199490040541,0.0007039930205792189,-0.21050384640693665,0.047458112239837646,-0.00143167853821069 -1769682064,857575680,0.0,0.0,0.0,1.0,-0.0001189074173453264,0.004231571685522795,0.0008261853945441544,0.25796112418174744,0.1631891429424286,0.00697754742577672 -1769682064,873666304,0.0,0.0,0.0,1.0,-0.00018988517695106566,0.0038934475742280483,0.0009915356058627367,0.08149529248476028,-0.1288968175649643,0.006325681693851948 -1769682064,914503424,0.0,0.0,0.0,1.0,-0.00020107097225263715,0.003912101034075022,0.0011272416450083256,-0.17651335895061493,-0.29183652997016907,0.011202564463019371 -1769682064,949531648,0.0,0.0,0.0,1.0,9.663257515057921e-05,0.0039035461377352476,0.0013127689016982913,4.5438791858032346e-05,-0.000304358167340979,-0.01549416221678257 -1769682064,971125248,0.0,0.0,0.0,1.0,0.00015406739839818329,0.00384715897962451,0.0014035124331712723,-0.04745803773403168,-0.21083256602287292,-0.01507814135402441 -1769682065,15328768,0.0,0.0,0.0,1.0,-0.00010863556963158771,0.00389954075217247,0.0015818929532542825,1.8861355783883482e-05,-0.00011709345562849194,-0.005959288217127323 -1769682065,48721920,0.0,0.0,0.0,1.0,0.0003823346924036741,0.003981519024819136,0.0017864943947643042,0.08147210627794266,-0.12898650765419006,0.0028064721263945103 -1769682065,80981504,0.0,0.0,0.0,1.0,0.00012817390961572528,0.004074954893440008,0.0019677705131471157,-0.04759335517883301,-0.21023806929588318,0.01470138505101204 -1769682065,116196864,0.0,0.0,0.0,1.0,0.00040061335312202573,0.00418202206492424,0.00217933370731771,-0.0814516693353653,0.12897279858589172,-0.004020477645099163 -1769682065,154633216,0.0,0.0,0.0,1.0,0.0006427782354876399,0.0038598054088652134,0.0024710530415177345,0.1764424741268158,0.2928413450717926,0.04377581179141998 -1769682065,181611520,0.0,0.0,0.0,1.0,0.00041399867041036487,0.002354753203690052,0.0027024205774068832,-0.2584080100059509,-0.16116328537464142,0.08803979307413101 -1769682065,214542848,0.0,0.0,0.0,1.0,0.00019421798060648143,0.001012306078337133,0.0029282723553478718,-0.08170181512832642,0.13045072555541992,0.06984542310237885 -1769682065,262968320,0.0,0.0,0.0,1.0,0.0002929075271822512,-0.0003347863384988159,0.003171690972521901,-0.00024808908347040415,0.0012699415674433112,0.06436005234718323 -1769682065,274883328,0.0,0.0,0.0,1.0,0.00016983403475023806,-0.0007299479912035167,0.0033603848423808813,0.08126966655254364,-0.1284000426530838,0.03503907471895218 -1769682065,315156480,0.0,0.0,0.0,1.0,7.50465042074211e-05,-0.0009954074630513787,0.0035134986974298954,0.08131169527769089,-0.12869074940681458,0.02073507569730282 -1769682065,348409856,0.0,0.0,0.0,1.0,0.00011521320993779227,-0.0010360804153606296,0.00368844554759562,-0.08132527768611908,0.12886720895767212,-0.0123890470713377 -1769682065,370297600,0.0,0.0,0.0,1.0,4.863106005359441e-05,-0.0009356773225590587,0.0037765365559607744,8.025209535844624e-05,-0.0004236143722664565,-0.021453354507684708 -1769682065,415511040,0.0,0.0,0.0,1.0,-0.0003826417960226536,-0.0006679053185507655,0.003949977457523346,-0.3058933913707733,-0.3735218644142151,-0.017606832087039948 -1769682065,448700672,0.0,0.0,0.0,1.0,-0.000221018010051921,-0.00032449958962388337,0.0041138543747365475,0.081341452896595,-0.12925206124782562,-0.005495572462677956 -1769682065,481463296,0.0,0.0,0.0,1.0,-0.00043419847497716546,0.0011338680051267147,0.004229258745908737,-0.16270363330841064,0.25880661606788635,0.02529258467257023 -1769682065,515089920,0.0,0.0,0.0,1.0,-7.635002839379013e-05,0.0025602250825613737,0.004355074372142553,-8.080591214820743e-05,0.00042313264566473663,0.021453361958265305 -1769682065,551361280,0.0,0.0,0.0,1.0,0.00010948070121230558,0.00377836124971509,0.004513701889663935,0.04785702005028725,0.21058310568332672,0.006764780264347792 -1769682065,581227264,0.0,0.0,0.0,1.0,9.942601900547743e-05,0.004335206467658281,0.004638385958969593,-0.129197895526886,-0.08106660097837448,0.009425565600395203 -1769682065,615428864,0.0,0.0,0.0,1.0,1.8246937543153763e-06,0.004563564900308847,0.004762828350067139,-9.895135008264333e-06,4.699812416220084e-05,0.002383703365921974 -1769682065,660287744,0.0,0.0,0.0,1.0,5.1791153964586556e-05,0.004401359707117081,0.004880839493125677,0.1291266828775406,0.08147607743740082,0.013254542835056782 -1769682065,669043200,0.0,0.0,0.0,1.0,-3.1174233299680054e-05,0.00426979037001729,0.0050260210409760475,0.33954209089279175,0.03334483504295349,0.009186643175780773 -1769682065,714778880,0.0,0.0,0.0,1.0,0.0003612875589169562,0.004105324856936932,0.005246372893452644,-0.08108056336641312,0.1288803368806839,-0.018413538113236427 -1769682065,750295296,0.0,0.0,0.0,1.0,0.00023378044716082513,0.0038108977023512125,0.005491306073963642,-0.048128534108400345,-0.21025317907333374,0.007498479448258877 -1769682065,771294976,0.0,0.0,0.0,1.0,0.0001506009721197188,0.0037169698625802994,0.005622221622616053,0.16222259402275085,-0.2584485709667206,0.0046869986690580845 -1769682065,816030720,0.0,0.0,0.0,1.0,0.0007105401600711048,0.003413981990888715,0.0059589846059679985,0.032969191670417786,-0.3398445248603821,-0.00862455740571022 -1769682065,853338624,0.0,0.0,0.0,1.0,0.0004866492818109691,0.0033659408800303936,0.006274993531405926,-0.2585480511188507,-0.16215814650058746,-0.0016792949754744768 -1769682065,881689088,0.0,0.0,0.0,1.0,0.0003947959921788424,0.00331084500066936,0.006506169680505991,0.12932337820529938,0.08092441409826279,-0.0057039083912968636 -1769682065,911521792,0.0,0.0,0.0,1.0,0.0002850957971531898,0.0032132668420672417,0.006718092132359743,-0.2586864233016968,-0.1617734730243683,0.01257660798728466 -1769682065,944504832,0.0,0.0,0.0,1.0,0.0003986043739132583,0.0032958206720650196,0.006885422859340906,0.42056024074554443,-0.09652471542358398,0.0113137261942029 -1769682065,967592192,0.0,0.0,0.0,1.0,0.0004003573558293283,0.0032951722387224436,0.007015627343207598,-0.129271000623703,-0.08122289925813675,-0.013400914147496223 -1769682066,14743552,0.0,0.0,0.0,1.0,0.00033603806514292955,0.0033035119995474815,0.007148848846554756,0.2103080153465271,-0.04855510964989662,-0.003828497603535652 -1769682066,63951616,0.0,0.0,0.0,1.0,-7.21897158655338e-05,0.003363365773111582,0.007242071907967329,-0.12944279611110687,-0.08069977909326553,0.009210825897753239 -1769682066,73490432,0.0,0.0,0.0,1.0,0.00015537839499302208,0.0033963376190513372,0.007322611752897501,6.899893924128264e-05,-0.00023654317192267627,-0.011918390169739723 -1769682066,114445056,0.0,0.0,0.0,1.0,-3.108850069111213e-05,0.0034429088700562716,0.0074076284654438496,-0.25893229246139526,-0.1613801121711731,0.01360232662409544 -1769682066,155020288,0.0,0.0,0.0,1.0,-0.00015980511670932174,0.0026107782032340765,0.007533382624387741,0.08025136590003967,-0.12766538560390472,0.09124824404716492 -1769682066,169782528,0.0,0.0,0.0,1.0,-2.663792110979557e-05,0.0011303230421617627,0.007672930136322975,-0.13001300394535065,-0.07895112782716751,0.09140406548976898 -1769682066,215048960,0.0,0.0,0.0,1.0,-1.0609808668959886e-05,-0.00010079325875267386,0.007890713401138783,0.3394284248352051,0.032834116369485855,0.04551060497760773 -1769682066,248492544,0.0,0.0,0.0,1.0,-3.389491030247882e-05,-0.0009076974238269031,0.008095158264040947,-0.00012149734538979828,0.00040243694093078375,0.020261229947209358 -1769682066,286859520,0.0,0.0,0.0,1.0,0.00014726322842761874,-0.0010901937494054437,0.008265363052487373,-0.12963813543319702,-0.08030430227518082,0.01751566305756569 -1769682066,315307008,0.0,0.0,0.0,1.0,-0.0001114594197133556,-0.0010787098435685039,0.00840367004275322,0.2590542435646057,0.1614197939634323,0.009058668278157711 -1769682066,345708032,0.0,0.0,0.0,1.0,0.00013401669275481254,-0.0008041121764108539,0.008568703196942806,0.21026837825775146,-0.04937922582030296,-0.018049724400043488 -1769682066,381553408,0.0,0.0,0.0,1.0,-6.094500713516027e-05,-0.0005862288526259363,0.008765743114054203,-0.4202152192592621,0.09793313592672348,-0.012754172086715698 -1769682066,413714432,0.0,0.0,0.0,1.0,0.00012169532419648021,-0.00040216889465227723,0.008862702175974846,-0.08040423691272736,0.1292571723461151,-0.01973273605108261 -1769682066,454605568,0.0,0.0,0.0,1.0,0.00016481376951560378,0.0006935506244190037,0.009149967692792416,-0.2906348407268524,0.17911489307880402,0.010241208598017693 -1769682066,483993344,0.0,0.0,0.0,1.0,0.00023452653840649873,0.001780967228114605,0.009349796921014786,-0.12976446747779846,-0.08012298494577408,0.015140208415687084 -1769682066,514940928,0.0,0.0,0.0,1.0,0.0003225734399165958,0.002522889291867614,0.009559649042785168,-0.1607113927602768,0.25924596190452576,-0.01088578812777996 -1769682066,567768064,0.0,0.0,0.0,1.0,0.0005073013599030674,0.0031822752207517624,0.009799285791814327,0.03079543635249138,-0.3393672704696655,0.024834096431732178 -1769682066,569479936,0.0,0.0,0.0,1.0,0.00036462186835706234,0.0033205754589289427,0.009942387230694294,-0.00010926429240498692,0.00035642966395244,0.017877517268061638 -1769682066,617638656,0.0,0.0,0.0,1.0,0.000355868018232286,0.003247178392484784,0.010183006525039673,-0.21009047329425812,0.04972166568040848,0.008429219014942646 -1769682066,649973504,0.0,0.0,0.0,1.0,0.00013488862896338105,0.00322123896330595,0.010336474515497684,-0.17946089804172516,-0.29011285305023193,0.007034860551357269 -1769682066,681453824,0.0,0.0,0.0,1.0,3.0370705644600093e-05,0.003076514694839716,0.010400653816759586,0.16036872565746307,-0.2598535120487213,-0.0057005807757377625 -1769682066,701700096,0.0,0.0,0.0,1.0,0.00023304030764847994,0.0029605827294290066,0.010445863008499146,-0.20995347201824188,0.04963177442550659,-0.0059334710240364075 -1769682066,747170560,0.0,0.0,0.0,1.0,-4.179941606707871e-05,0.00286021176725626,0.010439462959766388,-0.049669910222291946,-0.21040120720863342,-0.019971609115600586 -1769682066,781495552,0.0,0.0,0.0,1.0,-0.00017090470646508038,0.0026667534839361906,0.010419554077088833,0.0499153807759285,0.20990416407585144,-0.0038587558083236217 -1769682066,816462848,0.0,0.0,0.0,1.0,0.00017898248916026205,0.002709031803533435,0.01043924130499363,0.00015365330909844488,-0.00045245158253237605,-0.022644925862550735 -1769682066,850797056,0.0,0.0,0.0,1.0,-6.03513399255462e-05,0.0026492751203477383,0.010485666804015636,-0.12984447181224823,-0.08031246811151505,-0.018363656476140022 -1769682066,869662208,0.0,0.0,0.0,1.0,0.00024472898803651333,0.0026849291753023863,0.010593601502478123,-0.20981252193450928,0.049862079322338104,-0.013182764872908592 -1769682066,901763584,0.0,0.0,0.0,1.0,0.0003560768673196435,0.002628125948831439,0.010732973925769329,-0.07981093227863312,0.12989699840545654,-0.007925959303975105 -1769682066,948372736,0.0,0.0,0.0,1.0,7.106347766239196e-05,0.0026355357840657234,0.0110152093693614,0.2896159589290619,-0.18029393255710602,0.00567264948040247 -1769682066,974065408,0.0,0.0,0.0,1.0,0.00020565908926073462,0.002696871291846037,0.0111248092725873,0.20988298952579498,-0.05044782534241676,-0.004637360572814941 -1769682067,16069120,0.0,0.0,0.0,1.0,0.00016355373372789472,0.002737634116783738,0.011343722231686115,-0.31075528264045715,-0.36896878480911255,0.014667203649878502 -1769682067,50342912,0.0,0.0,0.0,1.0,0.00037348276237025857,0.002794120693579316,0.011601792648434639,4.3986110540572554e-05,-0.00011945288861170411,-0.005959109403192997 -1769682067,81325312,0.0,0.0,0.0,1.0,0.00026108184829354286,0.0028484617359936237,0.011799870058894157,0.13023291528224945,0.07946483790874481,-0.006584228947758675 -1769682067,103924224,0.0,0.0,0.0,1.0,4.869337135460228e-05,0.002565777860581875,0.011914885602891445,-0.2606295943260193,-0.158532977104187,0.029840685427188873 -1769682067,152974336,0.0,0.0,0.0,1.0,-9.55223513301462e-05,0.0008562958682887256,0.012177865952253342,-0.05111146718263626,-0.20883458852767944,0.046729493886232376 -1769682067,181705984,0.0,0.0,0.0,1.0,3.486420609988272e-06,0.0001428250689059496,0.012283663265407085,0.33982783555984497,0.029034079983830452,0.023452138528227806 -1769682067,200770304,0.0,0.0,0.0,1.0,-0.00039515207754448056,-0.00028279179241508245,0.012318342924118042,-0.0003243766550440341,0.0008609220385551453,0.04290550947189331 -1769682067,261800192,0.0,0.0,0.0,1.0,-0.00034600371145643294,-0.0005631503299809992,0.012386997230350971,0.07928131520748138,-0.13024713099002838,0.006785699166357517 -1769682067,275688192,0.0,0.0,0.0,1.0,-0.0002964046725537628,-0.0007094427710399032,0.01239760871976614,-0.2607101500034332,-0.15865930914878845,-0.0035451073199510574 -1769682067,314756352,0.0,0.0,0.0,1.0,-0.0002702584897633642,-0.00069242570316419,0.012481802143156528,-0.20957013964653015,0.051017723977565765,-0.009742018766701221 -1769682067,349707520,0.0,0.0,0.0,1.0,-0.0002603091415949166,-0.0005709006800316274,0.012569938786327839,0.340023398399353,0.02795708179473877,0.005544963758438826 -1769682067,370775296,0.0,0.0,0.0,1.0,-0.00012220811913721263,-0.00044280843576416373,0.012627254240214825,-0.13033053278923035,-0.07950090616941452,-0.0184513870626688 -1769682067,414894080,0.0,0.0,0.0,1.0,0.00023466443235520273,0.00014810150605626404,0.012755370698869228,-0.0001676384563324973,0.0004539853543974459,0.02264479547739029 -1769682067,450336256,0.0,0.0,0.0,1.0,-0.00031421237508766353,0.0013411190593615174,0.01286261435598135,-0.15804778039455414,0.2612757384777069,0.005511234048753977 -1769682067,468816128,0.0,0.0,0.0,1.0,-0.0002499788533896208,0.0017619746504351497,0.012922454625368118,0.20948344469070435,-0.05149152874946594,0.007364492863416672 -1769682067,515846144,0.0,0.0,0.0,1.0,2.6085239369422197e-05,0.0023757629096508026,0.012974749319255352,-0.4191098213195801,0.10372583568096161,0.011454246938228607 -1769682067,545666816,0.0,0.0,0.0,1.0,-0.0002492157509550452,0.0025674595963209867,0.013024115934967995,0.15773500502109528,-0.26143595576286316,-0.0042885951697826385 -1769682067,567542784,0.0,0.0,0.0,1.0,0.00015338763478212059,0.002663980470970273,0.013090396299958229,0.07877526432275772,-0.13064129650592804,0.003225439228117466 -1769682067,617783296,0.0,0.0,0.0,1.0,0.0004015051817987114,0.0025515675079077482,0.013248834758996964,0.00012035468535032123,-0.000310999748762697,-0.015493628568947315 -1769682067,655936000,0.0,0.0,0.0,1.0,0.00029167463071644306,0.0023492956534028053,0.013392114080488682,-0.026400169357657433,0.3398054540157318,-0.021340128034353256 -1769682067,682322176,0.0,0.0,0.0,1.0,6.519233284052461e-05,0.0023105554282665253,0.01350137684494257,0.15714702010154724,-0.2614651024341583,0.008881828747689724 -1769682067,714955520,0.0,0.0,0.0,1.0,0.00021872342040296644,0.0021633224096149206,0.013668731786310673,7.604228449054062e-05,-0.00019167890422977507,-0.009534520097076893 -1769682067,763396608,0.0,0.0,0.0,1.0,0.0002694682916626334,0.0020490079186856747,0.013904284685850143,-0.07859101891517639,0.13116759061813354,0.013421911746263504 -1769682067,772164352,0.0,0.0,0.0,1.0,9.971918188966811e-05,0.0020840163342654705,0.014030246995389462,-0.13080212473869324,-0.07864377647638321,-0.010206179693341255 -1769682067,815911936,0.0,0.0,0.0,1.0,0.00030893899383954704,0.0019968515262007713,0.014289154671132565,-0.41844096779823303,0.10480129718780518,-0.01983029954135418 -1769682067,850230784,0.0,0.0,0.0,1.0,5.9359706938266754e-05,0.0020423445384949446,0.014504645019769669,0.07836765795946121,-0.13118359446525574,-0.008636323735117912 -1769682067,883884800,0.0,0.0,0.0,1.0,-7.440059562213719e-06,0.0019460712792351842,0.014585782773792744,-0.3147825300693512,-0.3656620383262634,0.005963297560811043 -1769682067,905762304,0.0,0.0,0.0,1.0,-7.09261221345514e-05,0.0018502670573070645,0.014728750102221966,-0.15873898565769196,-0.6273812651634216,0.018481703475117683 -1769682067,949771264,0.0,0.0,0.0,1.0,0.00012678744678851217,0.0020213911775499582,0.014831873588263988,-0.20924997329711914,0.05316520109772682,0.006711832247674465 -1769682067,981664768,0.0,0.0,0.0,1.0,-0.00016703670553397387,0.002074298681691289,0.014876087196171284,-5.0293827371206135e-05,0.00012014432286377996,0.005959045607596636 -1769682068,17246976,0.0,0.0,0.0,1.0,-0.00016362802125513554,0.001977363834157586,0.014914721250534058,-0.20894016325473785,0.05272722989320755,-0.024299923330545425 -1769682068,56690688,0.0,0.0,0.0,1.0,-0.00022968667326495051,0.0020197152625769377,0.014995047822594643,-0.07782917469739914,0.1310545802116394,-0.009270302951335907 -1769682068,81898752,0.0,0.0,0.0,1.0,-4.759898001793772e-05,0.0014524429570883512,0.01507942471653223,-0.13154245913028717,-0.07713369280099869,0.03500295430421829 -1769682068,99915264,0.0,0.0,0.0,1.0,-2.144409518223256e-05,0.0008149095810949802,0.0151784997433424,-0.13148438930511475,-0.07728610187768936,0.025465888902544975 -1769682068,158731264,0.0,0.0,0.0,1.0,-2.008488809224218e-05,-1.7875740013550967e-05,0.015383466146886349,-0.20941725373268127,0.05450808256864548,0.04359976202249527 -1769682068,171855616,0.0,0.0,0.0,1.0,-0.0002183036267524585,-0.0003850840439554304,0.015570846386253834,-0.13157784938812256,-0.07712049037218094,0.02665710635483265 -1769682068,215074560,0.0,0.0,0.0,1.0,4.024767258670181e-05,-0.0006159662152640522,0.015890071168541908,-0.26291510462760925,-0.15486843883991241,0.013990936800837517 -1769682068,250471680,0.0,0.0,0.0,1.0,-0.00010612074402160943,-0.0006951011018827558,0.016193464398384094,0.05420234799385071,0.2083686888217926,-0.029976611956954002 -1769682068,279708928,0.0,0.0,0.0,1.0,0.00037871699896641076,-0.0006429371424019337,0.01634243130683899,-0.053905390202999115,-0.20921720564365387,-0.012926789931952953 -1769682068,317196032,0.0,0.0,0.0,1.0,-0.00024149456294253469,-0.0005140329012647271,0.01656121201813221,-0.1313057839870453,-0.0778818428516388,-0.025770345702767372 -1769682068,366028288,0.0,0.0,0.0,1.0,-0.00023411426809616387,-0.0002691856352612376,0.01668844185769558,0.15469148755073547,-0.26352086663246155,-0.014835947193205357 -1769682068,373295872,0.0,0.0,0.0,1.0,-0.0001760628802003339,0.0002910498878918588,0.016778700053691864,-0.20883718132972717,0.05445634573698044,0.0007182038389146328 -1769682068,420034816,0.0,0.0,0.0,1.0,-0.00016931045684032142,0.0009330864995718002,0.016824012622237206,-0.2632434070110321,-0.15443269908428192,-0.0074480511248111725 -1769682068,451804672,0.0,0.0,0.0,1.0,-0.0005630510859191418,0.0016640396788716316,0.01687873713672161,0.0770033523440361,-0.13160139322280884,0.006887876428663731 -1769682068,467650048,0.0,0.0,0.0,1.0,-0.00029544191784225404,0.001882148557342589,0.01691482774913311,-0.1318262666463852,-0.07678210735321045,0.011160219088196754 -1769682068,514882304,0.0,0.0,0.0,1.0,-0.00012106529902666807,0.002184363082051277,0.017008163034915924,0.20860478281974792,-0.05465003103017807,0.012432357296347618 -1769682068,567009024,0.0,0.0,0.0,1.0,0.00033245974918827415,0.0021584765054285526,0.017151596024632454,0.0001237037795362994,-0.0002889566821977496,-0.014301670715212822 -1769682068,581251584,0.0,0.0,0.0,1.0,0.0003237323253415525,0.0021832664497196674,0.017330633476376534,0.2638525664806366,0.15328501164913177,-0.011533601209521294 -1769682068,599630080,0.0,0.0,0.0,1.0,-8.437735959887505e-05,0.0021227786783128977,0.017407391220331192,0.07665286958217621,-0.13177447021007538,0.008103086613118649 -1769682068,648901376,0.0,0.0,0.0,1.0,1.1733645806089044e-05,0.0019305115565657616,0.017664335668087006,0.18750551342964172,0.2848030626773834,-0.019609369337558746 -1769682068,682166528,0.0,0.0,0.0,1.0,0.00022467912640422583,0.0017521983245387673,0.01776537299156189,0.15318939089775085,-0.2642199695110321,-0.0076061999425292015 -1769682068,715099392,0.0,0.0,0.0,1.0,-6.326241418719292e-06,0.0018322921823710203,0.017910974100232124,-0.05557609722018242,-0.20856449007987976,-0.0010415525175631046 -1769682068,749976832,0.0,0.0,0.0,1.0,0.00035858803312294185,0.0016996337799355388,0.018069814890623093,-0.20844145119190216,0.055697765201330185,-0.004187757149338722 -1769682068,781735424,0.0,0.0,0.0,1.0,-8.439761586487293e-06,0.0017726487712934613,0.01815997064113617,0.02039792574942112,-0.34053799510002136,0.005890482105314732 -1769682068,819792896,0.0,0.0,0.0,1.0,-6.907600618433207e-05,0.001784814172424376,0.01828089728951454,0.2085847705602646,-0.05638398230075836,-0.01843516156077385 -1769682068,853638912,0.0,0.0,0.0,1.0,-0.00022315603564493358,0.0017925059655681252,0.018418727442622185,-0.11241920292377472,-0.4163856506347656,0.02053362876176834 -1769682068,881828608,0.0,0.0,0.0,1.0,-0.00021190414554439485,0.0017215259140357375,0.018488997593522072,0.07600457966327667,-0.13220785558223724,0.005759233608841896 -1769682068,915045888,0.0,0.0,0.0,1.0,-0.0001022920769173652,0.0017345244996249676,0.01854427345097065,0.019560188055038452,-0.34053751826286316,0.008275997824966908 -1769682068,958238720,0.0,0.0,0.0,1.0,6.0530990594998e-05,0.0017501190304756165,0.018602464348077774,-0.26474207639694214,-0.15180625021457672,-0.0005548724438995123 -1769682068,971916800,0.0,0.0,0.0,1.0,6.89798325765878e-05,0.001745398622006178,0.018698157742619514,0.05669187381863594,0.20803098380565643,-0.012040074914693832 -1769682069,15511296,0.0,0.0,0.0,1.0,0.00014965928858146071,0.0017511022742837667,0.018865903839468956,-0.4164167046546936,0.11356663703918457,-0.00021921005100011826 -1769682069,50912000,0.0,0.0,0.0,1.0,2.0296720322221518e-06,0.0010846770601347089,0.01906280778348446,-0.0003121927729807794,0.0006770924665033817,0.03337029367685318 -1769682069,83518720,0.0,0.0,0.0,1.0,-0.00021685013780370355,0.0007326339255087078,0.0191375520080328,-0.00033482781145721674,0.0007254664087668061,0.03575388342142105 -1769682069,115322368,0.0,0.0,0.0,1.0,1.9397761207073927e-05,0.00011233650002395734,0.019275115802884102,0.07519438117742538,-0.13202840089797974,0.03080841340124607 -1769682069,151166208,0.0,0.0,0.0,1.0,-0.0005104900919832289,-0.00011479643580969423,0.019332239404320717,-0.057430364191532135,-0.2077869027853012,0.014410324394702911 -1769682069,167411712,0.0,0.0,0.0,1.0,-0.00024115316045936197,-0.000267887458903715,0.019320810213685036,0.1326856017112732,0.07535864412784576,0.0020944802090525627 -1769682069,217044992,0.0,0.0,0.0,1.0,-0.0002806895354297012,-0.0003733173361979425,0.019272545352578163,-0.05772615596652031,-0.20759981870651245,0.020365260541439056 -1769682069,248285952,0.0,0.0,0.0,1.0,-0.0005234670825302601,-0.0002307238755747676,0.01923811435699463,-0.26545271277427673,-0.150624617934227,-0.017297690734267235 -1769682069,282080000,0.0,0.0,0.0,1.0,-0.0002411113673588261,-0.00010945164831355214,0.019229399040341377,-0.05769626051187515,-0.20819850265979767,-0.013009677641093731 -1769682069,314832384,0.0,0.0,0.0,1.0,-0.00030342041281983256,-6.645602115895599e-05,0.019228676334023476,-0.07480743527412415,0.13258494436740875,-0.017686503008008003 -1769682069,356436480,0.0,0.0,0.0,1.0,-0.00019149278523400426,0.0003448612114880234,0.0192656721919775,-0.05824488773941994,-0.20745553076267242,0.02035820297896862 -1769682069,370805504,0.0,0.0,0.0,1.0,-0.0003145335940644145,0.001109686098061502,0.019303476437926292,-0.1912962645292282,-0.2823653817176819,0.013489596545696259 -1769682069,415119616,0.0,0.0,0.0,1.0,-0.00010044708324130625,0.0018280366202816367,0.019348815083503723,-0.20784839987754822,0.05856488272547722,0.008803565055131912 -1769682069,449536256,0.0,0.0,0.0,1.0,0.0002854249032679945,0.0022899117320775986,0.01949915662407875,-0.1332133412361145,-0.07437481731176376,0.010990908369421959 -1769682069,483289600,0.0,0.0,0.0,1.0,1.2192234862595797e-05,0.002366112545132637,0.01966487057507038,0.14901237189769745,-0.2662660479545593,0.005613888148218393 -1769682069,516258304,0.0,0.0,0.0,1.0,0.00022159900981932878,0.00236326502636075,0.01983039826154709,-7.916464528534561e-05,0.00016931371646933258,0.0083425622433424 -1769682069,550697472,0.0,0.0,0.0,1.0,0.0001199569960590452,0.0021906783804297447,0.020016970112919807,-0.26669132709503174,-0.14829444885253906,0.018347326666116714 -1769682069,581647872,0.0,0.0,0.0,1.0,-0.00026514637283980846,0.0022328817285597324,0.02011575922369957,0.0743718221783638,-0.1335597187280655,-0.010879854671657085 -1769682069,618499328,0.0,0.0,0.0,1.0,-2.54438491538167e-05,0.0019720366690307856,0.020197555422782898,-3.4552514989627525e-05,7.268035551533103e-05,0.003575375536456704 -1769682069,658823936,0.0,0.0,0.0,1.0,-0.0002477155067026615,0.0019794628024101257,0.020309023559093475,0.22219306230545044,-0.4002434313297272,0.004337185528129339 -1769682069,667823616,0.0,0.0,0.0,1.0,0.00010581867536529899,0.0018880777060985565,0.020372362807393074,-8.13804508652538e-05,0.0001696850813459605,0.008342533372342587 -1769682069,715285760,0.0,0.0,0.0,1.0,9.427254553884268e-06,0.0018409661715850234,0.020551670342683792,-0.19315555691719055,-0.28118395805358887,0.007402559742331505 -1769682069,759261696,0.0,0.0,0.0,1.0,0.00013679644325748086,0.001778950565494597,0.020691631361842155,0.07389214634895325,-0.13370457291603088,-0.006090033799409866 -1769682069,769373184,0.0,0.0,0.0,1.0,0.00012294994667172432,0.0017385224346071482,0.020810484886169434,-0.13350991904735565,-0.07389982044696808,-0.00816384144127369 -1769682069,815605760,0.0,0.0,0.0,1.0,-0.00031706091249361634,0.0017724710050970316,0.02091771736741066,0.07357918471097946,-0.13356953859329224,0.005836290307343006 -1769682069,850731008,0.0,0.0,0.0,1.0,-0.0005032708868384361,0.0019509359262883663,0.02090919390320778,0.13369174301624298,0.07355504482984543,0.002225183881819248 -1769682069,882062848,0.0,0.0,0.0,1.0,-0.0003031677333638072,0.0017917322693392634,0.020845185965299606,-0.06030678004026413,-0.20724546909332275,-0.0011569233611226082 -1769682069,907837696,0.0,0.0,0.0,1.0,-0.0004703064914792776,0.0019438223680481315,0.020756114274263382,0.1338314414024353,0.0732908621430397,-0.0025255600921809673 -1769682069,950323712,0.0,0.0,0.0,1.0,-0.00040473369881510735,0.0018288897117599845,0.020679449662566185,0.13392853736877441,0.07310733199119568,-0.006089736707508564 -1769682069,982201344,0.0,0.0,0.0,1.0,-0.0004590359458234161,0.0017763831419870257,0.020665204152464867,0.20733395218849182,-0.06131354719400406,-0.025258934125304222 -1769682070,15707904,0.0,0.0,0.0,1.0,-0.0002812831080518663,0.0013927941909059882,0.020748037844896317,-0.12220396101474762,-0.4132193922996521,0.04411753639578819 -1769682070,48500480,0.0,0.0,0.0,1.0,-6.708572618663311e-05,0.0006262535462155938,0.020817521959543228,0.14559485018253326,-0.2672826647758484,0.039121367037296295 -1769682070,83404288,0.0,0.0,0.0,1.0,-0.0003145442751701921,-8.854816405801103e-05,0.020904559642076492,0.13378503918647766,0.0734243094921112,0.027299914509058 -1769682070,115424512,0.0,0.0,0.0,1.0,-0.0002542813599575311,-0.0003790632472373545,0.021003196015954018,0.2067553848028183,-0.06105047091841698,0.015275771729648113 -1769682070,150355456,0.0,0.0,0.0,1.0,-0.00012255337787792087,-0.000635036441963166,0.021133631467819214,-0.011169426143169403,0.3410153090953827,-0.0034740061964839697 -1769682070,173350912,0.0,0.0,0.0,1.0,-6.867447518743575e-05,-0.0006118458695709705,0.02123490907251835,0.13407033681869507,0.07287907600402832,0.01299369428306818 -1769682070,201046528,0.0,0.0,0.0,1.0,-9.712341125123203e-05,-0.0005352023290470243,0.02138141728937626,-0.4026649296283722,-0.2177489846944809,-0.007987765595316887 -1769682070,246270464,0.0,0.0,0.0,1.0,-0.00012182688806205988,-0.00039604277117177844,0.021547598764300346,0.00012014015374006703,-0.00024267734261229634,-0.011917861178517342 -1769682070,267038208,0.0,0.0,0.0,1.0,-0.00021790309983771294,-0.0002185635967180133,0.021626299247145653,-0.13425108790397644,-0.07254227995872498,-0.01060497760772705 -1769682070,302091776,0.0,0.0,0.0,1.0,3.7298595998436213e-06,-0.00010702356667025015,0.021666666492819786,1.1968886610702612e-05,-2.4268712877528742e-05,-0.001191786490380764 -1769682070,350552576,0.0,0.0,0.0,1.0,-0.00040796835673972964,0.0012891310034319758,0.02163884975016117,0.20641499757766724,-0.062065958976745605,0.017649322748184204 -1769682070,369484544,0.0,0.0,0.0,1.0,7.080170325934887e-05,0.0017242805333808064,0.021610768511891365,0.06257083266973495,0.2063666135072708,-0.01072704792022705 -1769682070,400067584,0.0,0.0,0.0,1.0,-2.1420419216156006e-06,0.0021200075279921293,0.021577445790171623,0.1343686729669571,0.07233411818742752,0.01896647736430168 -1769682070,467053056,0.0,0.0,0.0,1.0,-6.936091813258827e-05,0.002654517535120249,0.021568777039647102,0.07188128679990768,-0.13479770720005035,-0.00605837581679225 -1769682070,468894720,0.0,0.0,0.0,1.0,0.0001843854843173176,0.0025758659467101097,0.02162003703415394,-0.07138251513242722,0.13395479321479797,-0.03684937581419945 -1769682070,515633920,0.0,0.0,0.0,1.0,-8.555053500458598e-05,0.0025805423501878977,0.021829677745699883,0.0717560276389122,-0.13498836755752563,-0.010814364068210125 -1769682070,556925696,0.0,0.0,0.0,1.0,-1.6878620954230428e-05,0.0024502489250153303,0.022022180259227753,6.209110870258883e-05,-0.00012151764531154186,-0.005958906374871731 -1769682070,569918464,0.0,0.0,0.0,1.0,3.168545663356781e-05,0.002394536742940545,0.022199396044015884,-0.06326090544462204,-0.2065059393644333,-0.009565859101712704 -1769682070,615976960,0.0,0.0,0.0,1.0,-0.000199883637833409,0.002185962861403823,0.02239980734884739,-0.13489115238189697,-0.07132651656866074,3.329617902636528e-05 -1769682070,649969152,0.0,0.0,0.0,1.0,0.00010981503874063492,0.0020866766571998596,0.02255861833691597,0.00017711552209220827,-0.00034083795617334545,-0.016684891656041145 -1769682070,684355840,0.0,0.0,0.0,1.0,-9.152229176834226e-05,0.0021306811831891537,0.02266700379550457,0.20631447434425354,-0.06426817178726196,-0.016757782548666 -1769682070,716235008,0.0,0.0,0.0,1.0,-0.00018430214549880475,0.002021404914557934,0.0227803997695446,0.06398577988147736,0.20615921914577484,0.002433438552543521 -1769682070,747448320,0.0,0.0,0.0,1.0,-2.974551171064377e-05,0.0020063400734215975,0.022899983450770378,0.20599764585494995,-0.06411175429821014,0.004718845244497061 -1769682070,766844672,0.0,0.0,0.0,1.0,-0.000360095058567822,0.0019814500119537115,0.022985147312283516,0.14163289964199066,-0.27022722363471985,0.007055156864225864 -1769682070,819246848,0.0,0.0,0.0,1.0,-0.0002339650527574122,0.0020200491417199373,0.023049095645546913,-0.06454894691705704,-0.20584116876125336,0.005893074441701174 -1769682070,851350528,0.0,0.0,0.0,1.0,-0.00040274180355481803,0.0019496034365147352,0.023092366755008698,0.20600275695323944,-0.06495014578104019,-0.010731486603617668 -1769682070,870626816,0.0,0.0,0.0,1.0,-0.00015344198618549854,0.0019843413028866053,0.023128226399421692,0.0706605464220047,-0.13556909561157227,-0.010763030499219894 -1769682070,900159232,0.0,0.0,0.0,1.0,-0.0001852639834396541,0.0019234736682847142,0.023183567449450493,-0.20027408003807068,-0.27625811100006104,-0.00013083592057228088 -1769682070,961434624,0.0,0.0,0.0,1.0,-0.0002617126447148621,0.00206181057728827,0.023314720019698143,0.0,-0.0,0.0 -1769682070,968610816,0.0,0.0,0.0,1.0,6.203886005096138e-05,0.0017238677246496081,0.02341262623667717,-0.06542001664638519,-0.20540547370910645,0.015398537740111351 -1769682071,16912640,0.0,0.0,0.0,1.0,-8.181427256204188e-05,0.0008197007700800896,0.023545291274785995,0.1352105587720871,0.07069116085767746,0.029868759214878082 -1769682071,50582784,0.0,0.0,0.0,1.0,-0.00023733280249871314,-0.00011794545571319759,0.02362070605158806,0.20517021417617798,-0.0649358406662941,0.03699802979826927 -1769682071,79723008,0.0,0.0,0.0,1.0,-0.0002269726974191144,-0.0003052129177376628,0.023651648312807083,0.27081945538520813,0.14063245058059692,0.04186349734663963 -1769682071,116632576,0.0,0.0,0.0,1.0,-0.00023567728931084275,-0.000543793139513582,0.02365114726126194,-0.20567220449447632,0.06632498651742935,0.016638267785310745 -1769682071,151895040,0.0,0.0,0.0,1.0,-0.0004997934447601438,-0.0005423640250228345,0.023600710555911064,-0.13911980390548706,0.27127981185913086,-0.016621708869934082 -1769682071,182310912,0.0,0.0,0.0,1.0,-0.0003999049949925393,-0.0006284741684794426,0.023558789864182472,-0.1357308328151703,-0.06970720738172531,-0.008412878029048443 -1769682071,217046784,0.0,0.0,0.0,1.0,-0.0006573258433490992,-0.0005145515315234661,0.023489784449338913,-0.47400006651878357,-0.4137206971645355,-0.0026975772343575954 -1769682071,252994816,0.0,0.0,0.0,1.0,-0.0002902947016991675,-0.0004524261166807264,0.023389730602502823,0.06675129383802414,0.20493759214878082,-0.017767269164323807 -1769682071,282529536,0.0,0.0,0.0,1.0,-0.00015074448310770094,0.00012427241017576307,0.023272261023521423,0.20497551560401917,-0.06634114682674408,0.022668981924653053 -1769682071,303728128,0.0,0.0,0.0,1.0,-0.0002778037451207638,0.001370321260765195,0.02318674325942993,-0.00027326797135174274,0.0005113463848829269,0.025027252733707428 -1769682071,361313792,0.0,0.0,0.0,1.0,-0.0003013791283592582,0.0025303997099399567,0.023093849420547485,-0.27246883511543274,-0.13748443126678467,0.02485673502087593 -1769682071,371862528,0.0,0.0,0.0,1.0,-1.7971615307033062e-05,0.0029028947465121746,0.023054048418998718,-0.06741135567426682,-0.20466284453868866,0.021325187757611275 -1769682071,414990336,0.0,0.0,0.0,1.0,8.885675924830139e-05,0.003362087532877922,0.02299816533923149,-0.13474024832248688,-0.4100542962551117,0.0009195598540827632 -1769682071,450112768,0.0,0.0,0.0,1.0,-0.00016740098362788558,0.003485216060653329,0.02294343151152134,0.3422181010246277,-0.3399255871772766,0.0131902564316988 -1769682071,479511552,0.0,0.0,0.0,1.0,-0.00019369371875654906,0.0035167608875781298,0.022914106026291847,-1.3498348380380776e-05,2.4370241590077057e-05,0.0011917680967599154 -1769682071,516103424,0.0,0.0,0.0,1.0,-0.0003373927029315382,0.003277535317465663,0.02284351922571659,0.20442809164524078,0.2729431092739105,-0.021129194647073746 -1769682071,551506944,0.0,0.0,0.0,1.0,7.215177174657583e-05,0.0031547562684863806,0.022795692086219788,-1.3770069926977158e-05,2.4380664399359375e-05,0.0011917647207155824 -1769682071,566821376,0.0,0.0,0.0,1.0,-0.00013830020907334983,0.003129548393189907,0.022797485813498497,0.13655368983745575,0.0681157335639,-0.009347986429929733 -1769682071,621639424,0.0,0.0,0.0,1.0,-0.0001379815803375095,0.0029222466982901096,0.022880826145410538,-0.00019341360894031823,-0.3411012887954712,0.00817284919321537 -1769682071,654332672,0.0,0.0,0.0,1.0,-9.723505354486406e-05,0.002900502411648631,0.022947845980525017,-0.00012661085929721594,0.0002196975110564381,0.010725846514105797 -1769682071,669191680,0.0,0.0,0.0,1.0,-7.817399455234408e-05,0.002840840257704258,0.02295420505106449,0.13668377697467804,0.06785167753696442,-0.0069246962666511536 -1769682071,716161024,0.0,0.0,0.0,1.0,-0.0004168091109022498,0.002730973996222019,0.022811496630311012,0.1368034929037094,0.06762906908988953,-0.011675708927214146 -1769682071,760567552,0.0,0.0,0.0,1.0,-0.0005237438017502427,0.0027769010048359632,0.02259092964231968,-0.2733735740184784,-0.1356203407049179,-0.006475983187556267 -1769682071,769743360,0.0,0.0,0.0,1.0,-0.0007314134854823351,0.002858769381418824,0.022476401180028915,0.06910447776317596,0.20438094437122345,-0.0045404862612485886 -1769682071,800771328,0.0,0.0,0.0,1.0,-0.0007507326081395149,0.002788617042824626,0.022332264110445976,0.3394967317581177,-0.34266945719718933,0.012329703196883202 -1769682071,843371264,0.0,0.0,0.0,1.0,-0.0005320004420354962,0.002837777603417635,0.022254712879657745,-0.1367710679769516,-0.06762009859085083,-0.007446612231433392 -1769682071,878524928,0.0,0.0,0.0,1.0,-8.108816109597683e-05,0.0028764682356268167,0.022275283932685852,-0.2061420977115631,-0.27214521169662476,-0.02201325073838234 -1769682071,900224512,0.0,0.0,0.0,1.0,-0.00010979345825035125,0.002910090610384941,0.022318312898278236,-0.13447095453739166,0.27372944355010986,-0.012036647647619247 -1769682071,950403840,0.0,0.0,0.0,1.0,0.000516714877448976,0.00235451920889318,0.022452542558312416,-0.06745383888483047,0.13755013048648834,0.02376542240381241 -1769682071,968138240,0.0,0.0,0.0,1.0,0.00010779115837067366,0.001568633015267551,0.02244599536061287,0.13606850802898407,0.06868745386600494,0.07899849116802216 -1769682072,10996736,0.0,0.0,0.0,1.0,-0.00027160809258930385,0.0005984714953228831,0.02240172028541565,-0.0005829556612297893,0.000952528091147542,0.046478237956762314 -1769682072,55296768,0.0,0.0,0.0,1.0,-0.0002215688582509756,-0.0005142397712916136,0.0223526768386364,0.13338401913642883,-0.27391108870506287,0.02517024800181389 -1769682072,66903040,0.0,0.0,0.0,1.0,-0.00013993900211062282,-0.0006837554392404854,0.022369667887687683,0.407520592212677,-0.1401887983083725,0.03777577728033066 -1769682072,115173376,0.0,0.0,0.0,1.0,-9.87612729659304e-05,-0.0009686154080554843,0.022476481273770332,0.06663443148136139,-0.13725292682647705,0.0024505737237632275 -1769682072,157634304,0.0,0.0,0.0,1.0,-0.00010388159716967493,-0.0008339000050909817,0.022574063390493393,-0.07061932981014252,-0.20409530401229858,-0.009806548245251179 -1769682072,171496704,0.0,0.0,0.0,1.0,-1.7025507986545563e-05,-0.0007247977191582322,0.0226461049169302,-0.2745899558067322,-0.1331149786710739,-0.010203398764133453 -1769682072,217202944,0.0,0.0,0.0,1.0,-0.00013316910190042108,-0.0005673834821209311,0.022649582475423813,0.27001816034317017,-0.20839804410934448,0.00879465788602829 -1769682072,249401344,0.0,0.0,0.0,1.0,4.5236345613375306e-05,-0.00017892944742925465,0.022644290700554848,-0.20907072722911835,-0.26934677362442017,0.027998827397823334 -1769682072,284000512,0.0,0.0,0.0,1.0,5.658384179696441e-05,0.0011765861418098211,0.02261592261493206,-0.06658980250358582,0.13831569254398346,0.03688422217965126 -1769682072,299708672,0.0,0.0,0.0,1.0,-0.0001689037017058581,0.002109980210661888,0.022584866732358932,-0.27528074383735657,-0.13185162842273712,0.012431973591446877 -1769682072,345761280,0.0,0.0,0.0,1.0,0.00025060202460736036,0.0034333679359406233,0.022568579763174057,0.05992826446890831,-0.47835657000541687,0.02488326095044613 -1769682072,367950080,0.0,0.0,0.0,1.0,0.00010684767039492726,0.004034109879285097,0.022573411464691162,0.2032998949289322,-0.07151030749082565,0.017133841291069984 -1769682072,416855296,0.0,0.0,0.0,1.0,4.154173075221479e-05,0.0044142561964690685,0.022639138624072075,-0.06574654579162598,0.1377752274274826,0.0011026500724256039 -1769682072,451330304,0.0,0.0,0.0,1.0,-0.00016400970343966037,0.004376767668873072,0.022733300924301147,0.2756967544555664,0.13093139231204987,-0.011079784482717514 -1769682072,469274368,0.0,0.0,0.0,1.0,-9.865645552054048e-05,0.004256530664861202,0.022787852212786674,-0.07218122482299805,-0.20348840951919556,-0.00628334516659379 -1769682072,516491008,0.0,0.0,0.0,1.0,-3.6729295970872045e-05,0.003998447675257921,0.022967113181948662,0.07266228646039963,0.20295579731464386,-0.01634886860847473 -1769682072,553114880,0.0,0.0,0.0,1.0,0.00027140675229020417,0.003773878561332822,0.023212216794490814,0.13801628351211548,0.06512441486120224,-0.006676136516034603 -1769682072,566524416,0.0,0.0,0.0,1.0,6.0794263845309615e-05,0.003706613089889288,0.023350218310952187,-0.2030354142189026,0.07256227731704712,-0.011344020254909992 -1769682072,615275008,0.0,0.0,0.0,1.0,0.00017248789663426578,0.003487205132842064,0.023662909865379333,0.008094113320112228,0.3407641351222992,-0.02004339173436165 -1769682072,656239360,0.0,0.0,0.0,1.0,0.0001278150884900242,0.003497409401461482,0.02385355718433857,0.13809208571910858,0.0649297833442688,-0.0018650798592716455 -1769682072,671572736,0.0,0.0,0.0,1.0,9.161059278994799e-05,0.003492848016321659,0.02398686483502388,-0.3408357501029968,0.00796714797616005,-0.021482961252331734 -1769682072,701652736,0.0,0.0,0.0,1.0,-0.0002617243444547057,0.0034869827795773745,0.02405403181910515,-0.13805557787418365,-0.06492803990840912,-0.007698079105466604 -1769682072,748213248,0.0,0.0,0.0,1.0,-0.00024068247876130044,0.003540933597832918,0.02414930798113346,8.209826046368107e-05,-0.0001231776550412178,-0.005958630237728357 -1769682072,782064896,0.0,0.0,0.0,1.0,3.863044548779726e-05,0.0036158859729766846,0.024269113317131996,0.0,-0.0,0.0 -1769682072,799064576,0.0,0.0,0.0,1.0,-0.00025320990243926644,0.003635970875620842,0.024417854845523834,-0.21217279136180878,-0.26721495389938354,0.00017896783538162708 -1769682072,847961856,0.0,0.0,0.0,1.0,-4.4097891077399254e-05,0.0037386417388916016,0.024586716666817665,0.1284862458705902,-0.27657732367515564,0.012303500436246395 -1769682072,867475200,0.0,0.0,0.0,1.0,-0.0005879938253201544,0.0037778697442263365,0.024645816534757614,-0.20244184136390686,0.07395615428686142,-0.015135339461266994 -1769682072,912663552,0.0,0.0,0.0,1.0,-0.0005695691215805709,0.003776365891098976,0.02462044730782509,-0.13841629028320312,-0.06417902559041977,-0.00422705989331007 -1769682072,954352896,0.0,0.0,0.0,1.0,-0.00049653893802315,0.002101405058056116,0.02455967850983143,-0.0010130386799573898,0.0014565340243279934,0.07031120359897614 -1769682072,982140672,0.0,0.0,0.0,1.0,-0.00032955611823126674,0.0010143122635781765,0.024477139115333557,-0.27794280648231506,-0.12657898664474487,0.05108014494180679 -1769682073,120576,0.0,0.0,0.0,1.0,-0.0003098139713983983,0.00030170686659403145,0.024440987035632133,-0.13939808309078217,-0.06265385448932648,0.05294780433177948 -1769682073,68014848,0.0,0.0,0.0,1.0,-0.0001630592450965196,-0.00037413323298096657,0.024501454085111618,-0.07551845908164978,-0.20171982049942017,0.029327113181352615 -1769682073,71040512,0.0,0.0,0.0,1.0,-7.174460915848613e-05,-0.0006627100519835949,0.024598656222224236,0.06333878636360168,-0.1384766399860382,0.014512795954942703 -1769682073,115492608,0.0,0.0,0.0,1.0,-0.00022047196398489177,-0.0005623269244097173,0.02483639121055603,0.051407694816589355,-0.4798727035522461,0.001148937619291246 -1769682073,146671616,0.0,0.0,0.0,1.0,-5.0437694881111383e-05,-0.0004359338490758091,0.025027764961123466,-0.07533616572618484,-0.2024659365415573,-0.014762735925614834 -1769682073,182164992,0.0,0.0,0.0,1.0,-4.979464574716985e-05,-0.0002637170546222478,0.02524581365287304,-0.012394066900014877,-0.3413122892379761,-0.013360945507884026 -1769682073,201795328,0.0,0.0,0.0,1.0,-8.701370097696781e-05,-0.00018195666780229658,0.025336740538477898,-0.27753886580467224,-0.1266465038061142,-0.025172879919409752 -1769682073,252159232,0.0,0.0,0.0,1.0,0.0001757536083459854,0.0006015487597323954,0.025554783642292023,-0.06311921775341034,0.13935646414756775,0.01409175619482994 -1769682073,267197696,0.0,0.0,0.0,1.0,7.9082150477916e-05,0.0013656184310093522,0.025633152574300766,-0.12567192316055298,0.2781580090522766,-0.001612980617210269 -1769682073,315620352,0.0,0.0,0.0,1.0,0.00014612686936743557,0.002233773237094283,0.025769473984837532,-0.15310229361057281,-0.4032839834690094,0.018127748742699623 -1769682073,347081216,0.0,0.0,0.0,1.0,-0.0003828298067674041,0.002783769741654396,0.025821160525083542,0.0001540249359095469,-0.0002232094411738217,-0.010725416243076324 -1769682073,367266304,0.0,0.0,0.0,1.0,-0.0004029894480481744,0.00309526058845222,0.025786958634853363,0.12481663376092911,-0.2782825827598572,0.011170913465321064 -1769682073,415492864,0.0,0.0,0.0,1.0,-0.0006571656558662653,0.0031311754137277603,0.025629471987485886,-0.3411216139793396,0.014987794682383537,0.013808242976665497 -1769682073,465690112,0.0,0.0,0.0,1.0,-0.0005642818287014961,0.003061865223571658,0.02546514943242073,0.06221769377589226,-0.13940541446208954,-0.0009600224439054728 -1769682073,479762688,0.0,0.0,0.0,1.0,-0.0006326687289401889,0.003021807176992297,0.025382250547409058,0.07738255709409714,0.20132675766944885,-0.009011252783238888 -1769682073,498666752,0.0,0.0,0.0,1.0,-0.00031728646717965603,0.00296952435746789,0.025303484871983528,-0.20144732296466827,0.07746346294879913,-0.0010075131431221962 -1769682073,544422144,0.0,0.0,0.0,1.0,-0.0005148376221768558,0.0029302844777703285,0.025260018184781075,0.061811573803424835,-0.1394229531288147,0.00500896293669939 -1769682073,582112256,0.0,0.0,0.0,1.0,-0.0001084387768059969,0.0028097894974052906,0.02533719316124916,-0.00023177363618742675,0.0003220049839001149,0.0154921505600214 -1769682073,621497856,0.0,0.0,0.0,1.0,-0.00025941929197870195,0.00276654283516109,0.02541816234588623,0.13957296311855316,0.061643097549676895,0.0020082416012883186 -1769682073,648935424,0.0,0.0,0.0,1.0,-8.067276212386787e-05,0.0027292061131447554,0.025518590584397316,-0.016959620639681816,-0.34034833312034607,0.024710513651371002 -1769682073,669148672,0.0,0.0,0.0,1.0,0.00019003479974344373,0.00280101434327662,0.025769807398319244,0.00025293807266280055,-0.00034716882510110736,-0.01668379455804825 -1769682073,698979584,0.0,0.0,0.0,1.0,0.00012307302677072585,0.0030090026557445526,0.02624760940670967,3.6304689274402335e-05,-4.963021638104692e-05,-0.0023833971936255693 -1769682073,764568064,0.0,0.0,0.0,1.0,-0.0003653172170743346,0.0030898975674062967,0.026608237996697426,0.12223336100578308,-0.27968528866767883,0.0017420898657292128 -1769682073,771654912,0.0,0.0,0.0,1.0,-0.000932973634917289,0.0031637821812182665,0.026620617136359215,0.12197408825159073,-0.27960148453712463,0.008894742466509342 -1769682073,799819264,0.0,0.0,0.0,1.0,-0.0011240108869969845,0.0030975351110100746,0.026529867202043533,0.06077367439866066,-0.1397130936384201,0.011003055609762669 -1769682073,842647552,0.0,0.0,0.0,1.0,-0.001296430011279881,0.003114276099950075,0.026262840256094933,0.07912982255220413,0.20082589983940125,0.003024778328835964 -1769682073,878208512,0.0,0.0,0.0,1.0,-0.0017082847189158201,0.0030677099712193012,0.02598634362220764,-0.14006249606609344,-0.060592200607061386,0.0026400568895041943 -1769682073,899599104,0.0,0.0,0.0,1.0,-0.0010693263029679656,0.0027243555523455143,0.025753676891326904,0.200289785861969,-0.07909297198057175,0.022676950320601463 -1769682073,952709888,0.0,0.0,0.0,1.0,-0.00148509640712291,0.0016890008701011539,0.0253740306943655,-0.0006972039118409157,0.0009110845858231187,0.04409259185194969 -1769682073,966647296,0.0,0.0,0.0,1.0,-0.001210184651426971,0.0013785178307443857,0.025281697511672974,0.2602623403072357,-0.21938380599021912,0.03607643023133278 -1769682074,13666560,0.0,0.0,0.0,1.0,-0.0010994335170835257,0.000908274669200182,0.02519160881638527,0.1395266205072403,0.06108669191598892,0.04388130083680153 -1769682074,49081344,0.0,0.0,0.0,1.0,-0.0011017824290320277,0.0007012065034359694,0.025101855397224426,0.3401573598384857,-0.019597934558987617,0.030839232727885246 -1769682074,68237312,0.0,0.0,0.0,1.0,-0.001272432622499764,0.0007037890027277172,0.025008095428347588,0.319905549287796,-0.36068952083587646,0.022031936794519424 -1769682074,98925824,0.0,0.0,0.0,1.0,-0.0012533178087323904,0.0008169685024768114,0.02481701970100403,0.25978779792785645,-0.22055493295192719,0.020577387884259224 -1769682074,166398464,0.0,0.0,0.0,1.0,-0.0015183226205408573,0.0007426892407238483,0.024445096030831337,-0.02123105712234974,-0.3403782546520233,0.011406227014958858 -1769682074,174823168,0.0,0.0,0.0,1.0,-0.001226472551934421,0.000894107564818114,0.02425764873623848,-0.34023573994636536,0.020974542945623398,-0.02133878879249096 -1769682074,199748864,0.0,0.0,0.0,1.0,-0.0014087804593145847,0.0009323781123384833,0.024164527654647827,0.28134581446647644,0.11857666820287704,-0.01941468007862568 -1769682074,244656896,0.0,0.0,0.0,1.0,-0.001043221214786172,0.001261784927919507,0.024082832038402557,-0.08113352954387665,-0.20002251863479614,-0.0031732013449072838 -1769682074,278633984,0.0,0.0,0.0,1.0,-0.000615868775639683,0.001192646101117134,0.024105576798319817,0.14075450599193573,0.059075914323329926,-0.008499972522258759 -1769682074,299702784,0.0,0.0,0.0,1.0,0.0001047379628289491,0.0010397362057119608,0.023621276021003723,-0.05901487171649933,0.14046809077262878,-0.010964259505271912 -1769682074,345906432,0.0,0.0,0.0,1.0,-0.000573597033508122,0.0009938010480254889,0.023169120773673058,0.2583710849285126,-0.2218857705593109,0.028935633599758148 -1769682074,366366976,0.0,0.0,0.0,1.0,-0.0008132135262712836,0.0008263374911621213,0.022895965725183487,-7.628774619661272e-05,9.731786121847108e-05,0.004766771104186773 -1769682074,412994816,0.0,0.0,0.0,1.0,-0.0011502394918352365,0.0008344062371179461,0.022636566311120987,0.1994132697582245,-0.08168565481901169,0.015591992065310478 -1769682074,448562432,0.0,0.0,0.0,1.0,-0.0015403395518660545,0.000812141690403223,0.022381747141480446,-0.08223190158605576,-0.19942526519298553,0.0075109126046299934 -1769682074,466808320,0.0,0.0,0.0,1.0,-0.0015707493294030428,0.0009235424804501235,0.022321917116642,0.11731972545385361,-0.28187888860702515,-0.0019308286719024181 -1769682074,499130880,0.0,0.0,0.0,1.0,-0.0014143830630928278,0.0007808464579284191,0.022340411320328712,0.3403891324996948,-0.02391808107495308,0.0011783493682742119 -1769682074,557254400,0.0,0.0,0.0,1.0,-0.0015899097779765725,0.0009325317805632949,0.02240702509880066,-0.08290785551071167,-0.19895268976688385,0.021774161607027054 -1769682074,573992704,0.0,0.0,0.0,1.0,-0.0015897373668849468,0.0009791821939870715,0.022404231131076813,0.11631888896226883,-0.2817816138267517,0.017098985612392426 -1769682074,599676160,0.0,0.0,0.0,1.0,-0.0018202763749286532,0.000983719015493989,0.022370170801877975,-0.08271601051092148,-0.1994197964668274,-0.0068521648645401 -1769682074,645679616,0.0,0.0,0.0,1.0,-0.0021292439196258783,0.0010839622700586915,0.022258007898926735,0.03318110853433609,-0.481452077627182,0.0018601457122713327 -1769682074,678196224,0.0,0.0,0.0,1.0,-0.001853720168583095,0.0008278336026705801,0.022166918963193893,0.48106318712234497,0.03323750197887421,0.02498341165482998 -1769682074,699724800,0.0,0.0,0.0,1.0,-0.0019240695983171463,0.0008781458018347621,0.022044885903596878,0.31488388776779175,-0.3656942546367645,0.0040517570450901985 -1769682074,749010688,0.0,0.0,0.0,1.0,-0.0019979283679276705,0.000784633681178093,0.021837778389453888,0.31437039375305176,-0.36573296785354614,0.015950076282024384 -1769682074,765869568,0.0,0.0,0.0,1.0,-0.0018939089495688677,0.0006877006962895393,0.021679988130927086,0.19896064698696136,-0.08361785113811493,0.0013033535797148943 -1769682074,814642432,0.0,0.0,0.0,1.0,-0.0019267213065177202,0.0007639511022716761,0.02149074152112007,0.14137394726276398,0.05749882012605667,-0.003622993128374219 -1769682074,853520896,0.0,0.0,0.0,1.0,-0.0016684754518792033,0.0008748789550736547,0.021244624629616737,0.19887353479862213,-0.08396352082490921,-0.0010790927335619926 -1769682074,870573056,0.0,0.0,0.0,1.0,-0.0016217067604884505,0.0009109860402531922,0.02107691578567028,0.19883960485458374,-0.08411307632923126,-0.002270190045237541 -1769682074,899298304,0.0,0.0,0.0,1.0,-0.0014453122857958078,0.0008166852057911456,0.020922591909766197,-0.027010297402739525,-0.33995893597602844,0.01222236454486847 -1769682074,958349312,0.0,0.0,0.0,1.0,-0.0011006887070834637,0.0007809314411133528,0.02074987068772316,0.19881334900856018,-0.08452057838439941,-0.00822589173913002 -1769682074,969755904,0.0,0.0,0.0,1.0,-0.0012012154329568148,0.0008110600174404681,0.020610276609659195,0.19870300590991974,-0.08457326889038086,-0.0046492209658026695 -1769682075,230912,0.0,0.0,0.0,1.0,-0.0009231120930053294,0.0007819855818524957,0.020463600754737854,0.05709529295563698,-0.14167329668998718,-0.004640632774680853 -1769682075,43188736,0.0,0.0,0.0,1.0,-0.001318962313234806,0.0008666483336128294,0.020232995972037315,0.14164084196090698,0.05681619793176651,-0.0023823105730116367 -1769682075,66142720,0.0,0.0,0.0,1.0,-0.001166289672255516,0.0009548286907374859,0.02004648931324482,0.5954770445823669,-0.25478893518447876,-0.006774100475013256 -1769682075,106228224,0.0,0.0,0.0,1.0,-0.0013538222992792726,0.0011213512625545263,0.01976865530014038,-0.14199282228946686,-0.056292612105607986,0.019051898270845413 -1769682075,144318464,0.0,0.0,0.0,1.0,-0.0010589922312647104,0.000934671435970813,0.019549552351236343,0.2547035813331604,-0.22659456729888916,0.015736322849988937 -1769682075,170809344,0.0,0.0,0.0,1.0,-0.0013184399576857686,0.001010526088066399,0.01936500146985054,0.05667500197887421,-0.141934335231781,-0.008233592845499516 -1769682075,199264768,0.0,0.0,0.0,1.0,-0.0009822758147493005,0.0008802663069218397,0.0192321315407753,0.396239310503006,-0.17049753665924072,0.014578267931938171 -1769682075,261477376,0.0,0.0,0.0,1.0,-0.0007623626152053475,0.000907899287994951,0.019141357392072678,0.3398970663547516,-0.029116041958332062,0.006141048856079578 -1769682075,269707776,0.0,0.0,0.0,1.0,-0.0005685710930265486,0.0005692379781976342,0.019138827919960022,0.4818338453769684,0.026799684390425682,0.0002336832694709301 -1769682075,299593984,0.0,0.0,0.0,1.0,-0.0005225275526754558,0.00017465197015553713,0.01914665848016739,0.4817708730697632,0.02661551535129547,0.0050061289221048355 -1769682075,344856832,0.0,0.0,0.0,1.0,-0.0008045813883654773,-8.978241385193542e-05,0.019131576642394066,0.395975261926651,-0.17179159820079803,0.0026707041542977095 -1769682075,370312192,0.0,0.0,0.0,1.0,-0.0005646984209306538,-0.00012443010928109288,0.019077423959970474,0.00011714725405909121,-0.0001386095827911049,-0.007150270510464907 -1769682075,402289920,0.0,0.0,0.0,1.0,-0.0006703985272906721,-0.0003152095596306026,0.019030854105949402,0.1116713359951973,-0.28385424613952637,0.009712752886116505 -1769682075,447666432,0.0,0.0,0.0,1.0,-0.0008072069613263011,-0.0003359561087563634,0.018975714221596718,0.4816456437110901,0.02555968426167965,0.016914792358875275 -1769682075,466610176,0.0,0.0,0.0,1.0,-0.0003941390896216035,-0.0004086057306267321,0.018986361101269722,0.2840023338794708,0.11153203994035721,0.008437403477728367 -1769682075,503380224,0.0,0.0,0.0,1.0,-0.0005503330612555146,-0.00016541543300263584,0.01904202438890934,0.339651495218277,-0.030686544254422188,0.012091872282326221 -1769682075,548681984,0.0,0.0,0.0,1.0,-0.0008497008820995688,-0.0001255939423572272,0.019089045003056526,0.14222097396850586,0.05540354177355766,-0.004718779120594263 -1769682075,567600896,0.0,0.0,0.0,1.0,-0.0008656489662826061,-6.840679270680994e-05,0.01903414912521839,0.33982351422309875,-0.03139379620552063,-0.0010209972970187664 -1769682075,599390464,0.0,0.0,0.0,1.0,-0.0009478655410930514,6.4904845203273e-05,0.018876928836107254,0.00011621445446508005,-0.00013806890638079494,-0.007150284945964813 -1769682075,649558784,0.0,0.0,0.0,1.0,-0.0012013575760647655,2.040235631284304e-05,0.018577231094241142,0.39500999450683594,-0.174067422747612,0.0014231097884476185 -1769682075,667882752,0.0,0.0,0.0,1.0,-0.001404438866302371,-3.7930272810626775e-05,0.018321285024285316,-0.14200760424137115,-0.05546996742486954,-0.016738638281822205 -1769682075,698997760,0.0,0.0,0.0,1.0,-0.0011276159202679992,-2.4252109142253175e-05,0.018082447350025177,0.17437605559825897,0.39483141899108887,0.0011996317189186811 -1769682075,743160064,0.0,0.0,0.0,1.0,-0.0011529281036928296,-0.00012638518819585443,0.01784961298108101,0.5920886397361755,-0.26223301887512207,-0.000877751037478447 -1769682075,768974592,0.0,0.0,0.0,1.0,-0.001012096763588488,-6.184682570165023e-05,0.01773224025964737,0.3946389853954315,-0.17504002153873444,-0.0009889616630971432 -1769682075,799744256,0.0,0.0,0.0,1.0,-0.000534266117028892,-0.0001099166547646746,0.01766481064260006,0.42704522609710693,0.1646585613489151,0.010907281190156937 -1769682075,845285888,0.0,0.0,0.0,1.0,-0.0009755751816555858,-0.00022019642347004265,0.017589794471859932,0.591489315032959,-0.2631199061870575,0.007432318292558193 -1769682075,866714112,0.0,0.0,0.0,1.0,-0.0006946398643776774,-0.0001531348389107734,0.0175116378813982,0.4271707236766815,0.16422323882579803,0.01568065956234932 -1769682075,901907456,0.0,0.0,0.0,1.0,-0.0011428090510889888,-3.082754119532183e-05,0.01740938611328602,0.1092144325375557,-0.28505396842956543,4.8394082114100456e-05 -1769682075,942686464,0.0,0.0,0.0,1.0,-0.0008934861980378628,-7.62721465434879e-05,0.017326191067695618,0.08801253139972687,0.19705642759799957,0.0012390388874337077 -1769682075,967694336,0.0,0.0,0.0,1.0,-0.00102468382101506,-3.808375186054036e-05,0.017337262630462646,0.2513982653617859,-0.23074612021446228,0.0024808640591800213 -1769682075,999599104,0.0,0.0,0.0,1.0,-0.0005844674305990338,0.0003863849851768464,0.017431950196623802,0.1972634196281433,-0.0886642187833786,-0.018985044211149216 -1769682076,62849536,0.0,0.0,0.0,1.0,-0.00012283265823498368,0.0009907289640977979,0.01757647655904293,0.33979812264442444,-0.034536462277173996,-0.016521988436579704 -1769682076,69712384,0.0,0.0,0.0,1.0,-0.0003789816692005843,0.0012938629370182753,0.01760670728981495,0.19690541923046112,-0.08861129730939865,-0.0034815918188542128 -1769682076,99459328,0.0,0.0,0.0,1.0,-0.0008966856403276324,0.00137196178548038,0.01752633973956108,0.2509101927280426,-0.23136374354362488,0.00011243694461882114 -1769682076,145954560,0.0,0.0,0.0,1.0,-0.0006876027910038829,0.0013186406577005982,0.01728462241590023,0.2855554223060608,0.1078278198838234,-0.005767577327787876 -1769682076,174153472,0.0,0.0,0.0,1.0,-0.0008449595188722014,0.001189790666103363,0.016892144456505775,0.6245899200439453,0.07315410673618317,0.02426326833665371 -1769682076,199449600,0.0,0.0,0.0,1.0,-0.0010926405666396022,0.0011351227294653654,0.016676055267453194,0.44710442423820496,-0.3207090198993683,0.003815904026851058 -1769682076,244525312,0.0,0.0,0.0,1.0,-0.0008635183330625296,0.0011305701918900013,0.01629355363547802,0.2501670718193054,-0.23173195123672485,0.01204222347587347 -1769682076,266600960,0.0,0.0,0.0,1.0,-0.0007868572138249874,0.000946391373872757,0.016101054847240448,0.589155375957489,-0.2670612037181854,0.03016854077577591 -1769682076,301907968,0.0,0.0,0.0,1.0,-0.00048756084288470447,0.0010059332707896829,0.015981370583176613,0.19619277119636536,-0.08894220739603043,0.01919676549732685 -1769682076,346052096,0.0,0.0,0.0,1.0,-0.00048568123020231724,0.0008681489853188396,0.015834733843803406,0.4824141561985016,0.017397956922650337,-0.009129979647696018 -1769682076,369266176,0.0,0.0,0.0,1.0,-0.00046479905722662807,0.00014597469998989254,0.015705497935414314,0.5357800722122192,-0.12565061450004578,-0.001976165920495987 -1769682076,399237888,0.0,0.0,0.0,1.0,-0.0005848481669090688,-0.0003254185139667243,0.015526625327765942,0.6254444122314453,0.07024568319320679,-0.012565219774842262 -1769682076,448070912,0.0,0.0,0.0,1.0,-0.0004663998552132398,-0.0009835698874667287,0.015311218798160553,0.196580171585083,-0.09004799276590347,-0.016559597104787827 -1769682076,467144448,0.0,0.0,0.0,1.0,-0.00038785976357758045,-0.0010921566281467676,0.015187571756541729,0.19628648459911346,-0.08984530717134476,-0.0010742286685854197 -1769682076,500030976,0.0,0.0,0.0,1.0,-0.0003561092307791114,-0.0010182686382904649,0.01509361807256937,0.4823000729084015,0.01638861931860447,0.0003619985654950142 -1769682076,544713472,0.0,0.0,0.0,1.0,-0.0003065104247070849,-0.0010438540484756231,0.01497985515743494,0.39217111468315125,-0.1798572838306427,0.010926324874162674 -1769682076,573702912,0.0,0.0,0.0,1.0,-0.0005275827134028077,-0.0009683641255833209,0.014855800196528435,0.5722739696502686,0.21211357414722443,0.006424735300242901 -1769682076,600652288,0.0,0.0,0.0,1.0,-0.0004036952741444111,-0.000936912139877677,0.01469553355127573,0.5721378326416016,0.21212968230247498,0.02071242406964302 -1769682076,644968448,0.0,0.0,0.0,1.0,-0.0008455722709186375,-0.0007694184314459562,0.014349643141031265,0.6253458261489868,0.0684010460972786,0.008749344386160374 -1769682076,666765568,0.0,0.0,0.0,1.0,-0.001104425871744752,-0.0007743535097688437,0.01398965623229742,0.3392086923122406,-0.03765247017145157,-0.0022047124803066254 -1769682076,701735936,0.0,0.0,0.0,1.0,-0.0009533506236039102,-0.0007248991169035435,0.013588435016572475,0.3919285535812378,-0.18096330761909485,0.00012700771912932396 -1769682076,747885568,0.0,0.0,0.0,1.0,-0.0008275902946479619,-0.0005882768309675157,0.01314721442759037,0.2863234579563141,0.10545066744089127,0.00735903438180685 -1769682076,766772736,0.0,0.0,0.0,1.0,-0.0004170734900981188,-0.0006530486862175167,0.012980500236153603,0.39155271649360657,-0.1810789704322815,0.013207999989390373 -1769682076,800073472,0.0,0.0,0.0,1.0,-0.00021646425011567771,-0.0006856226245872676,0.012933362275362015,0.5347045660018921,-0.12863974273204803,0.015681244432926178 -1769682076,858154240,0.0,0.0,0.0,1.0,-0.00011183766036992893,-0.0007221404230222106,0.013025503605604172,0.39140766859054565,-0.18145690858364105,0.01199499424546957 -1769682076,871242240,0.0,0.0,0.0,1.0,-0.000265177950495854,-0.0005966940079815686,0.013097708113491535,0.43011149764060974,0.1570245772600174,-0.011635911650955677 -1769682076,899393536,0.0,0.0,0.0,1.0,-0.0003216706681996584,-0.0007531510200351477,0.013107534497976303,0.43007880449295044,0.1569671630859375,-0.005685687065124512 -1769682076,947039744,0.0,0.0,0.0,1.0,-0.00037225993582978845,-0.0006950176903046668,0.013040805235505104,0.33916643261909485,-0.03896801546216011,-0.008231541141867638 -1769682076,969317376,0.0,0.0,0.0,1.0,-0.0006104839849285781,-0.0008374900207854807,0.012882283888757229,0.33920732140541077,-0.039166636765003204,-0.01181558333337307 -1769682077,653568,0.0,0.0,0.0,1.0,-0.0009495170670561492,-0.0007464858354069293,0.01266070269048214,0.24797199666500092,-0.2348468154668808,-0.009596457704901695 -1769682077,48444928,0.0,0.0,0.0,1.0,-0.0007645137375220656,-0.000721067248377949,0.012397939339280128,0.33870530128479004,-0.0389079749584198,0.017957612872123718 -1769682077,66733568,0.0,0.0,0.0,1.0,-0.00044871235149912536,-0.0007154523627832532,0.01229555532336235,0.72984379529953,-0.22197894752025604,0.011981233954429626 -1769682077,105638912,0.0,0.0,0.0,1.0,-0.0003171825665049255,-0.0008320311899296939,0.012288859114050865,0.7296421527862549,-0.22222639620304108,0.017912304028868675 -1769682077,146056448,0.0,0.0,0.0,1.0,-0.0003576828457880765,-0.0008087579626590014,0.012314747087657452,0.677984893321991,-0.07945193350315094,-0.0070458268746733665 -1769682077,167197440,0.0,0.0,0.0,1.0,-0.0001839067117543891,-0.00019419705495238304,0.012357328087091446,0.5344130992889404,-0.13153143227100372,-0.004740271717309952 -1769682077,199474688,0.0,0.0,0.0,1.0,1.5952929970808327e-05,0.0003018488350789994,0.012333402410149574,0.5345680713653564,-0.13197410106658936,-0.017848167568445206 -1769682077,250156800,0.0,0.0,0.0,1.0,-0.0001776290882844478,0.0006645926041528583,0.012199338525533676,0.5342442393302917,-0.13192446529865265,-0.0011540921404957771 -1769682077,266427648,0.0,0.0,0.0,1.0,-0.0004201923729851842,0.0009165095980279148,0.012024530209600925,0.6261770129203796,0.06299532949924469,-0.010504523292183876 -1769682077,300988160,0.0,0.0,0.0,1.0,-0.0005358530906960368,0.0011249654926359653,0.01184906717389822,0.3908783197402954,-0.18433277308940887,-0.02147095277905464 -1769682077,343119360,0.0,0.0,0.0,1.0,-0.0004936481127515435,0.0011069669853895903,0.011663423851132393,0.4825999438762665,0.010921761393547058,-0.009354749694466591 -1769682077,370148864,0.0,0.0,0.0,1.0,0.00010422727791592479,0.0009634782327339053,0.011624238453805447,0.23569060862064362,0.24671189486980438,0.0002842170652002096 -1769682077,400395776,0.0,0.0,0.0,1.0,-7.556637865491211e-05,0.0008560735150240362,0.01164259947836399,0.43077296018600464,0.15463539958000183,0.011025948449969292 -1769682077,444122368,0.0,0.0,0.0,1.0,1.6443271306343377e-05,0.0008748366381041706,0.01167340762913227,0.5230278372764587,0.3495870530605316,0.013620635494589806 -1769682077,466388224,0.0,0.0,0.0,1.0,-0.0001716835831757635,0.0006472925888374448,0.011632938869297504,0.5849302411079407,-0.27666014432907104,0.0215085968375206 -1769682077,502403072,0.0,0.0,0.0,1.0,-0.0004352114046923816,0.0005566970212385058,0.011527789756655693,0.6261213421821594,0.06157972663640976,0.003931542858481407 -1769682077,549288448,0.0,0.0,0.0,1.0,-0.0006716413190588355,0.0005189825315028429,0.011288176290690899,0.4826066195964813,0.009826431050896645,-0.008087316527962685 -1769682077,566206208,0.0,0.0,0.0,1.0,-0.0004953978932462633,0.0003221806837245822,0.011062098667025566,0.4314107894897461,0.1533937156200409,-0.010371647775173187 -1769682077,599908864,0.0,0.0,0.0,1.0,-0.00037143786903470755,-8.167414489435032e-05,0.010809074155986309,0.5334651470184326,-0.13388285040855408,0.01327701099216938 -1769682077,655584000,0.0,0.0,0.0,1.0,-0.0006487664068117738,-0.00023667447385378182,0.01051917765289545,0.49176737666130066,-0.4726893901824951,0.020106416195631027 -1769682077,672938752,0.0,0.0,0.0,1.0,4.643383726943284e-05,-0.0004430669650901109,0.010435511358082294,0.48250752687454224,0.00928446650505066,-0.0009370483458042145 -1769682077,699330048,0.0,0.0,0.0,1.0,-3.132244455628097e-05,-0.00036522519076243043,0.010468507185578346,0.33871135115623474,-0.041888631880283356,-0.0022504646331071854 -1769682077,747691520,0.0,0.0,0.0,1.0,0.0004756845301017165,-0.0005648101214319468,0.010641765780746937,0.28737980127334595,0.10223276168107986,0.01929331198334694 -1769682077,771655680,0.0,0.0,0.0,1.0,0.00039233718416653574,-0.0004603884881362319,0.010755798779428005,0.676949679851532,-0.08379283547401428,0.02169663831591606 -1769682077,800315648,0.0,0.0,0.0,1.0,0.0001031998690450564,-0.0004293883393984288,0.010835499502718449,0.338573157787323,-0.04213958978652954,0.0036934721283614635 -1769682077,844195584,0.0,0.0,0.0,1.0,8.413373143412173e-05,-0.0002008613955695182,0.01081265602260828,0.5838332772254944,-0.279031366109848,0.020284686237573624 -1769682077,867036672,0.0,0.0,0.0,1.0,-0.00018885153986047953,-0.00018219985940959305,0.01068294420838356,0.71958988904953,0.2536414861679077,-0.0018544625490903854 -1769682077,902261760,0.0,0.0,0.0,1.0,-0.00020039209630340338,-0.00017316435696557164,0.010503564029932022,0.38899821043014526,-0.18614372611045837,0.020268836989998817 -1769682077,945521152,0.0,0.0,0.0,1.0,-0.0008206355851143599,-0.00010224661673419178,0.010276501066982746,0.6768348813056946,-0.08506341278553009,0.019282447174191475 -1769682077,967819776,0.0,0.0,0.0,1.0,-0.00015189066471066326,-0.00022209101007319987,0.010224996134638786,0.5834723114967346,-0.2798480689525604,0.01906740665435791 -1769682077,999665920,0.0,0.0,0.0,1.0,0.0003960473113693297,-0.00026561113190837204,0.010312860831618309,0.48231446743011475,0.007870139554142952,0.013315549120306969 -1769682078,58462976,0.0,0.0,0.0,1.0,0.0002920546685345471,-0.00033187371445819736,0.010530225932598114,0.6765990853309631,-0.0855846181511879,0.028800498694181442 -1769682078,75539712,0.0,0.0,0.0,1.0,2.944041625596583e-05,-0.00011821754014817998,0.010750682093203068,0.4321935176849365,0.1511095017194748,-0.008040307089686394 -1769682078,101531648,0.0,0.0,0.0,1.0,0.00014772573194932193,-0.00011617562267929316,0.01081234309822321,0.4823782742023468,0.007291875779628754,0.009729751385748386 -1769682078,143899904,0.0,0.0,0.0,1.0,-0.0001862034696387127,-0.00013921853678766638,0.010827491991221905,0.8710018992424011,-0.18015378713607788,0.024015061557292938 -1769682078,169916672,0.0,0.0,0.0,1.0,-0.00011697631271090358,-0.00015765560965519398,0.010726402513682842,0.6264910697937012,0.05716390162706375,0.007440934889018536 -1769682078,200510720,0.0,0.0,0.0,1.0,-0.0005941936979070306,-0.000217277993215248,0.010521352291107178,0.2880434989929199,0.10062742978334427,0.008541392162442207 -1769682078,244829696,0.0,0.0,0.0,1.0,-0.0008020380628295243,-0.0001524005929240957,0.010153613053262234,0.5827456116676331,-0.281602680683136,0.014256476424634457 -1769682078,267003648,0.0,0.0,0.0,1.0,-0.001066768541932106,-0.00035306307836435735,0.009859479032456875,0.6765745878219604,-0.08745133131742477,0.016845710575580597 -1769682078,301872896,0.0,0.0,0.0,1.0,-0.0009308748412877321,-0.0003076574648730457,0.00960426963865757,0.8208513259887695,-0.037756409496068954,0.006209898740053177 -1769682078,346119680,0.0,0.0,0.0,1.0,-0.00032497092615813017,-0.00022319721756502986,0.009436670690774918,0.48234012722969055,0.006172763183712959,0.013280453160405159 -1769682078,366557440,0.0,0.0,0.0,1.0,2.667587250471115e-05,-0.0001660340785747394,0.009478012099862099,0.5325601696968079,-0.13838133215904236,0.001233480405062437 -1769682078,400947200,0.0,0.0,0.0,1.0,0.00017626106273382902,-0.0002861686807591468,0.00967630185186863,0.6269862651824951,0.05529733747243881,-0.016423644497990608 -1769682078,458158848,0.0,0.0,0.0,1.0,0.00041853508446365595,-0.00045250364928506315,0.01006089523434639,1.0647108554840088,-0.277225524187088,0.016747308894991875 -1769682078,476181248,0.0,0.0,0.0,1.0,0.0003619181225076318,-0.00038475554902106524,0.0103832446038723,0.4824585020542145,0.005374673753976822,0.006107209715992212 -1769682078,499763200,0.0,0.0,0.0,1.0,0.00020484269771259278,-0.0003255042538512498,0.010469666682183743,0.7263875007629395,-0.23344001173973083,0.005947137717157602 -1769682078,545159168,0.0,0.0,0.0,1.0,-0.0005327180260792375,-0.00032076891511678696,0.010475733317434788,0.676576554775238,-0.08955196291208267,0.001293489709496498 -1769682078,573505280,0.0,0.0,0.0,1.0,-0.0006127493688836694,-0.0001534674083814025,0.01037556305527687,0.6271357536315918,0.054134078323841095,-0.020037228241562843 -1769682078,601125376,0.0,0.0,0.0,1.0,-0.00038550252793356776,0.00026568854809738696,0.010216602124273777,0.8207709789276123,-0.040269698947668076,0.0037600556388497353 -1769682078,650863104,0.0,0.0,0.0,1.0,-0.000683677033521235,0.000602202897425741,0.009949544444680214,0.6267915368080139,0.05415508151054382,0.005005474202334881 -1769682078,666732288,0.0,0.0,0.0,1.0,-0.0002921122941188514,0.0007063240627758205,0.009759497828781605,0.626697838306427,0.05410339683294296,0.012170098721981049 -1769682078,705923840,0.0,0.0,0.0,1.0,-0.00040274375351145864,0.0006534588756039739,0.00956804770976305,0.5817874670028687,-0.2847713530063629,-0.009631020948290825 -1769682078,746508288,0.0,0.0,0.0,1.0,9.074443369172513e-05,0.000679744640365243,0.009511809796094894,0.6267333626747131,0.053682684898376465,0.01220107451081276 -1769682078,769578240,0.0,0.0,0.0,1.0,0.0002625169581733644,0.0005879834061488509,0.009682536125183105,0.5812763571739197,-0.2846840023994446,0.01303289458155632 -1769682078,799727616,0.0,0.0,0.0,1.0,0.0006286345887929201,0.00043336552334949374,0.010012137703597546,0.4825458824634552,0.0037405285984277725,0.0013855635188519955 -1769682078,843753216,0.0,0.0,0.0,1.0,0.0009634782327339053,0.00035448139533400536,0.01054071169346571,0.5279483199119568,0.3420725464820862,0.02081792987883091 -1769682078,867414016,0.0,0.0,0.0,1.0,0.0004993350594304502,0.0002319652121514082,0.0108822425827384,0.6762394905090332,-0.09174655377864838,0.0037698112428188324 -1769682078,900413952,0.0,0.0,0.0,1.0,0.00013695341476704925,0.0002819993533194065,0.01110046822577715,0.8207184076309204,-0.0428377203643322,-0.0008814465254545212 -1769682078,944239360,0.0,0.0,0.0,1.0,-5.462983972392976e-05,0.0002550676872488111,0.011177643202245235,0.7714483737945557,0.10134673118591309,0.002819526009261608 -1769682078,969913088,0.0,0.0,0.0,1.0,-0.0006287859287112951,0.0002527687465772033,0.011061511933803558,0.4824235439300537,0.00300506129860878,0.009751041419804096 -1769682079,40960,0.0,0.0,0.0,1.0,-0.0007881829515099525,0.0002981574216391891,0.01083054393529892,0.43326911330223083,0.14743025600910187,0.013453724794089794 -1769682079,45426432,0.0,0.0,0.0,1.0,-0.0010425852378830314,0.00035718412254936993,0.010421394370496273,0.5804488062858582,-0.28636544942855835,0.013079961761832237 -1769682079,67083008,0.0,0.0,0.0,1.0,-0.0008740638731978834,0.00022012768022250384,0.010096607729792595,0.6271653771400452,0.051210738718509674,-0.0032235169783234596 -1769682079,105412096,0.0,0.0,0.0,1.0,-0.0005305579397827387,0.0002998279524035752,0.009742803871631622,0.6757634878158569,-0.09319108724594116,0.01929343119263649 -1769682079,146401792,0.0,0.0,0.0,1.0,-0.000506956537719816,0.0003174794837832451,0.009626267477869987,0.4822440445423126,0.002385515719652176,0.021693013608455658 -1769682079,166629888,0.0,0.0,0.0,1.0,6.738137744832784e-05,0.00029308433295227587,0.009764187969267368,0.33816656470298767,-0.04716850817203522,-0.010607872158288956 -1769682079,200773120,0.0,0.0,0.0,1.0,0.0006391499191522598,4.982815153198317e-05,0.010099155828356743,0.7226661443710327,0.24419359862804413,0.018511082977056503 -1769682079,257304064,0.0,0.0,0.0,1.0,0.0006845423486083746,-6.793624925194308e-05,0.010671919211745262,0.7228782773017883,0.24375861883163452,0.011353484354913235 -1769682079,277591808,0.0,0.0,0.0,1.0,0.0008126820903271437,-0.0001266615727217868,0.01118503138422966,0.9649519324302673,0.002820238471031189,0.013599170371890068 -1769682079,299540224,0.0,0.0,0.0,1.0,0.0003088002558797598,-9.085515921469778e-05,0.01134248822927475,0.7244707942008972,-0.23947423696517944,0.003693732898682356 -1769682079,345458432,0.0,0.0,0.0,1.0,-6.317230872809887e-05,-1.798018638510257e-05,0.011473236605525017,0.8203819394111633,-0.04650018736720085,0.007514765951782465 -1769682079,372029184,0.0,0.0,0.0,1.0,-0.00031321041751652956,-6.418275734176859e-05,0.01138350460678339,0.9647348523139954,0.002097219228744507,0.02789430320262909 -1769682079,399777536,0.0,0.0,0.0,1.0,-0.0007898238254711032,0.00010162244871025905,0.011134270578622818,0.6754708886146545,-0.09528571367263794,0.019307032227516174 -1769682079,445514752,0.0,0.0,0.0,1.0,-0.0011056740768253803,0.00012155895819887519,0.010704358108341694,0.6754658818244934,-0.09562485665082932,0.01692291721701622 -1769682079,466813440,0.0,0.0,0.0,1.0,-0.0008814922766759992,0.00014601914153899997,0.010348259471356869,0.5790311098098755,-0.2888777554035187,0.02023443579673767 -1769682079,501824256,0.0,0.0,0.0,1.0,-0.0008615183760412037,0.0001266963081434369,0.009987923316657543,0.8686919808387756,-0.19276157021522522,0.0038024811074137688 -1769682079,545820416,0.0,0.0,0.0,1.0,-0.0007303312886506319,0.00021194845612626523,0.009596133604645729,0.723558247089386,-0.24098767340183258,0.02273714728653431 -1769682079,566662912,0.0,0.0,0.0,1.0,-0.0006028742645867169,0.0001758239377522841,0.009412257000803947,0.5791369676589966,0.19278211891651154,-0.0006571691483259201 -1769682079,599666944,0.0,0.0,0.0,1.0,-0.0002991599903907627,-1.5536534192506224e-05,0.009349729865789413,0.43417853116989136,0.14472468197345734,0.01351169217377901 -1769682079,648483072,0.0,0.0,0.0,1.0,0.000640754762571305,-0.00025287785683758557,0.009656129404902458,0.6273349523544312,0.0476500429213047,0.003959582187235355 -1769682079,668722176,0.0,0.0,0.0,1.0,0.000866516144014895,-0.0001889530394691974,0.010175786912441254,0.33760616183280945,-0.04855089634656906,0.00965217687189579 -1769682079,700720384,0.0,0.0,0.0,1.0,0.0013308535562828183,-0.0001528993743704632,0.010868865996599197,0.43426838517189026,0.14435873925685883,0.017068542540073395 -1769682079,741837824,0.0,0.0,0.0,1.0,0.0013113160384818912,-0.0001448168040951714,0.01173884142190218,0.7723219990730286,0.09483594447374344,-0.0006970874965190887 -1769682079,773693696,0.0,0.0,0.0,1.0,0.0006036516861058772,-0.00013105911784805357,0.012239872477948666,0.7229822874069214,-0.24270831048488617,0.022756190970540047 -1769682079,800300544,0.0,0.0,0.0,1.0,0.00019255871302448213,-3.154399018967524e-05,0.012544565834105015,0.4823762774467468,-0.0011500492691993713,0.013350934721529484 -1769682079,848369152,0.0,0.0,0.0,1.0,-0.000657367636449635,-0.00020031466556247324,0.012625844217836857,0.5300020575523376,-0.14611920714378357,0.02513820305466652 -1769682079,866862336,0.0,0.0,0.0,1.0,-0.0009509763331152499,-0.00016267559840343893,0.012432185932993889,0.4823571443557739,-0.0015528574585914612,0.014536322094500065 -1769682079,903360768,0.0,0.0,0.0,1.0,-0.0012938342988491058,-0.00014739720791112632,0.011936536990106106,0.3850942850112915,-0.19444522261619568,0.013078073039650917 -1769682079,944939264,0.0,0.0,0.0,1.0,-0.0013001641491428018,-9.03481850400567e-06,0.011528471484780312,0.3872539699077606,0.28785648941993713,0.00409602839499712 -1769682079,967220480,0.0,0.0,0.0,1.0,-0.0015269034774973989,3.455545083852485e-06,0.011126851662993431,0.6276052594184875,0.04511380195617676,-0.002027123235166073 -1769682079,999644160,0.0,0.0,0.0,1.0,-0.001308596576564014,-0.00017099827527999878,0.010779331438243389,0.7248240113258362,0.23777775466442108,0.016132956370711327 -1769682080,49384192,0.0,0.0,0.0,1.0,-0.0008962875581346452,-0.0001647497119847685,0.010402169078588486,0.5800190567970276,0.18987998366355896,0.007665595971047878 -1769682080,68831744,0.0,0.0,0.0,1.0,-0.0007004353683441877,-0.00014855287736281753,0.010199607349932194,0.43510329723358154,0.14222069084644318,0.0027712611481547356 -1769682080,99782144,0.0,0.0,0.0,1.0,-0.0006305724382400513,-5.336725735105574e-05,0.01005448866635561,0.6747271418571472,-0.1004287451505661,0.019246507436037064 -1769682080,146134272,0.0,0.0,0.0,1.0,-0.0002551187644712627,0.00010761959129013121,0.009960582479834557,0.7250555157661438,0.23687084019184113,0.023295272141695023 -1769682080,170734848,0.0,0.0,0.0,1.0,-4.2788960854522884e-05,-1.5100327800610103e-05,0.009929078631103039,0.5330901145935059,0.3341085612773895,0.000692238099873066 -1769682080,201095168,0.0,0.0,0.0,1.0,0.000291220290819183,-6.676682824036106e-05,0.010045812465250492,0.7725651264190674,0.09114809334278107,0.014778923243284225 -1769682080,247782912,0.0,0.0,0.0,1.0,0.0008817162015475333,-1.7586024114280008e-05,0.010559584945440292,0.7728011608123779,0.0905856341123581,0.0016656061634421349 -1769682080,266414336,0.0,0.0,0.0,1.0,0.0013427307130768895,-5.993647937430069e-05,0.011220126412808895,0.5804819464683533,0.18849387764930725,0.006463656201958656 -1769682080,305361152,0.0,0.0,0.0,1.0,0.0011343464720994234,-9.885164035949856e-05,0.012257675640285015,0.7259528040885925,0.2349783331155777,-0.007726514711976051 -1769682080,347603456,0.0,0.0,0.0,1.0,0.000984351267106831,-0.00013672311615664512,0.012934167869389057,0.7216178774833679,-0.2475660741329193,0.0095681706443429 -1769682080,369229824,0.0,0.0,0.0,1.0,0.00046745705185458064,-0.000261222681729123,0.013436093926429749,0.7215911149978638,-0.2479427605867386,0.0048007541336119175 -1769682080,399466752,0.0,0.0,0.0,1.0,-0.00017018005019053817,-0.0003175678139086813,0.013687311671674252,0.6230713725090027,-0.4402279555797577,0.010487432591617107 -1769682080,449623296,0.0,0.0,0.0,1.0,-0.000792799866758287,-0.00042345005203969777,0.013649373315274715,0.6274952292442322,0.0422048419713974,0.020573880523443222 -1769682080,467485440,0.0,0.0,0.0,1.0,-0.0014182196464389563,-0.00034165926626883447,0.013352750800549984,0.4304177761077881,-0.34197744727134705,0.024785086512565613 -1769682080,500086016,0.0,0.0,0.0,1.0,-0.001616229536011815,-0.0003465242334641516,0.012895611114799976,0.8195639252662659,-0.05701449513435364,0.016938693821430206 -1769682080,542259200,0.0,0.0,0.0,1.0,-0.002114530187100172,-0.00013534263416659087,0.012226602993905544,0.6742282509803772,-0.10401159524917603,0.016806919127702713 -1769682080,571776768,0.0,0.0,0.0,1.0,-0.0018227564869448543,-0.00016132986638695002,0.011752724647521973,0.43597158789634705,0.13960407674312592,0.00036434968933463097 -1769682080,600462080,0.0,0.0,0.0,1.0,-0.0010803211480379105,-0.00012030922516714782,0.011355212889611721,0.6802658438682556,0.37767964601516724,-0.005152742378413677 -1769682080,648828416,0.0,0.0,0.0,1.0,-0.001142743043601513,-0.00019624900596681982,0.010898643173277378,0.7732071280479431,0.08678038418292999,0.003994646016508341 -1769682080,667529472,0.0,0.0,0.0,1.0,-0.0007605114369653165,-0.0002861006651073694,0.010636942461133003,0.6279308795928955,0.040070220828056335,-0.0008996827527880669 -1769682080,704863232,0.0,0.0,0.0,1.0,-0.0002460729447193444,-0.0001734898833092302,0.01040270272642374,0.5288323760032654,-0.1518395096063614,0.003531391266733408 -1769682080,744992000,0.0,0.0,0.0,1.0,-0.0003838847333099693,-0.00010132676834473386,0.010270711034536362,0.6276400089263916,0.04000760614871979,0.020546551793813705 -1769682080,767188736,0.0,0.0,0.0,1.0,-0.00018418865511193871,-8.473891648463905e-05,0.01016713585704565,0.48249542713165283,-0.006736744195222855,0.002543963957577944 -1769682080,799608064,0.0,0.0,0.0,1.0,-7.102925155777484e-05,-0.0001125623457483016,0.010089832358062267,0.7271153330802917,0.2309829592704773,0.005384648684412241 -1769682080,851192832,0.0,0.0,0.0,1.0,-4.109177825739607e-05,-0.00020655446860473603,0.009995968081057072,0.6279640793800354,0.03902209550142288,0.0014696596190333366 -1769682080,867097088,0.0,0.0,0.0,1.0,-6.968715024413541e-05,-0.0004060364153701812,0.009902638383209705,0.7197291254997253,-0.2515680491924286,0.0332174077630043 -1769682080,900081920,0.0,0.0,0.0,1.0,-3.4573167795315385e-06,-0.00030465712188743055,0.00985100120306015,0.3830401301383972,-0.19886372983455658,0.0045808954164385796 -1769682080,948035840,0.0,0.0,0.0,1.0,0.0002755494206212461,-0.0007638134993612766,0.009913954883813858,0.33668196201324463,-0.05315699428319931,0.022662809118628502 -1769682080,969871104,0.0,0.0,0.0,1.0,0.0008390722214244306,-0.0009244236280210316,0.010211905464529991,0.2372630536556244,-0.24490958452224731,0.012796838767826557 -1769682081,18500352,0.0,0.0,0.0,1.0,0.0009725176496431231,-0.0006830177153460681,0.01085669081658125,0.5821211934089661,0.18350665271282196,0.0016139950603246689 -1769682081,44119296,0.0,0.0,0.0,1.0,0.0011697569862008095,-0.0004157954244874418,0.011541812680661678,0.23699654638767242,-0.24505001306533813,0.016378451138734818 -1769682081,68686848,0.0,0.0,0.0,1.0,0.0005900544347241521,-0.00014735849981661886,0.011817403137683868,0.4367159605026245,0.1372915506362915,-0.0008928440511226654 -1769682081,101387264,0.0,0.0,0.0,1.0,0.00033797419746406376,-0.00029255542904138565,0.01216653361916542,0.6738086938858032,-0.10830091685056686,0.002375164069235325 -1769682081,146633984,0.0,0.0,0.0,1.0,-0.0003629831480793655,-0.0004346199566498399,0.012393167242407799,0.43655338883399963,0.13727237284183502,0.01816394180059433 -1769682081,166793472,0.0,0.0,0.0,1.0,-0.0008744372753426433,-0.0007422952330671251,0.012365761213004589,0.19130505621433258,-0.10012304037809372,-0.003685764968395233 -1769682081,213166848,0.0,0.0,0.0,1.0,-0.00091666413936764,-0.0007249877671711147,0.012194410897791386,0.8193138241767883,-0.06359253823757172,0.002422885037958622 -1769682081,246841856,0.0,0.0,0.0,1.0,-0.0013825123896822333,-0.0008297630120068789,0.011796364560723305,0.4368952512741089,0.13651838898658752,0.006228774320334196 -1769682081,268187904,0.0,0.0,0.0,1.0,-0.001453330391086638,-0.0006567795062437654,0.011441183276474476,0.6734111905097961,-0.10946771502494812,0.014202740974724293 -1769682081,299646208,0.0,0.0,0.0,1.0,-0.0014965217560529709,-0.00041294822585769,0.011050703004002571,0.6732708811759949,-0.109562449157238,0.02133850008249283 -1769682081,359890176,0.0,0.0,0.0,1.0,-0.0014484330313280225,-0.00032461516093462706,0.01050026435405016,0.5275822281837463,-0.15524713695049286,0.016464857384562492 -1769682081,368420864,0.0,0.0,0.0,1.0,-0.0014028864679858088,-0.0005430658929981291,0.010090481489896774,0.38203418254852295,-0.2009565830230713,0.0008701090700924397 -1769682081,401242368,0.0,0.0,0.0,1.0,-0.001157496590167284,-0.0006766972946934402,0.0096996845677495,0.5827122330665588,0.18118490278720856,0.017032623291015625 -1769682081,443579904,0.0,0.0,0.0,1.0,-0.0007832266855984926,-0.0006385519518516958,0.009176257066428661,0.5275173187255859,-0.15587295591831207,0.010457870550453663 -1769682081,468076288,0.0,0.0,0.0,1.0,-0.0007625081343576312,-0.000999479671008885,0.008782956749200821,0.5274930596351624,-0.15603597462177277,0.009248210117220879 -1769682081,500944640,0.0,0.0,0.0,1.0,-0.0006991542177274823,-0.0011583497980609536,0.008394011296331882,0.5828076004981995,0.18074724078178406,0.021767083555459976 -1769682081,545471488,0.0,0.0,0.0,1.0,-0.0003216397890355438,-0.0014087274903431535,0.007906789891421795,0.6729070544242859,-0.11093087494373322,0.02953101508319378 -1769682081,566448896,0.0,0.0,0.0,1.0,-0.0005157441482879221,-0.001521228812634945,0.007546834647655487,0.48233866691589355,-0.010654028505086899,0.008261030539870262 -1769682081,610672896,0.0,0.0,0.0,1.0,-0.00022954223095439374,-0.0013656325172632933,0.007183136884123087,0.7291871309280396,0.22472995519638062,-0.008040618151426315 -1769682081,648259840,0.0,0.0,0.0,1.0,-0.00010954577737720683,-0.0010709413327276707,0.0067368499003350735,0.4375487267971039,0.13472239673137665,-0.004606491886079311 -1769682081,667057152,0.0,0.0,0.0,1.0,-0.00047172344056889415,-0.0007837942102923989,0.006379150319844484,0.5832722187042236,0.17971740663051605,0.004967766348272562 -1769682081,700596992,0.0,0.0,0.0,1.0,-0.0002849023730959743,-0.0005506675806827843,0.006035267375409603,0.437193363904953,0.13507583737373352,0.02397962659597397 -1769682081,757301504,0.0,0.0,0.0,1.0,-0.00028501194901764393,-0.0007444003713317215,0.0056008086539804935,0.48212650418281555,-0.010927261784672737,0.022488882765173912 -1769682081,771046400,0.0,0.0,0.0,1.0,0.00028968308470211923,-0.0028286059387028217,0.005316086113452911,0.6278532147407532,0.03399144858121872,0.032031476497650146 -1769682081,802579712,0.0,0.0,0.0,1.0,-7.297081174328923e-05,-0.005284679587930441,0.005051161628216505,0.04424285516142845,-0.14511430263519287,0.04260364919900894 -1769682081,846728704,0.0,0.0,0.0,1.0,-7.270067726494744e-05,-0.005172290373593569,0.004718833602964878,0.3818286061286926,-0.2028682827949524,-0.03402724862098694 -1769682081,879350784,0.0,0.0,0.0,1.0,-6.80199300404638e-05,-0.00133746606297791,0.004455273505300283,0.5277615785598755,-0.1582755744457245,-0.04004528746008873 -1769682081,900073216,0.0,0.0,0.0,1.0,0.000523173832334578,0.00044558412628248334,0.004204919096082449,0.39311936497688293,0.279814213514328,-0.016451191157102585 -1769682081,947145472,0.0,0.0,0.0,1.0,8.433569018961862e-05,0.002842313377186656,0.0038659567944705486,0.6849561929702759,0.36917319893836975,-0.016447918489575386 -1769682081,967244032,0.0,0.0,0.0,1.0,-0.00012765788414981216,0.0025466817896813154,0.00361430156044662,0.6726729869842529,-0.11255587637424469,0.027976438403129578 -1769682082,13926656,0.0,0.0,0.0,1.0,0.0003701512177940458,0.001554106012918055,0.003388596000149846,0.6727418899536133,-0.1127338781952858,0.022056665271520615 -1769682082,49657856,0.0,0.0,0.0,1.0,-8.028979209484532e-06,-0.00010779633885249496,0.0030998766887933016,0.4379784166812897,0.13365714251995087,-0.017859887331724167 -1769682082,69134848,0.0,0.0,0.0,1.0,-8.022117253858596e-05,0.00019233868806622922,0.00291331484913826,0.29182931780815125,0.0892956405878067,1.4104880392551422e-05 -1769682082,100992000,0.0,0.0,0.0,1.0,0.0002515448140911758,-5.261308251647279e-05,0.002723891055211425,0.7740515470504761,0.07751473784446716,0.015223697759211063 -1769682082,159826688,0.0,0.0,0.0,1.0,-9.485602640779689e-05,-0.000990071683190763,0.00249188463203609,0.48278728127479553,-0.012565825134515762,-0.02652551792562008 -1769682082,171554816,0.0,0.0,0.0,1.0,-2.6220104700769298e-05,0.00018705490219872445,0.0023213112726807594,0.4823445975780487,-0.012015104293823242,0.005652530584484339 -1769682082,201535232,0.0,0.0,0.0,1.0,2.1822386770509183e-05,-0.0004004767688456923,0.0021471811924129725,0.5834219455718994,0.1787925660610199,0.021450813859701157 -1769682082,244322048,0.0,0.0,0.0,1.0,0.00016995528130792081,0.001099083572626114,0.0019370841328054667,0.4257280230522156,-0.34868124127388,0.0002763774245977402 -1769682082,278693632,0.0,0.0,0.0,1.0,-5.3275660320650786e-05,0.0010938704945147038,0.0017705238424241543,0.6281453967094421,0.03264289349317551,0.015214706771075726 -1769682082,302338816,0.0,0.0,0.0,1.0,0.00015477357374038547,-0.0007502599619328976,0.0016113142482936382,0.4820290505886078,-0.011723028495907784,0.0283184964209795 -1769682082,344004096,0.0,0.0,0.0,1.0,-0.0002702127967495471,-0.004195645451545715,0.0014069078024476767,0.5264714360237122,-0.1575017124414444,0.039867572486400604 -1769682082,366952448,0.0,0.0,0.0,1.0,-9.231572767021134e-05,-0.005381203722208738,0.0012591587146744132,0.6279146075248718,0.03287571668624878,0.03291871398687363 -1769682082,411063808,0.0,0.0,0.0,1.0,-0.00018550165987107903,-0.005396594759076834,0.0011284103384241462,0.33623984456062317,-0.05653775855898857,0.017437569797039032 -1769682082,449259520,0.0,0.0,0.0,1.0,-7.538766658399254e-05,-0.004533232189714909,0.0009627108811400831,0.4825631082057953,-0.012523209676146507,-0.01131821796298027 -1769682082,470454272,0.0,0.0,0.0,1.0,-0.00011187609197804704,-0.0034375402610749006,0.0008475693757645786,0.628242552280426,0.03237645700573921,0.008784950710833073 -1769682082,499718912,0.0,0.0,0.0,1.0,0.00019981565128546208,-0.002300666179507971,0.0007413997664116323,0.1908029466867447,-0.10182441025972366,-0.021909447386860847 -1769682082,556731648,0.0,0.0,0.0,1.0,2.5071851268876344e-05,-0.0010708679910749197,0.0006046958733350039,0.336563378572464,-0.057032451033592224,-0.00774246035143733 -1769682082,573547264,0.0,0.0,0.0,1.0,8.012641774257645e-05,-5.5613807489862666e-05,0.00047908732085488737,0.3364546298980713,-0.05688723921775818,0.0005948557518422604 -1769682082,601403648,0.0,0.0,0.0,1.0,0.00020756440062541515,0.00020683216280303895,0.00042269896948710084,0.2920990288257599,0.0887831300497055,-0.015743307769298553 -1769682082,646631680,0.0,0.0,0.0,1.0,3.027138336619828e-05,0.0005835126503370702,0.00030967796919867396,0.3807445764541626,-0.20248189568519592,0.021710822358727455 -1769682082,682195968,0.0,0.0,0.0,1.0,5.6245789892273024e-05,0.0006572404527105391,0.00023842713562771678,0.6282013654708862,0.03237808123230934,0.012288527563214302 -1769682082,700030720,0.0,0.0,0.0,1.0,-9.340788528788835e-05,0.0006247521378099918,0.00017466254939790815,0.19053295254707336,-0.10147126764059067,-0.0016502400394529104 -1769682082,744256512,0.0,0.0,0.0,1.0,9.439286077395082e-05,0.0005705072544515133,8.679472375661135e-05,0.24710676074028015,0.23536014556884766,0.017988871783018112 -1769682082,766758400,0.0,0.0,0.0,1.0,-3.196996112819761e-05,0.00043950119288638234,2.5266834200010635e-05,0.4377002716064453,0.13380016386508942,0.01158234104514122 -1769682082,811920896,0.0,0.0,0.0,1.0,-3.59791265509557e-05,0.00022019748575985432,-2.28739736485295e-05,0.29184120893478394,0.08914221078157425,0.0045453570783138275 -1769682082,847386624,0.0,0.0,0.0,1.0,0.0002851698955055326,-1.6557411072426476e-05,-7.934903260320425e-05,0.4820946455001831,-0.011938367038965225,0.024358199909329414 -1769682082,868546816,0.0,0.0,0.0,1.0,0.00018995351274497807,9.092182881431654e-05,-0.00012692251766566187,0.3363136947154999,-0.05670413002371788,0.011359259486198425 -1769682082,899733248,0.0,0.0,0.0,1.0,0.0007636380614712834,0.026446867734193802,0.00013412036059889942,0.38680705428123474,-0.21077407896518707,-0.4321650266647339 -1769682082,959776256,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682082,968217600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682083,1189120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5947694919304922e-05,-2.1751979147666134e-05,-0.0011917894007638097 -1769682083,45297664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682083,67079424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.594779132574331e-05,2.175199733756017e-05,0.0011917894007638097 -1769682083,100843776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682083,145018112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682083,166908416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.594792956893798e-05,-2.175202280341182e-05,-0.0011917894007638097 -1769682083,210521344,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682083,252890368,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682083,269690112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.594806781213265e-05,2.1752051907242276e-05,0.0011917894007638097 -1769682083,299925760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5948107829899527e-05,-2.175205918319989e-05,-0.0011917894007638097 -1769682083,356153600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682083,371346688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5948204236337915e-05,-2.175207919208333e-05,-0.0011917894007638097 -1769682083,401261824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5948246073094197e-05,-2.1752086468040943e-05,-0.0011917894007638097 -1769682083,445146624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,3.189660492353141e-05,-4.350419476395473e-05,-0.0023835788015276194 -1769682083,484638720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-0.1459352672100067,-0.044550247490406036,-0.0011397688649594784 -1769682083,500248832,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682083,553031936,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5948438885970972e-05,2.175212102883961e-05,0.0011917894007638097 -1769682083,568423168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682083,610156544,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5948522559483536e-05,2.1752139218733646e-05,0.0011917894007638097 -1769682083,650585600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5948577129165642e-05,2.1752150132670067e-05,0.0011917894007638097 -1769682083,669925120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5948618965921924e-05,-2.175215740862768e-05,-0.0011917894007638097 -1769682083,700141312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682083,749115136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.594871537236031e-05,2.175217741751112e-05,0.0011917894007638097 -1769682083,767376384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5948757209116593e-05,-2.1752184693468735e-05,-0.0011917894007638097 -1769682083,800025600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682083,846175232,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.594885361555498e-05,-2.1752204702352174e-05,-0.0011917892843484879 -1769682083,874117120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5948908185237087e-05,-2.175221379729919e-05,-0.0011917892843484879 -1769682083,901275136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.594893547007814e-05,2.1752217435278e-05,0.0011917892843484879 -1769682083,945452032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682083,967096832,0.0,0.0,0.0,1.0,1.8781616972773918e-07,1.1900870049430523e-06,2.9381942567852093e-06,0.0,-0.0,0.0 -1769682084,1591040,0.0,0.0,0.0,1.0,3.8577195482503157e-07,1.1254639957769541e-06,2.9401082883850904e-06,3.189814378856681e-05,-4.350450399215333e-05,-0.0023835785686969757 -1769682084,53830400,0.0,0.0,0.0,1.0,3.8577195482503157e-07,1.1254641094637918e-06,2.9401082883850904e-06,-1.594912464497611e-05,2.1752266547991894e-05,0.0011917892843484879 -1769682084,69840384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.594916648173239e-05,2.1752277461928315e-05,0.0011917892843484879 -1769682084,99989760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682084,147319040,0.0,0.0,0.0,1.0,1.8781625499286747e-07,1.1900870049430523e-06,2.9381944841588847e-06,0.0,-0.0,0.0 -1769682084,167347456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682084,199950080,0.0,0.0,0.0,1.0,-1.2564315454710595e-07,7.666914143555914e-07,2.939960268122377e-06,-1.5949317457852885e-05,2.1752302927779965e-05,0.0011917892843484879 -1769682084,245154048,0.0,0.0,0.0,1.0,-5.078126719126885e-07,8.038302894419758e-07,2.9370648917392828e-06,0.044517915695905685,-0.14591319859027863,0.0032589472830295563 -1769682084,269090816,0.0,0.0,0.0,1.0,-1.2564315454710595e-07,7.666914711990103e-07,2.9399604954960523e-06,0.08900391310453415,-0.2917828857898712,0.008901476860046387 -1769682084,302657024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949393855407834e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682084,344418048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682084,377261312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682084,401446656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682084,445255168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682084,467307008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682084,515792896,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682084,550869760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682084,568656896,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682084,600370688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682084,657609728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682084,671206912,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682084,702611200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682084,745089792,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682084,778501120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682084,800088576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682084,850441472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682084,869529088,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682084,910708224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682084,949907456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682084,968005888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682085,309248,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,56625408,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,70534400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682085,101980416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,145369600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,178552832,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682085,201444352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,242617344,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,268505600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682085,308949504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,344801536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,368370176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682085,400276480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,457104640,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,470277632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682085,501427456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,543836672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,578663168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682085,601424384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,653579776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,668230656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682085,715586816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,753086208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,767601664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682085,800599296,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,854455040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,868394496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682085,902194176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,945838336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682085,977769472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682086,4374784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,46510592,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,67021056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682086,114012160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,150988800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,169460224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682086,200225536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,263780864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,271913472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682086,301250816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,345116928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,367672320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682086,406958848,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682086,453281024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,468862720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682086,500257280,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,560218880,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,576051200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,600630016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,642856704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,671268096,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682086,702610944,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,747206144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,767444480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682086,800580608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,848278784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,867320320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682086,900621312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,962771968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682086,968716288,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682087,2586112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,46226688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,70904576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682087,102161408,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,144808704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,167735552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682087,201449984,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,243593728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,268052736,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682087,300843776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,350578176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,370375424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682087,400790784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,461197312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,467825920,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682087,501841664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,542622464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,567191296,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682087,601043200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,647229952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,667252224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682087,711976704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,748259584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,769778688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682087,800303104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,861694464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,869394176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682087,901801216,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,943182592,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682087,967414528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682088,1566720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682088,57739008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682088,66552832,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682088,116413952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682088,144082432,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682088,167690240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682088,200344320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682088,253566464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682088,267112192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682088,301330944,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682088,346173952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682088,380875264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682088,401437696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682088,445327104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682088,467452416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682088,510909440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682088,550889984,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682088,570718464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682088,600809984,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682088,656332288,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682088,671085056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682088,701696512,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682088,745242112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682088,778148352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682088,801236736,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682088,846893568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682088,867847680,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682088,915020800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682088,947500800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682088,968869632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682089,974592,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,60551168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,71622144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682089,102294272,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,143278080,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,168619520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682089,201644800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,245386240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,268064000,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682089,300414720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,360175360,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,373010176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682089,401531904,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,444015616,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,469026304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682089,502698752,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,544877824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,578245888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682089,602183424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,647107072,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,667830016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682089,713103104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,748694272,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,768646144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682089,801313536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,858898688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,869523968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682089,901785856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,945173504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682089,968343808,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682090,937728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,43367680,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,68318464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682090,110804736,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,149252864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,168895232,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682090,201241600,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,262012416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,270625024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682090,302916096,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,346373376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,367480064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682090,402911232,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,448682752,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,469311744,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682090,501424128,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,550449152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,568290816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682090,601570304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,655679488,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,668326912,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682090,700977152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,747012608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,779870720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682090,801827072,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,845739264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,868306944,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682090,913390080,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,950379520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682090,969762560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682091,1190400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,60015360,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,71372032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682091,102918144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,147604480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,179352576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682091,200877568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,248184064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,268024576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682091,315819264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,349074176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,368170496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682091,403470592,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,464043264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,471492352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682091,501661440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,543589376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,568183296,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682091,602468096,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,645394176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,668560128,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682091,700762624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,747931648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,768348928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682091,800759296,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,842963200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,873432320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682091,902818304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,946960384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682091,967916544,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682092,2733568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,49252608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,70161664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682092,101263872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,150342656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,168711168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682092,201744128,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,245451520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,269645312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682092,302489088,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,346228736,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,380333312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682092,400846336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,446180096,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,467685120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682092,512944384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,550346496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,568842752,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682092,601004032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,655400448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,668307712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682092,701967872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,747995648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,784634880,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,801406720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,847246080,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,867593984,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682092,900833536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,950657024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682092,969387264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682093,1694720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,46229504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,69094144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682093,101796608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,147415040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,171635968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682093,201969408,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,244904448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,282383104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682093,301704704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,346708224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,367779840,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682093,416419584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,448824320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,468235520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682093,502560256,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,554246400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,568986112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682093,602163200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,649902336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,679266048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682093,701974784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,749291520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,767998720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682093,812592640,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,848216064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,869088256,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682093,902040064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,963467776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682093,973167872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682094,2236672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,47957504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,68667136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682094,104891392,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682094,147595520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,168186112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682094,202307584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,251640576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,269573376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682094,301573376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,350397440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,375817728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,402716416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,445457408,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,468429312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682094,502643456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,548631552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,569327360,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682094,601094400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,647091200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,668291584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682094,704028928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,744999424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,771682816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682094,803543552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,846203392,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,883618304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682094,902047232,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,945339136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682094,968221696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682095,12246016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,49461248,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,70133248,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682095,101155840,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,158017280,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,173765376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,202547200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,246927616,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,278849536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682095,302323200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,350221824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,368677376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682095,414601472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,449997568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,470258688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682095,501335808,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,562229760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,571393536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682095,602961408,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,643320320,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,668193792,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682095,706045696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682095,746213632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,768340480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682095,801990144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,849941760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,869876736,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682095,901302784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,943642624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682095,969823488,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682096,2885888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682096,45609216,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682096,68712448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682096,105926912,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682096,145586176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682096,169277696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682096,201285120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682096,248489728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682096,268139008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682096,302189312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682096,347063040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682096,369359872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682096,401248000,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682096,448882688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682096,483486208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682096,501614336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682096,552724480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682096,568273664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682096,612008192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682096,649933056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682096,669118464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682096,701845504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682096,755952384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682096,770249728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682096,804998912,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682096,847458048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682096,884714496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682096,901889280,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682096,947325440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682096,968619520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682097,4386048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682097,49726976,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682097,69617152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682097,101513728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682097,161211136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682097,171282432,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682097,205092864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682097,243603200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,1.5949402950354852e-05,-2.1752288375864737e-05,-0.0011917892843484879 -1769682097,268856576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682097,353511680,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682097,377361664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-1.5949402950354852e-05,2.1752288375864737e-05,0.0011917892843484879 -1769682097,403884288,0.0,0.0,0.0,1.0,-0.0035942692775279284,-0.009212064556777477,-9.924649202730507e-05,0.33446431159973145,-0.05416807532310486,0.15088599920272827 -1769682097,407940864,0.0,0.0,0.0,1.0,-0.004390263464301825,-0.01550078485161066,-0.000194189342437312,0.24580679833889008,0.2371724247932434,0.11813031136989594 -1769682097,445907456,0.0,0.0,0.0,1.0,-0.0030720618087798357,-0.023568470031023026,-0.0004202936834190041,-0.19129860401153564,0.1026206836104393,0.06623376905918121 -1769682097,468826624,0.0,0.0,0.0,1.0,-0.002148950472474098,-0.02424110472202301,-0.0004901762586086988,-0.0004899436025880277,0.000766909564845264,0.04290572181344032 -1769682097,501429504,0.0,0.0,0.0,1.0,-0.0012180343037471175,-0.02311142534017563,-0.0006064481567591429,-0.6725927591323853,0.11323709040880203,-0.029489953070878983 -1769682097,550935040,0.0,0.0,0.0,1.0,-0.00031764627783559263,-0.018819911405444145,-0.0007425482617691159,-0.6278324723243713,-0.03313760831952095,-0.0509251169860363 -1769682097,568925440,0.0,0.0,0.0,1.0,0.0001839823235059157,-0.014646115712821484,-0.0008361560176126659,-0.33587536215782166,0.055763281881809235,-0.06138288974761963 -1769682097,601410304,0.0,0.0,0.0,1.0,0.0009612255962565541,-0.010252624750137329,-0.0009052776731550694,-0.5707262754440308,0.30259937047958374,-0.09044621139764786 -1769682097,645191680,0.0,0.0,0.0,1.0,0.0012493893736973405,-0.005491847172379494,-0.0010041891364380717,-0.7166538238525391,0.25791454315185547,-0.0955447107553482 -1769682097,670521856,0.0,0.0,0.0,1.0,0.0013091729488223791,-0.0028898646123707294,-0.0010454467264935374,-0.42493635416030884,0.34730109572410583,-0.0802428126335144 -1769682097,702001664,0.0,0.0,0.0,1.0,0.0012595225125551224,-0.0008128851186484098,-0.0010907927062362432,-0.6725398302078247,0.11283449083566666,-0.043585922569036484 -1769682097,755006464,0.0,0.0,0.0,1.0,0.0011998306727036834,0.00039907809696160257,-0.001136689679697156,-0.8185750246047974,0.06842678040266037,-0.032128818333148956 -1769682097,770576384,0.0,0.0,0.0,1.0,0.001376171363517642,0.0009022353915497661,-0.0011475383071228862,-0.3361400067806244,0.05610959604382515,-0.03730052709579468 -1769682097,803006208,0.0,0.0,0.0,1.0,0.000923873798456043,0.0008108473266474903,-0.0011510413605719805,-0.482230007648468,0.011841455474495888,-0.01870040036737919 -1769682097,847173376,0.0,0.0,0.0,1.0,0.0010836757719516754,0.00040210873703472316,-0.0011531247291713953,-0.48229217529296875,0.01194760575890541,-0.011559967882931232 -1769682097,869215488,0.0,0.0,0.0,1.0,0.0004567274881992489,0.00010311765799997374,-0.0011407763231545687,-0.39313533902168274,-0.2797938585281372,-0.001928416546434164 -1769682097,913400064,0.0,0.0,0.0,1.0,0.0005293840076774359,-0.0002157453418476507,-0.0011110439663752913,-0.3364778459072113,0.05674684792757034,0.0008164402097463608 -1769682097,952013056,0.0,0.0,0.0,1.0,0.00012583320494741201,-0.001178049948066473,-0.0011111559579148889,-0.8634936213493347,0.21475431323051453,-0.0006400486454367638 -1769682097,971014656,0.0,0.0,0.0,1.0,0.00012787045852746814,-0.002143397694453597,-0.0010982590029016137,-0.6729643940925598,0.11344149708747864,0.001689014956355095 -1769682098,1625088,0.0,0.0,0.0,1.0,-0.00017273909179493785,-0.002586553106084466,-0.0010955261532217264,-0.48247912526130676,0.012250160798430443,0.00997002050280571 -1769682098,63450368,0.0,0.0,0.0,1.0,-0.0001889695122372359,-0.003471693489700556,-0.0010993435280397534,-0.33649638295173645,0.0567166730761528,0.002104027196764946 -1769682098,71071744,0.0,0.0,0.0,1.0,-2.6127401724806987e-05,-0.003886898048222065,-0.0010948959970846772,-0.23523470759391785,0.2472773790359497,0.0019097139593213797 -1769682098,103282432,0.0,0.0,0.0,1.0,-0.000331885035848245,-0.0037757502868771553,-0.0010906908428296447,-0.5837534070014954,-0.17833438515663147,0.012766038067638874 -1769682098,145004800,0.0,0.0,0.0,1.0,-5.193257675273344e-05,-0.003606291487812996,-0.001105829724110663,-0.6283544301986694,-0.03254355490207672,0.0062704067677259445 -1769682098,169245952,0.0,0.0,0.0,1.0,-0.0002216405118815601,-0.003887301543727517,-0.0011086781742051244,-0.6283526420593262,-0.03256448358297348,0.006340145133435726 -1769682098,205999872,0.0,0.0,0.0,1.0,-9.424093150300905e-05,-0.0037102338392287493,-0.001133360667154193,-0.6282482743263245,-0.032830312848091125,-0.00667549530044198 -1769682098,245369600,0.0,0.0,0.0,1.0,-5.401237649493851e-05,-0.0037787719629704952,-0.0011591230286285281,-0.48233652114868164,0.011797768995165825,-0.0074867671355605125 -1769682098,269176064,0.0,0.0,0.0,1.0,-4.4299747969489545e-05,-0.003996185027062893,-0.0011913120979443192,-0.42577168345451355,0.3482299745082855,-0.011900736019015312 -1769682098,301660672,0.0,0.0,0.0,1.0,-2.5839412046479993e-05,-0.004180410876870155,-0.0012320384848862886,-0.8634474873542786,0.214081272482872,-0.017438767477869987 -1769682098,357875712,0.0,0.0,0.0,1.0,-0.0004452480934560299,-0.0038632263895124197,-0.001300695352256298,-0.4822543263435364,0.011523161083459854,-0.019212618470191956 -1769682098,373480960,0.0,0.0,0.0,1.0,-0.00022963744413573295,-0.0028140905778855085,-0.0013412267435342073,-0.538774847984314,-0.32495826482772827,-0.01466422714293003 -1769682098,401848576,0.0,0.0,0.0,1.0,-0.0002898047387134284,-0.002444206504151225,-0.0013872144045308232,-0.6846684217453003,-0.3696524202823639,-0.01367250643670559 -1769682098,447592448,0.0,0.0,0.0,1.0,-0.0002926813904196024,-0.0023072464391589165,-0.0014515307266265154,-0.818881630897522,0.06826967000961304,-0.002191992476582527 -1769682098,473146368,0.0,0.0,0.0,1.0,-5.589490319835022e-05,-0.0024905919563025236,-0.0015085857594385743,-0.875407338142395,-0.26810091733932495,0.009511998854577541 -1769682098,504124416,0.0,0.0,0.0,1.0,-0.00016419112216681242,-0.002443824429064989,-0.0015624344814568758,-0.7740467190742493,-0.07801008969545364,-0.018200542777776718 -1769682098,546977024,0.0,0.0,0.0,1.0,-0.00012952768884133548,-0.002428098116070032,-0.001669149729423225,-0.717608630657196,0.25840914249420166,-0.02262512966990471 -1769682098,568444160,0.0,0.0,0.0,1.0,-1.5270108633558266e-05,-0.0020664806943386793,-0.0017463038675487041,-0.6729509830474854,0.11266706138849258,-0.011299953795969486 -1769682098,605028608,0.0,0.0,0.0,1.0,-4.802025796379894e-05,-0.0009664896642789245,-0.0018429955234751105,-0.7294076085090637,-0.22370754182338715,0.0015878574922680855 -1769682098,651876864,0.0,0.0,0.0,1.0,0.0001426935486961156,-0.000559210660867393,-0.0019273879006505013,-0.7741557955741882,-0.07787953317165375,-0.0001347418874502182 -1769682098,669231360,0.0,0.0,0.0,1.0,0.00010706937609938905,0.0010840255999937654,-0.001981232548132539,-0.8634762763977051,0.2132778763771057,-0.03341173380613327 -1769682098,702919680,0.0,0.0,0.0,1.0,0.00022024173813406378,0.0030768888536840677,-0.00201651593670249,-0.8187615871429443,0.06748738884925842,-0.024584822356700897 -1769682098,749486080,0.0,0.0,0.0,1.0,0.0002000001259148121,0.0035721284803003073,-0.0020646711345762014,-1.0658433437347412,-0.16767330467700958,-0.004269249737262726 -1769682098,769249024,0.0,0.0,0.0,1.0,-0.00010547427518758923,0.0018835890805348754,-0.0022302705328911543,-0.7293415069580078,-0.223944753408432,0.0013754572719335556 -1769682098,801976064,0.0,0.0,0.0,1.0,-0.0007053626468405128,0.0001254828239325434,-0.0024228033144026995,-0.7626826763153076,0.40425968170166016,-0.004241228569298983 -1769682098,850634752,0.0,0.0,0.0,1.0,-0.0011561919236555696,-0.0017369827255606651,-0.0026251019444316626,-0.437642365694046,-0.13427427411079407,0.010125670582056046 -1769682098,883041792,0.0,0.0,0.0,1.0,-0.0011896262876689434,-0.003045374993234873,-0.002803270472213626,-0.9199260473251343,-0.12322605401277542,-0.005236342549324036 -1769682098,902987264,0.0,0.0,0.0,1.0,-0.0011527196038514376,-0.003286972176283598,-0.0028717154636979103,-1.0657519102096558,-0.1681678295135498,-0.007741933688521385 -1769682098,946468608,0.0,0.0,0.0,1.0,-0.0013209335738793015,-0.003210346680134535,-0.003007367718964815,-0.7179243564605713,0.2579769194126129,-0.010548912920057774 -1769682098,969476096,0.0,0.0,0.0,1.0,-0.0017389331478625536,-0.00295790727250278,-0.0031023581977933645,-0.8749501705169678,-0.26949799060821533,-0.014014897868037224 -1769682099,8695040,0.0,0.0,0.0,1.0,-0.0014922141563147306,-0.0017518012318760157,-0.0031942285131663084,-0.9646123051643372,0.02180035412311554,-0.0316249281167984 -1769682099,50125568,0.0,0.0,0.0,1.0,-0.0014122892171144485,-0.0010527921840548515,-0.003240263322368264,-1.200433611869812,0.2689321041107178,-0.007667265832424164 -1769682099,69210880,0.0,0.0,0.0,1.0,-0.0013172563631087542,0.00038947875145822763,-0.00326451170258224,-1.2002086639404297,0.2681197226047516,-0.04698093980550766 -1769682099,101679104,0.0,0.0,0.0,1.0,-0.0014343212824314833,0.0016549568390473723,-0.003276060102507472,-0.8188644647598267,0.06662409007549286,-0.021936960518360138 -1769682099,158445056,0.0,0.0,0.0,1.0,-0.0011765029048547149,0.0029795279260724783,-0.003251519985496998,-0.6620452404022217,0.5937214493751526,-0.035027433186769485 -1769682099,171483904,0.0,0.0,0.0,1.0,-0.001424269750714302,0.0020163501612842083,-0.0032704004552215338,-0.6283668279647827,-0.03366255760192871,0.021476127207279205 -1769682099,201738496,0.0,0.0,0.0,1.0,-0.0015336412470787764,0.0007443242939189076,-0.0032873153686523438,-0.5275970101356506,0.15720880031585693,0.02832215093076229 -1769682099,249019648,0.0,0.0,0.0,1.0,-0.0016569863073527813,-0.001478137681260705,-0.0033154713455587626,-0.7184033393859863,0.25788673758506775,0.024136770516633987 -1769682099,270501120,0.0,0.0,0.0,1.0,-0.0016569672152400017,-0.002399055752903223,-0.0033210234250873327,-0.7183728218078613,0.25766903162002563,0.015850752592086792 -1769682099,301893888,0.0,0.0,0.0,1.0,-0.001674933242611587,-0.0029385818634182215,-0.0033234606962651014,-0.7632899284362793,0.40301257371902466,-0.0071557327173650265 -1769682099,345995008,0.0,0.0,0.0,1.0,-0.0016402594046667218,-0.003417858388274908,-0.0033103683963418007,-0.773967981338501,-0.07950787991285324,-0.0035440754145383835 -1769682099,369658624,0.0,0.0,0.0,1.0,-0.0015401772689074278,-0.0032554026693105698,-0.0032985075376927853,-0.8189442753791809,0.06596746295690536,-0.018178025260567665 -1769682099,405369088,0.0,0.0,0.0,1.0,-0.0015800312394276261,-0.002347138710319996,-0.0032386579550802708,-0.6732242703437805,0.1110716313123703,-0.010809764266014099 -1769682099,451331328,0.0,0.0,0.0,1.0,-0.0018288110150024295,-0.0017397969495505095,-0.0031844470649957657,-0.9647760391235352,0.020804911851882935,-0.011001694947481155 -1769682099,469133568,0.0,0.0,0.0,1.0,-0.0016935245366767049,-0.0014321833150461316,-0.003134234109893441,-0.6733042597770691,0.11110666394233704,-0.0011950256302952766 -1769682099,502968832,0.0,0.0,0.0,1.0,-0.002084069885313511,-0.0015585612272843719,-0.003085402073338628,-0.6731142401695251,0.11047784984111786,-0.03453020006418228 -1769682099,558326016,0.0,0.0,0.0,1.0,-0.001839080941863358,-0.0013808204093948007,-0.003007769351825118,-1.0655419826507568,-0.17001208662986755,0.01322808489203453 -1769682099,576232704,0.0,0.0,0.0,1.0,-0.0020370748825371265,-0.001352333347313106,-0.0029349213000386953,-0.7738392949104309,-0.08028984069824219,-0.015131523832678795 -1769682099,601661952,0.0,0.0,0.0,1.0,-0.0021679799538105726,-0.0012965186033397913,-0.002915146993473172,-0.6280866265296936,-0.035162344574928284,-0.01501695066690445 -1769682099,649403136,0.0,0.0,0.0,1.0,-0.002067259745672345,-0.0014127708273008466,-0.0028613728936761618,-0.7637221217155457,0.4022105634212494,-0.006385795772075653 -1769682099,672446720,0.0,0.0,0.0,1.0,-0.0020605057943612337,-0.0014444964472204447,-0.0028033133130520582,-0.864219605922699,0.2109868824481964,-0.01803489401936531 -1769682099,702805760,0.0,0.0,0.0,1.0,-0.0021036872640252113,-0.0013994124019518495,-0.002757288748398423,-0.9648299217224121,0.020166931673884392,-0.004668766632676125 -1769682099,745502976,0.0,0.0,0.0,1.0,-0.002188032027333975,-0.0013548695715144277,-0.0026228793431073427,-1.2110258340835571,-0.21624025702476501,-0.010459324344992638 -1769682099,768786944,0.0,0.0,0.0,1.0,-0.002338727004826069,-0.0012216848554089665,-0.0025076919700950384,-0.8743366003036499,-0.2715185880661011,-0.005237503442913294 -1769682099,805918976,0.0,0.0,0.0,1.0,-0.0021143555641174316,-0.0012328255688771605,-0.002295335754752159,-0.7738606333732605,-0.08056780695915222,-0.0030075320973992348 -1769682099,848960768,0.0,0.0,0.0,1.0,-0.0021676025353372097,-0.0013684419682249427,-0.0021328406874090433,-0.7186797857284546,0.2561396658420563,-0.002198224887251854 -1769682099,869601792,0.0,0.0,0.0,1.0,-0.0019692531786859035,-0.0013779448345303535,-0.0019388969521969557,-0.6734898686408997,0.11057434976100922,0.01118707936257124 -1769682099,969692160,0.0,0.0,0.0,1.0,-0.0022702058777213097,-0.001054425141774118,-0.0016871477710083127,-0.819172203540802,0.0651274248957634,0.004009981639683247 -1769682099,984181248,0.0,0.0,0.0,1.0,-0.002447035163640976,-0.0008972973446361721,-0.0014442182146012783,-1.2010241746902466,0.2654547691345215,-0.027468308806419373 -1769682099,998592256,0.0,0.0,0.0,1.0,-0.002371728653088212,-0.0009890375658869743,-0.0013336226111277938,-1.1558148860931396,0.1199435219168663,-0.011745497584342957 -1769682100,5492224,0.0,0.0,0.0,1.0,-0.0024045919999480247,-0.0005317731993272901,-0.0011168890632689,-0.6733190417289734,0.1098623126745224,-0.02444421499967575 -1769682100,47747328,0.0,0.0,0.0,1.0,-0.0011970348423346877,-0.00045803480315953493,-0.000573114026337862,-1.100770115852356,0.45668187737464905,-0.007163830101490021 -1769682100,68109056,0.0,0.0,0.0,1.0,-0.0007197527447715402,-0.00036745425313711166,-0.00020001971279270947,-0.9649210572242737,0.01976802572607994,0.010024460032582283 -1769682100,102001152,0.0,0.0,0.0,1.0,-0.0001601549593033269,-0.0003353188803885132,0.00028930322150699794,-0.6735402345657349,0.1104811429977417,0.016117241233587265 -1769682100,151415808,0.0,0.0,0.0,1.0,0.00019495657761581242,-3.110950274276547e-05,0.000843699905090034,-0.9649967551231384,0.020022498443722725,0.024339640513062477 -1769682100,170777600,0.0,0.0,0.0,1.0,0.0003013648383785039,0.00021466650650836527,0.0012045784387737513,-0.7738362550735474,-0.08080659061670303,-0.0028553111478686333 -1769682100,202674688,0.0,0.0,0.0,1.0,0.0001511279260739684,0.0005936937523074448,0.0015188864199444652,-0.6280969381332397,-0.0355750173330307,-0.008762684650719166 -1769682100,245246208,0.0,0.0,0.0,1.0,0.000505977775901556,0.0008223271579481661,0.001907716621644795,-0.9194823503494263,-0.12622816860675812,-0.01726021245121956 -1769682100,272992768,0.0,0.0,0.0,1.0,0.00029365773661993444,0.0008796540787443519,0.0021559910383075476,-0.81905198097229,0.06483703851699829,-0.017379125580191612 -1769682100,303249408,0.0,0.0,0.0,1.0,0.0005372323794290423,0.0007481602369807661,0.0024170971009880304,-0.7186928391456604,0.2561786472797394,0.0003805598244071007 -1769682100,347840000,0.0,0.0,0.0,1.0,0.0005313189467415214,0.0007398420129902661,0.002767267869785428,-0.6281004548072815,-0.0354008674621582,-0.010021451860666275 -1769682100,368942848,0.0,0.0,0.0,1.0,0.0003993733262177557,0.0009110952960327268,0.0030378964729607105,-0.9647752046585083,0.019855046644806862,-0.015145853161811829 -1769682100,405505024,0.0,0.0,0.0,1.0,0.0004436213057488203,0.0006996787269599736,0.0034287525340914726,-0.8743801116943359,-0.27141332626342773,-0.007660040631890297 -1769682100,445064192,0.0,0.0,0.0,1.0,0.0005566959735006094,0.0006334299687296152,0.003723727772012353,-0.8190498352050781,0.06534306704998016,-0.011534763500094414 -1769682100,470792448,0.0,0.0,0.0,1.0,0.00032312137773260474,0.0007897873874753714,0.004016596358269453,-0.9648065567016602,0.020313024520874023,-0.008068209514021873 -1769682100,502073344,0.0,0.0,0.0,1.0,0.00016966172552201897,0.0007879825425334275,0.004298531450331211,-0.6281858086585999,-0.03485238552093506,0.0018204869702458382 -1769682100,564418048,0.0,0.0,0.0,1.0,0.00021975382696837187,0.000871744763571769,0.004685272928327322,-0.9647262096405029,0.020400691777467728,-0.02123577706515789 -1769682100,572893952,0.0,0.0,0.0,1.0,0.0003412430523894727,0.0009352345950901508,0.004961565136909485,-0.6732792258262634,0.11102256178855896,-0.005564630497246981 -1769682100,603097856,0.0,0.0,0.0,1.0,-0.0005590067012235522,0.0014774248702451587,0.005119172856211662,-0.6278581619262695,-0.03552059829235077,-0.059027768671512604 -1769682100,647624960,0.0,0.0,0.0,1.0,-0.0018127014627680182,0.0025662812404334545,0.0052802423015236855,-0.7737653851509094,-0.08010927587747574,-0.03775344416499138 -1769682100,673396736,0.0,0.0,0.0,1.0,-0.0021972847171127796,0.0030629655811935663,0.005443782079964876,-0.33645686507225037,0.055272381752729416,-0.02906951680779457 -1769682100,701988096,0.0,0.0,0.0,1.0,-0.002605080371722579,0.0036075233947485685,0.0056363437324762344,-0.7738834619522095,-0.079586461186409,-0.0212264247238636 -1769682100,748855808,0.0,0.0,0.0,1.0,-0.0032478782813996077,0.0037543370854109526,0.005908552091568708,-0.6730867624282837,0.11142183840274811,-0.020146150141954422 -1769682100,770003200,0.0,0.0,0.0,1.0,-0.003439569380134344,0.0036398712545633316,0.006114580202847719,-0.9757440090179443,-0.4605241119861603,-0.0012684185057878494 -1769682100,804223488,0.0,0.0,0.0,1.0,-0.003461763495579362,0.0036658993922173977,0.006368372589349747,-1.1104971170425415,-0.023076757788658142,-0.023370476439595222 -1769682100,845643520,0.0,0.0,0.0,1.0,-0.0034970019478350878,0.003457664279267192,0.006575589068233967,-1.0097135305404663,0.1682509481906891,0.000463167205452919 -1769682100,870217984,0.0,0.0,0.0,1.0,-0.0035185408778488636,0.0032306259963661432,0.0068065631203353405,-0.5273043513298035,0.15723076462745667,0.004895927384495735 -1769682100,901863168,0.0,0.0,0.0,1.0,-0.003690251847729087,0.003083164105191827,0.007058833260089159,-0.4824594259262085,0.011522944085299969,0.00855272077023983 -1769682100,960941056,0.0,0.0,0.0,1.0,-0.0033440240658819675,0.0030381917022168636,0.007449386175721884,-0.8187745809555054,0.06750783324241638,-0.02321886457502842 -1769682100,976186624,0.0,0.0,0.0,1.0,-0.003420490538701415,0.0031455415301024914,0.007871574722230434,-0.7741495370864868,-0.07781711220741272,-0.0017740949988365173 -1769682101,5136128,0.0,0.0,0.0,1.0,-0.0034104730002582073,0.0032226296607404947,0.008197613060474396,-0.7741434574127197,-0.07768157124519348,-0.005430570803582668 -1769682101,45176832,0.0,0.0,0.0,1.0,-0.0033456087112426758,0.00316733680665493,0.008515976369380951,-0.8635166883468628,0.21436114609241486,-0.005632852204144001 -1769682101,76346112,0.0,0.0,0.0,1.0,-0.0033584574703127146,0.003009845968335867,0.008920865133404732,-0.6283649206161499,-0.032404009252786636,0.007891627959907055 -1769682101,102096384,0.0,0.0,0.0,1.0,-0.003385270480066538,0.0030016088858246803,0.009117134846746922,-0.2918347120285034,-0.08922041207551956,-0.0032064788974821568 -1769682101,145825792,0.0,0.0,0.0,1.0,-0.004932026378810406,0.0026386985555291176,0.009311552159488201,-0.2470783144235611,-0.2355477511882782,-0.03660920634865761 -1769682101,169196032,0.0,0.0,0.0,1.0,-0.006011568941175938,0.0020076886285096407,0.009419317357242107,-0.875579833984375,-0.26727157831192017,-0.0229780413210392 -1769682101,205315072,0.0,0.0,0.0,1.0,-0.006522688549011946,0.0013735821703448892,0.0095869405195117,-0.8185506463050842,0.06939176470041275,-0.029706252738833427 -1769682101,251753216,0.0,0.0,0.0,1.0,-0.006917068734765053,0.0011250256793573499,0.009739842265844345,-0.6726782917976379,0.11427871137857437,-0.01135382428765297 -1769682101,269931776,0.0,0.0,0.0,1.0,-0.0058903140015900135,0.00039032549830153584,0.009891903959214687,-0.38100600242614746,0.2038314938545227,0.0373314693570137 -1769682101,356883968,0.0,0.0,0.0,1.0,-0.004613176919519901,-0.0009918306022882462,0.01017887145280838,-0.8189345598220825,0.0710221454501152,0.031096823513507843 -1769682101,370817792,0.0,0.0,0.0,1.0,-0.004543237388134003,-0.001899887342005968,0.01048864796757698,-1.0092946290969849,0.1733735203742981,0.04630642011761665 -1769682101,392927232,0.0,0.0,0.0,1.0,-0.004431547597050667,-0.0022020009346306324,0.010710932314395905,-0.4824720025062561,0.013726795092225075,0.016553107649087906 -1769682101,402841856,0.0,0.0,0.0,1.0,-0.0039495183154940605,-0.002139451215043664,0.010873784311115742,-0.5706585049629211,0.3057378828525543,-0.002112730871886015 -1769682101,453012224,0.0,0.0,0.0,1.0,-0.004152173642069101,-0.002185413846746087,0.011299504898488522,-0.5263795852661133,0.15991009771823883,-0.005790151655673981 -1769682101,468650240,0.0,0.0,0.0,1.0,-0.004148347768932581,-0.0021685140673071146,0.011467475444078445,-0.8185792565345764,0.07203326374292374,0.0004198262467980385 -1769682101,514448128,0.0,0.0,0.0,1.0,-0.003816411131992936,-0.0019763547461479902,0.011723292991518974,-0.7304553985595703,-0.22011050581932068,-0.014344786293804646 -1769682101,553115904,0.0,0.0,0.0,1.0,-0.0040869261138141155,-0.0017564737936481833,0.012040476314723492,-0.6282866597175598,-0.029821641743183136,-0.02428661659359932 -1769682101,570317824,0.0,0.0,0.0,1.0,-0.003716899547725916,-0.0015534855192527175,0.012253860011696815,-0.6283482313156128,-0.029502371326088905,-0.017108194530010223 -1769682101,602212608,0.0,0.0,0.0,1.0,-0.0038092101458460093,-0.0013275389792397618,0.012437934055924416,-0.7745703458786011,-0.0729958638548851,-0.01041348185390234 -1769682101,663361536,0.0,0.0,0.0,1.0,-0.0037737982347607613,-0.0013160665985196829,0.012696769088506699,-0.5260047316551208,0.1611081212759018,-0.006695793475955725 -1769682101,671689984,0.0,0.0,0.0,1.0,-0.004007814917713404,-0.0012740634847432375,0.012911999598145485,-0.3360513746738434,0.05877833068370819,-0.006546664983034134 -1769682101,702881280,0.0,0.0,0.0,1.0,-0.0038234535604715347,-0.0013208487071096897,0.013147587887942791,-0.5259039402008057,0.16156025230884552,-0.0030417493544518948 -1769682101,749242624,0.0,0.0,0.0,1.0,-0.001738396822474897,-0.0005180700682103634,0.013884998857975006,-0.6722729206085205,0.11866918951272964,0.028703970834612846 -1769682101,768694784,0.0,0.0,0.0,1.0,-0.000828922085929662,0.0001836232258938253,0.014444083906710148,-0.6287857294082642,-0.02722538821399212,0.036643899977207184 -1769682101,803372032,0.0,0.0,0.0,1.0,-0.000262443907558918,0.0007730423239991069,0.014902404509484768,-0.7315221428871155,-0.21688412129878998,0.01666928082704544 -1769682101,846708480,0.0,0.0,0.0,1.0,2.6748835807666183e-05,0.0013103191740810871,0.015373134054243565,-0.7314700484275818,-0.21675439178943634,-0.010778434574604034 -1769682101,872194048,0.0,0.0,0.0,1.0,9.485958435107023e-05,0.0013411262771114707,0.015626072883605957,-0.5852532982826233,-0.17313611507415771,-0.00912211649119854 -1769682101,903743744,0.0,0.0,0.0,1.0,0.0005072206258773804,0.0013599207159131765,0.015872646123170853,-0.29267287254333496,-0.08639714121818542,-0.005767414346337318 -1769682101,949552128,0.0,0.0,0.0,1.0,0.0006282436661422253,0.0013967333361506462,0.016028394922614098,-0.3357888162136078,0.060079071670770645,-0.010149562731385231 -1769682101,971190016,0.0,0.0,0.0,1.0,0.0007631261833012104,0.0012485100887715816,0.016165412962436676,-0.5251163244247437,0.1634988635778427,-0.021008532494306564 -1769682102,2502912,0.0,0.0,0.0,1.0,0.0005758245242759585,0.0011475509963929653,0.016306139528751373,-0.43923696875572205,-0.12889009714126587,-0.0027364741545170546 -1769682102,63518976,0.0,0.0,0.0,1.0,0.0004921550862491131,0.0010478374315425754,0.016513364389538765,-0.671428382396698,0.12133362889289856,-0.013233417645096779 -1769682102,71917312,0.0,0.0,0.0,1.0,0.00043146172538399696,0.001109844888560474,0.01660255715250969,-0.6712759733200073,0.12151498347520828,-0.026368457823991776 -1769682102,104204032,0.0,0.0,0.0,1.0,-0.0018586262594908476,0.002258189721032977,0.016567640006542206,-0.8785040974617004,-0.256978839635849,-0.061610184609889984 -1769682102,148331776,0.0,0.0,0.0,1.0,-0.0027461617719382048,0.0033192515838891268,0.016596300527453423,-0.6709598302841187,0.12202271819114685,-0.05030708387494087 -1769682102,169152256,0.0,0.0,0.0,1.0,-0.003520695026963949,0.003940333146601915,0.01666373386979103,-0.6283486485481262,-0.024176882579922676,-0.04957948625087738 -1769682102,208229376,0.0,0.0,0.0,1.0,-0.004128080327063799,0.004473335575312376,0.01679966039955616,-0.5861660242080688,-0.16992680728435516,-0.014349039644002914 -1769682102,250356992,0.0,0.0,0.0,1.0,-0.004459606017917395,0.004502578638494015,0.01691334694623947,-0.4820280373096466,0.01932220160961151,-0.015769172459840775 -1769682102,269294592,0.0,0.0,0.0,1.0,-0.0047257812693715096,0.004611368291079998,0.017019646242260933,-0.4397827982902527,-0.12694962322711945,-0.006743879523128271 -1769682102,303016960,0.0,0.0,0.0,1.0,-0.004904582165181637,0.004519055597484112,0.01711057499051094,-0.2931723892688751,-0.08456407487392426,-0.012097876518964767 -1769682102,359331584,0.0,0.0,0.0,1.0,-0.005356566049158573,0.004430835135281086,0.01722050830721855,-0.5663052201271057,0.31358009576797485,-0.007850904949009418 -1769682102,373288704,0.0,0.0,0.0,1.0,-0.005318757612258196,0.00433594174683094,0.017302505671977997,-0.48218679428100586,0.02068137563765049,0.0101873017847538 -1769682102,404253440,0.0,0.0,0.0,1.0,-0.005420604255050421,0.004073420539498329,0.01740380749106407,-0.44022125005722046,-0.12571173906326294,0.009581480175256729 -1769682102,445373696,0.0,0.0,0.0,1.0,-0.00525696063414216,0.004100439604371786,0.017488284036517143,-0.6918811798095703,-0.35595378279685974,0.0085437698289752 -1769682102,475130368,0.0,0.0,0.0,1.0,-0.0039656274020671844,0.00483675254508853,0.017683900892734528,-0.4826706051826477,0.022125329822301865,0.07078738510608673 -1769682102,502497792,0.0,0.0,0.0,1.0,0.00036888851900584996,0.007489815354347229,0.018106993287801743,-0.29426199197769165,-0.08260161429643631,0.08052969723939896 -1769682102,555626752,0.0,0.0,0.0,1.0,0.0026254169642925262,0.009894107468426228,0.01849946193397045,-0.7760849595069885,-0.06069009378552437,0.04604917764663696 -1769682102,569503488,0.0,0.0,0.0,1.0,0.004819161724299192,0.011035059578716755,0.018665803596377373,-0.7762228846549988,-0.06015390157699585,0.05534111708402634 -1769682102,603131136,0.0,0.0,0.0,1.0,0.007917496375739574,0.010325534269213676,0.018738849088549614,-0.6296432018280029,-0.018031643703579903,0.07874439656734467 -1769682102,650306816,0.0,0.0,0.0,1.0,0.009894224815070629,0.009214340709149837,0.018755722790956497,-0.441419392824173,-0.12318559736013412,0.07200156152248383 -1769682102,672034048,0.0,0.0,0.0,1.0,0.010811899788677692,0.008338826708495617,0.018782857805490494,-0.5646480917930603,0.3172163963317871,0.014508607797324657 -1769682102,702425088,0.0,0.0,0.0,1.0,0.011684868484735489,0.00785779394209385,0.01885933242738247,-0.6289790868759155,-0.017600983381271362,0.005496155470609665 -1769682102,751551744,0.0,0.0,0.0,1.0,0.012282132171094418,0.0073890541680157185,0.01909715309739113,-0.25277701020240784,-0.22917057573795319,-0.00954208243638277 -1769682102,769185024,0.0,0.0,0.0,1.0,0.01273933332413435,0.007075359113514423,0.019386621192097664,-0.3345560133457184,0.06463980674743652,-0.036679934710264206 -1769682102,802413824,0.0,0.0,0.0,1.0,0.012893161736428738,0.007162188179790974,0.01970640756189823,-0.6081958413124084,-0.09031985700130463,-0.028344785794615746 -1769682102,846672896,0.0,0.0,0.0,1.0,0.012362807989120483,0.00720034446567297,0.020093193277716637,-0.4409465491771698,-0.12248647958040237,-0.01776808314025402 -1769682102,874913792,0.0,0.0,0.0,1.0,0.012399217113852501,0.0073575410060584545,0.020364586263895035,-0.5678684711456299,-0.23623283207416534,-0.011807632632553577 -1769682102,903152128,0.0,0.0,0.0,1.0,0.011806264519691467,0.007460825145244598,0.02044171281158924,-0.42072033882141113,-0.19559937715530396,-0.023756250739097595 -1769682102,946562560,0.0,0.0,0.0,1.0,0.01003074087202549,0.007613120600581169,0.020290818065404892,-0.7551158666610718,-0.12960919737815857,-0.0646052211523056 -1769682102,969485312,0.0,0.0,0.0,1.0,0.004918613471090794,0.00523643521592021,0.019613422453403473,-0.4203187823295593,-0.19580410420894623,-0.077471524477005 -1769682103,4190464,0.0,0.0,0.0,1.0,0.0022090261336416006,0.002873018616810441,0.01900017261505127,-0.4206371009349823,-0.19527974724769592,-0.06320703774690628 -1769682103,47913216,0.0,0.0,0.0,1.0,0.0005704008508473635,0.0017458177171647549,0.01866713911294937,-0.3809302747249603,-0.3418237864971161,-0.03312988206744194 -1769682103,69614592,0.0,0.0,0.0,1.0,-0.0001623165881028399,0.0011923146666958928,0.01838850788772106,-0.42136070132255554,-0.19421207904815674,-0.02271852269768715 -1769682103,103280128,0.0,0.0,0.0,1.0,-0.0013791467063128948,0.0008313360740430653,0.018062660470604897,-0.3345670998096466,0.06728875637054443,0.0019251564517617226 -1769682103,148385536,0.0,0.0,0.0,1.0,-0.002216181717813015,0.0009848317131400108,0.017720630392432213,-0.46188750863075256,-0.045965999364852905,0.0055497875437140465 -1769682103,169432832,0.0,0.0,0.0,1.0,-0.0021741141099482775,0.0012083427282050252,0.017566820606589317,-0.46194222569465637,-0.045687463134527206,0.007915329188108444 -1769682103,202198016,0.0,0.0,0.0,1.0,-0.0019983085803687572,0.0015226067043840885,0.017563892528414726,-0.27482929825782776,-0.1530865728855133,0.004694952163845301 -1769682103,245295360,0.0,0.0,0.0,1.0,0.0007273193914443254,0.0010727207409217954,0.01818506419658661,-0.10099669545888901,0.3705064058303833,0.1435452252626419 -1769682103,273301760,0.0,0.0,0.0,1.0,0.004905352368950844,-0.001926360186189413,0.019293665885925293,-0.6311506628990173,-0.00845826044678688,0.16138379275798798 -1769682103,303784704,0.0,0.0,0.0,1.0,0.007525433320552111,-0.004466325510293245,0.020473530516028404,-0.06103963032364845,0.22324298322200775,0.14256000518798828 -1769682103,346067200,0.0,0.0,0.0,1.0,0.009353188797831535,-0.006509286817163229,0.021872490644454956,-0.4631645679473877,-0.042847901582717896,0.095070980489254 -1769682103,369864960,0.0,0.0,0.0,1.0,0.009959317743778229,-0.00744278822094202,0.022662702947854996,-0.29550081491470337,-0.07774218171834946,0.04769298806786537 -1769682103,404245760,0.0,0.0,0.0,1.0,0.010463874787092209,-0.007989972829818726,0.023200711235404015,-0.3343040347099304,0.06954052299261093,0.015202241018414497 -1769682103,448546816,0.0,0.0,0.0,1.0,0.010623166337609291,-0.008021874353289604,0.02328028529882431,-0.40347784757614136,-0.2646375596523285,-0.005126723553985357 -1769682103,470040320,0.0,0.0,0.0,1.0,0.010744573548436165,-0.007729546632617712,0.023129167035222054,-0.12783318758010864,-0.11305632442235947,-0.02222215011715889 -1769682103,502690560,0.0,0.0,0.0,1.0,0.010733774863183498,-0.007300133816897869,0.022829707711935043,-0.4425475597381592,-0.11667876690626144,-0.016047628596425056 -1769682103,550712064,0.0,0.0,0.0,1.0,0.0110335573554039,-0.006727446336299181,0.022388609126210213,-0.03855881839990616,0.14741250872612,-0.012522709555923939 -1769682103,570037504,0.0,0.0,0.0,1.0,0.01113564521074295,-0.0063751693814992905,0.02211841195821762,-0.44262373447418213,-0.11618725955486298,-0.026476968079805374 -1769682103,602494720,0.0,0.0,0.0,1.0,0.011212769895792007,-0.005723281297832727,0.021968068554997444,-0.4237302839756012,-0.18931394815444946,-0.0021785348653793335 -1769682103,646029568,0.0,0.0,0.0,1.0,0.011723856441676617,-0.004882699344307184,0.021893462166190147,-0.16667203605175018,0.0351361483335495,-0.020236199721693993 -1769682103,672746496,0.0,0.0,0.0,1.0,0.0097274761646986,-0.003691783407703042,0.02190769463777542,-0.5132792592048645,-0.4504561722278595,-0.10395381599664688 -1769682103,703334656,0.0,0.0,0.0,1.0,0.0049307155422866344,-0.0003660586371552199,0.021875858306884766,-0.4036913514137268,-0.26483020186424255,-0.13609959185123444 -1769682103,750714624,0.0,0.0,0.0,1.0,0.002285922411829233,0.002777294721454382,0.02175411954522133,-0.2755352556705475,-0.15185187757015228,-0.09881477057933807 -1769682103,769071616,0.0,0.0,0.0,1.0,0.0011987609323114157,0.00411579804494977,0.02166476473212242,-0.12797491252422333,-0.11345809698104858,-0.08376914262771606 -1769682103,815612416,0.0,0.0,0.0,1.0,0.00011633598478510976,0.004819322377443314,0.02157706767320633,-0.4240270256996155,-0.1884041279554367,-0.050797320902347565 -1769682103,853587968,0.0,0.0,0.0,1.0,-0.0009192416328005493,0.004861733876168728,0.021382013335824013,-0.36951974034309387,-0.09445206820964813,-0.013979801908135414 -1769682103,868987904,0.0,0.0,0.0,1.0,-0.001366803073324263,0.0045806849375367165,0.02124633640050888,-0.36968472599983215,-0.09406470507383347,-0.0020985063165426254 -1769682103,901986560,0.0,0.0,0.0,1.0,-0.0017049582675099373,0.004159320145845413,0.02104600891470909,-0.1293993443250656,-0.11100905388593674,0.024598881602287292 -1769682103,959380736,0.0,0.0,0.0,1.0,-0.00206468952819705,0.003403525799512863,0.02068905532360077,-0.258719801902771,-0.2222859412431717,0.024115031585097313 -1769682103,967518208,0.0,0.0,0.0,1.0,-0.0021347629372030497,0.002964950632303953,0.02039121277630329,-0.14828966557979584,-0.036725517362356186,0.030085928738117218 -1769682104,5897216,0.0,0.0,0.0,1.0,-0.0018769903108477592,0.0024658297188580036,0.020109040662646294,-0.2403419017791748,-0.2960379421710968,0.020890070125460625 -1769682104,47273216,0.0,0.0,0.0,1.0,-0.0017391778528690338,0.0021170356776565313,0.019798187538981438,-0.24067887663841248,0.018550138920545578,0.00891161896288395 -1769682104,70438912,0.0,0.0,0.0,1.0,-0.0015126066282391548,0.0018698746571317315,0.019665736705064774,-0.07409209758043289,-0.01837579533457756,0.006680241785943508 -1769682104,102817792,0.0,0.0,0.0,1.0,-0.001201594597660005,0.001638309913687408,0.019600186496973038,-0.07405012845993042,-0.018422657623887062,0.0019085827516391873 -1769682104,148600064,0.0,0.0,0.0,1.0,-0.000688503438141197,0.001566152786836028,0.01965697854757309,-0.22206072509288788,-0.05531900376081467,-0.0062082745134830475 -1769682104,168913408,0.0,0.0,0.0,1.0,-0.0006397695979103446,0.0015407323371618986,0.019765468314290047,-0.29606175422668457,-0.0736883357167244,-0.013854654505848885 -1769682104,216841216,0.0,0.0,0.0,1.0,-0.00037117599276825786,0.001589913503266871,0.019896607846021652,-0.2962793707847595,-0.07321928441524506,0.001623830758035183 -1769682104,250597120,0.0,0.0,0.0,1.0,-0.0003005866310559213,0.001669825753197074,0.02002638578414917,-0.11178607493638992,-0.1844239979982376,0.014140786603093147 -1769682104,270796800,0.0,0.0,0.0,1.0,-0.0004071959119755775,0.001786605454981327,0.020043952390551567,-0.16638827323913574,0.037659719586372375,-0.001407105941325426 -1769682104,302384128,0.0,0.0,0.0,1.0,-0.0005333758308552206,0.001468457980081439,0.01996944472193718,-0.05624886602163315,-0.0917402058839798,0.028514938428997993 -1769682104,361143552,0.0,0.0,0.0,1.0,-0.0004229331389069557,0.0008694363059476018,0.0198042094707489,-0.20447620749473572,-0.12803727388381958,0.02154316008090973 -1769682104,377198336,0.0,0.0,0.0,1.0,-0.000360169040504843,0.0005517529207281768,0.019640546292066574,-0.16630548238754272,0.0380229726433754,-0.0014249798841774464 -1769682104,404979968,0.0,0.0,0.0,1.0,-0.0002578370040282607,0.0005062401760369539,0.019583798944950104,-0.05621422082185745,-0.09198947995901108,0.009438134729862213 -1769682104,448938496,0.0,0.0,0.0,1.0,-0.00023457231873180717,0.00034692618646658957,0.01950572431087494,-0.09448103606700897,-0.2582497000694275,0.008557338267564774 -1769682104,481438464,0.0,0.0,0.0,1.0,-0.00014674861449748278,0.0004142950929235667,0.01944788359105587,-0.2045166790485382,-0.1279890388250351,-0.003502398729324341 -1769682104,502799872,0.0,0.0,0.0,1.0,-0.00015974724374245852,0.00034383664024062455,0.019374554976820946,0.01793677732348442,-0.07426704466342926,-0.004356621764600277 -1769682104,545246720,0.0,0.0,0.0,1.0,-0.00022389835794456303,0.0005097222747281194,0.019260386005043983,-0.14833404123783112,-0.035695627331733704,-0.0034081609919667244 -1769682104,569886464,0.0,0.0,0.0,1.0,-0.000258665211731568,0.0006444971659220755,0.01914948597550392,-0.2047494798898697,-0.1276165097951889,-0.004706464242190123 -1769682104,614306048,0.0,0.0,0.0,1.0,-0.0003259771619923413,0.0006676307530142367,0.01901881769299507,-0.22272595763206482,-0.053018394857645035,0.00918014906346798 -1769682104,652516864,0.0,0.0,0.0,1.0,-0.00012732009054161608,0.0011173828970640898,0.018893050029873848,-0.24039527773857117,0.021285122260451317,0.003994396887719631 -1769682104,673559040,0.0,0.0,0.0,1.0,5.94593002460897e-05,0.0014353558653965592,0.018855512142181396,-0.07429296523332596,-0.01752963475883007,0.005437701009213924 -1769682104,702698496,0.0,0.0,0.0,1.0,0.00011233999975956976,0.001731274533085525,0.01886366866528988,-0.03910404443740845,-0.16597706079483032,0.0062569743022322655 -1769682104,759770624,0.0,0.0,0.0,1.0,0.00020801625214517117,0.0019424117635935545,0.018900619819760323,-0.1484675109386444,-0.03513283282518387,-0.003444117261096835 -1769682104,769932288,0.0,0.0,0.0,1.0,7.73539359215647e-05,0.0019514246378093958,0.018911616876721382,-0.13112479448318481,-0.10909143835306168,0.008879927918314934 -1769682104,804606976,0.0,0.0,0.0,1.0,-4.379521124064922e-05,0.0019469254184514284,0.018887368962168694,-0.1484510749578476,-0.03505456820130348,-0.008228526450693607 -1769682104,847590656,0.0,0.0,0.0,1.0,0.0001058397174347192,0.0019412675173953176,0.01887519471347332,-0.14861705899238586,-0.034717101603746414,0.0036780729424208403 -1769682104,870859008,0.0,0.0,0.0,1.0,8.504019933752716e-05,0.0018845419399440289,0.018885862082242966,-0.03946991637349129,-0.16612112522125244,-0.00805449765175581 -1769682104,902948864,0.0,0.0,0.0,1.0,6.008826312609017e-05,0.00174516171682626,0.018921080976724625,0.017304643988609314,-0.07428813725709915,0.0016112643061205745 -1769682104,947758336,0.0,0.0,0.0,1.0,0.0001031727297231555,0.0017324951477348804,0.018954148516058922,-0.017276616767048836,0.07434636354446411,0.000771065300796181 -1769682104,970097408,0.0,0.0,0.0,1.0,-2.5031680706888437e-05,0.0016444058855995536,0.01897321455180645,-0.1142626479268074,-0.1830185502767563,0.004487138241529465 -1769682105,13348864,0.0,0.0,0.0,1.0,-0.00018967059440910816,0.0016609864542260766,0.01896183378994465,-0.05725490301847458,-0.09136384725570679,0.008199363946914673 -1769682105,53391872,0.0,0.0,0.0,1.0,-0.00016142372624017298,0.0016027404926717281,0.01889631897211075,-0.09158188849687576,0.057414788752794266,0.008541413582861423 -1769682105,70637312,0.0,0.0,0.0,1.0,-0.0003316428337711841,0.0016555533511564136,0.018835704773664474,-0.16581878066062927,0.04025082290172577,0.0008128900080919266 -1769682105,106058240,0.0,0.0,0.0,1.0,-0.000234471372095868,0.001555370050482452,0.01879281923174858,0.017124546691775322,-0.07453691959381104,-0.007919689640402794 -1769682105,161062400,0.0,0.0,0.0,1.0,-0.00031930781551636755,0.0015231024008244276,0.01884295605123043,-0.0913156196475029,0.05733851343393326,-0.004580938257277012 -1769682105,169818368,0.0,0.0,0.0,1.0,-0.00014242947509046644,0.0015679672360420227,0.018957631662487984,0.017026353627443314,-0.07453358173370361,-0.006727172993123531 -1769682105,204499968,0.0,0.0,0.0,1.0,-4.92232502438128e-05,0.001577490591444075,0.019119376316666603,-0.11495693773031235,-0.18267831206321716,-0.0039058863185346127 -1769682105,249187584,0.0,0.0,0.0,1.0,-0.00013610991300083697,0.001641461276449263,0.019330017268657684,-0.07442450523376465,-0.01681758090853691,0.0005974335363134742 -1769682105,270365952,0.0,0.0,0.0,1.0,-0.00018844781152438372,0.0015990855172276497,0.019452549517154694,-0.07447835057973862,-0.016706451773643494,0.004169154912233353 -1769682105,303841792,0.0,0.0,0.0,1.0,-0.00020988546020817012,0.0013756301486864686,0.0195331908762455,-0.0579567551612854,-0.09076431393623352,0.022468512877821922 -1769682105,348713216,0.0,0.0,0.0,1.0,-0.00033802964026108384,0.0008267254452221096,0.019595202058553696,-0.04130521044135094,-0.16521775722503662,0.020508240908384323 -1769682105,369217792,0.0,0.0,0.0,1.0,-0.0001571561151649803,0.0005718843312934041,0.019625224173069,-0.0413290411233902,-0.16530653834342957,0.014547677710652351 -1769682105,412862976,0.0,0.0,0.0,1.0,-8.834288746584207e-05,0.000325061846524477,0.01966222934424877,-0.0746539756655693,-0.01631336286664009,0.0148860989138484 -1769682105,449200128,0.0,0.0,0.0,1.0,-0.00014307250967249274,0.00019426006474532187,0.019685527309775352,-0.05794224515557289,-0.09101221710443497,0.0010096416808664799 -1769682105,470651904,0.0,0.0,0.0,1.0,-0.00013729681086260825,0.0001990191376535222,0.019674966111779213,-0.13243664801120758,-0.10755051672458649,-0.0031749363988637924 -1769682105,502749952,0.0,0.0,0.0,1.0,-0.00026390812126919627,0.0002372295130044222,0.019616415724158287,-0.14882704615592957,-0.03317034989595413,-0.014327825978398323 -1769682105,561292032,0.0,0.0,0.0,1.0,-0.00045062621938996017,0.00033912539947777987,0.01947522535920143,0.123815156519413,-0.20731116831302643,-0.006459463387727737 -1769682105,567624960,0.0,0.0,0.0,1.0,-0.00034618371864780784,0.00035353351267986,0.01932777278125286,-0.07445799559354782,-0.016449671238660812,-0.005378331057727337 -1769682105,602821632,0.0,0.0,0.0,1.0,-0.0005491557531058788,0.0004011924029327929,0.019144820049405098,-0.041881125420331955,-0.1654137670993805,-0.0009587829699739814 -1769682105,646236672,0.0,0.0,0.0,1.0,-0.0002630396338645369,0.000826615490950644,0.01891755498945713,-0.13293690979480743,-0.10688836127519608,0.0087272422388196 -1769682105,670216704,0.0,0.0,0.0,1.0,-0.0003111212281510234,0.0011256460566073656,0.018749302253127098,-0.11664796620607376,-0.1815757006406784,-0.0015820303233340383 -1769682105,705506304,0.0,0.0,0.0,1.0,-0.00018229290435556322,0.0012874045642092824,0.018605265766382217,-0.13295386731624603,-0.10689713060855865,0.0003744709538295865 -1769682105,746653952,0.0,0.0,0.0,1.0,-8.938171959016472e-05,0.0014053734485059977,0.01844765804708004,-0.042463518679142,-0.16507722437381744,0.01094815880060196 -1769682105,769599744,0.0,0.0,0.0,1.0,-1.6814592527225614e-05,0.0014575745444744825,0.018360618501901627,0.09058152139186859,-0.05839632824063301,0.007010033819824457 -1769682105,802771712,0.0,0.0,0.0,1.0,0.00014995475066825747,0.0014911963371559978,0.01828005723655224,0.015962660312652588,-0.07448458671569824,0.0063837626948952675 -1769682105,849304320,0.0,0.0,0.0,1.0,-1.3573735486716032e-05,0.001440286636352539,0.0181584432721138,0.03213090822100639,-0.14946778118610382,-0.012257524766027927 -1769682105,869433856,0.0,0.0,0.0,1.0,-0.00011024158447980881,0.0013851557159796357,0.01805211417376995,0.10650672763586044,-0.13331498205661774,0.0002996019320562482 -1769682105,914866944,0.0,0.0,0.0,1.0,-6.533932173624635e-05,0.0013042273931205273,0.017927659675478935,6.0257352743064985e-05,-9.063203469850123e-05,-0.004767132457345724 -1769682105,947247872,0.0,0.0,0.0,1.0,-3.593780274968594e-05,0.0012225210666656494,0.017749298363924026,-0.16498132050037384,0.04275597259402275,-0.011251398362219334 -1769682105,971843840,0.0,0.0,0.0,1.0,-0.00016979048086795956,0.0011652277316898108,0.017609670758247375,-0.14922446012496948,-0.031689587980508804,-0.004869923461228609 -1769682106,2777344,0.0,0.0,0.0,1.0,-0.00020233466057106853,0.0011850164737552404,0.017479322850704193,-0.09039827436208725,0.05886039510369301,-0.00227042892947793 -1769682106,60207360,0.0,0.0,0.0,1.0,-0.00010943086817860603,0.001215631142258644,0.01732645556330681,-0.13352914154529572,-0.10619556903839111,-0.005645117722451687 -1769682106,69422592,0.0,0.0,0.0,1.0,-0.00014843119424767792,0.001185243483632803,0.017231883481144905,-4.572220132104121e-05,6.805097655160353e-05,0.003575341310352087 -1769682106,104868096,0.0,0.0,0.0,1.0,-0.00022946516401134431,0.001262447563931346,0.017173070460557938,-0.04341868683695793,-0.16496063768863678,0.002583990804851055 -1769682106,150258176,0.0,0.0,0.0,1.0,-1.5694822650402784e-06,0.0012988717062398791,0.0171522069722414,-0.05907585844397545,-0.09030640870332718,-0.0014243291225284338 -1769682106,169740800,0.0,0.0,0.0,1.0,-3.0950468499213457e-06,0.0012259959476068616,0.01717931590974331,-0.043554410338401794,-0.16500501334667206,-0.002187400823459029 -1769682106,202873600,0.0,0.0,0.0,1.0,5.616992712020874e-05,0.0011989837512373924,0.017220238223671913,0.04659978672862053,-0.22421640157699585,-0.0034724485594779253 -1769682106,245265408,0.0,0.0,0.0,1.0,-4.195008659735322e-05,0.001223806873895228,0.01727866567671299,0.030922310426831245,-0.14943842589855194,0.0008643744513392448 -1769682106,270486272,0.0,0.0,0.0,1.0,-4.989055742044002e-05,0.0012781053083017468,0.01731071062386036,-0.11857106536626816,-0.18032492697238922,-0.0016765721375122666 -1769682106,311904768,0.0,0.0,0.0,1.0,7.5879215728491545e-06,0.0008951956988312304,0.01733993925154209,0.10532023757696152,-0.13383540511131287,0.014653041958808899 -1769682106,347983616,0.0,0.0,0.0,1.0,-2.2073814761824906e-05,0.0005321514909155667,0.017331348732113838,0.015176648274064064,-0.07451842725276947,0.012351373210549355 -1769682106,369696000,0.0,0.0,0.0,1.0,-3.425701288506389e-05,0.00033041101414710283,0.01729195937514305,-0.22445903718471527,-0.04554183781147003,0.015836266800761223 -1769682106,402778368,0.0,0.0,0.0,1.0,-7.811319665051997e-05,0.00022219862148631364,0.017226271331310272,-7.748889038339257e-05,0.00011380625073798001,0.005958878435194492 -1769682106,448914944,0.0,0.0,0.0,1.0,-8.208284270949662e-05,0.00017670515808276832,0.017131172120571136,0.030281612649559975,-0.14936226606369019,0.01040167361497879 -1769682106,469417216,0.0,0.0,0.0,1.0,3.6607758374884725e-05,3.132905112579465e-05,0.017063351348042488,0.015056062489748001,-0.0746205523610115,0.008776232600212097 -1769682106,502424320,0.0,0.0,0.0,1.0,-5.1083421567454934e-05,0.00010781214223243296,0.016986722126603127,-0.11914481222629547,-0.1800590455532074,-0.01241336204111576 -1769682106,549727232,0.0,0.0,0.0,1.0,5.353655433282256e-05,0.00021389800531324,0.016879037022590637,0.030367793515324593,-0.14991503953933716,-0.015816928818821907 -1769682106,573068032,0.0,0.0,0.0,1.0,8.580973371863365e-07,0.0001594495406607166,0.01678549498319626,0.10494695603847504,-0.13468557596206665,-0.004408428445458412 -1769682106,604084224,0.0,0.0,0.0,1.0,0.003219283651560545,0.0014897756045684218,0.016872840002179146,-0.27102968096733093,0.18183240294456482,0.1217760518193245 -1769682106,645006592,0.0,0.0,0.0,1.0,0.012196238152682781,0.007708865217864513,0.017503727227449417,-0.241018146276474,0.03239717334508896,0.12139157950878143 -1769682106,669896960,0.0,0.0,0.0,1.0,0.015395976603031158,0.011119091883301735,0.01780998706817627,-0.15102049708366394,-0.027771450579166412,0.10106942057609558 -1769682106,703817472,0.0,0.0,0.0,1.0,0.018374664708971977,0.013789528980851173,0.018073871731758118,-0.015671098604798317,0.07605063170194626,0.05782918632030487 -1769682106,748605440,0.0,0.0,0.0,1.0,0.02019135281443596,0.014783648774027824,0.0182258989661932,0.059663478285074234,0.09019958972930908,0.025172647088766098 -1769682106,769529856,0.0,0.0,0.0,1.0,0.021407565101981163,0.014886632561683655,0.018394973129034042,-0.029527166858315468,0.14969328045845032,-0.002531293546780944 -1769682106,803337728,0.0,0.0,0.0,1.0,0.022349007427692413,0.014564194716513157,0.01858539693057537,0.014911952428519726,-0.07513405382633209,-0.011190745048224926 -1769682106,851530496,0.0,0.0,0.0,1.0,0.022807789966464043,0.013831655494868755,0.01885331980884075,-0.04532724246382713,-0.16471616923809052,-0.011151270940899849 -1769682106,869327872,0.0,0.0,0.0,1.0,0.022941483184695244,0.013258185237646103,0.019031284376978874,-0.06004806235432625,-0.08980950713157654,-0.011915627866983414 -1769682106,903960064,0.0,0.0,0.0,1.0,0.022748464718461037,0.012745499610900879,0.019148724153637886,-0.04532996937632561,-0.1649409383535385,-0.021685225889086723 -1769682106,946305280,0.0,0.0,0.0,1.0,0.022026855498552322,0.012246795929968357,0.01919645443558693,-0.045527148991823196,-0.16480228304862976,-0.016794444993138313 -1769682111,449709824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682111,469859328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682111,508509440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682111,551401216,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682111,570179072,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682111,603246080,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682111,654025728,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682111,675126784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682111,708136448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682111,749525504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682111,780176896,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682111,804022784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682111,850981120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682111,870001152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682111,905479168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682111,946494464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,2.983749618579168e-05,-2.9077438739477657e-05,-0.0011913662310689688 -1769682111,970120448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682112,3381760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682112,54460672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-2.9837494366802275e-05,2.9077393264742568e-05,0.0011913662310689688 -1769682112,69864960,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682112,103148032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682112,149174528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,2.9837490728823468e-05,-2.9077349608996883e-05,-0.0011913662310689688 -1769682112,174360064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,2.9837490728823468e-05,-2.9077331419102848e-05,-0.0011913662310689688 -1769682112,204487168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,2.9837490728823468e-05,-2.9077318686177023e-05,-0.0011913662310689688 -1769682112,248769536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682112,270050816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682112,306575872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682112,352612608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682112,372456192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,2.983748709084466e-05,-2.9077249564579688e-05,-0.0011913662310689688 -1769682112,405257984,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,2.983748709084466e-05,-2.9077231374685653e-05,-0.0011913662310689688 -1769682112,447825664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.967497418168932e-05,-5.815443000756204e-05,-0.0023827324621379375 -1769682112,473217792,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.967497418168932e-05,5.8154400903731585e-05,0.0023827324621379375 -1769682112,505187584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.9674970543710515e-05,5.8154360885964707e-05,0.0023827324621379375 -1769682112,562941440,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-2.9837483452865854e-05,2.907716407207772e-05,0.0011913662310689688 -1769682112,571296256,0.0,0.0,0.0,1.0,-0.008756635710597038,-0.05442739278078079,-0.00033104082103818655,2.2332217693328857,-0.10502099990844727,0.9607414603233337 -1769682112,604107776,0.0,0.0,0.0,1.0,-0.010440201498568058,-0.1138630136847496,-0.0008013287442736328,0.19377656280994415,0.19650958478450775,0.5001848936080933 -1769682112,646923520,0.0,0.0,0.0,1.0,-0.008604364469647408,-0.12436666339635849,-0.0009981729090213776,-0.5765535831451416,0.2281189262866974,0.19729392230510712 -1769682112,670377984,0.0,0.0,0.0,1.0,-0.006303846836090088,-0.11558905243873596,-0.0011187746422365308,-1.2743514776229858,0.2723561227321625,-0.04449739307165146 -1769682112,707104512,0.0,0.0,0.0,1.0,-0.003186236135661602,-0.08750796318054199,-0.0012216190807521343,-1.4764554500579834,0.08262033015489578,-0.25626876950263977 -1769682112,747721984,0.0,0.0,0.0,1.0,-0.0011786373797804117,-0.06250698864459991,-0.0012880105059593916,-1.7894163131713867,0.11087051779031754,-0.35017213225364685 -1769682112,770484480,0.0,0.0,0.0,1.0,0.00043194316094741225,-0.03858155384659767,-0.0013551611918956041,-1.616320013999939,-0.01835893839597702,-0.37711164355278015 -1769682112,804416512,0.0,0.0,0.0,1.0,0.0018632762366905808,-0.013277989812195301,-0.0014509354950860143,-1.261987566947937,0.1893768608570099,-0.34781503677368164 -1769682112,864302848,0.0,0.0,0.0,1.0,0.0026447258424013853,2.2794236429035664e-05,-0.0015078383730724454,-1.1755824089050293,0.12638403475284576,-0.2909657061100006 -1769682112,870610432,0.0,0.0,0.0,1.0,0.003066743491217494,0.008011781610548496,-0.001540872734040022,-1.0025458335876465,2.7354806661605835e-05,-0.1979741007089615 -1769682112,904457216,0.0,0.0,0.0,1.0,0.0030754904728382826,0.012206636369228363,-0.0015265223337337375,-0.7765618562698364,0.03587935492396355,-0.10626551508903503 -1769682112,950263552,0.0,0.0,0.0,1.0,0.0027150746900588274,0.011547456495463848,-0.0014778440818190575,-0.7014042139053345,0.04850265011191368,-0.04680192470550537 -1769682112,982112000,0.0,0.0,0.0,1.0,0.0023725503124296665,0.007500298786908388,-0.0013226439477875829,-0.7772985696792603,0.038992851972579956,0.02902258187532425 -1769682113,6509824,0.0,0.0,0.0,1.0,0.0019825263880193233,0.004497101996093988,-0.0011310992995277047,-0.9170626997947693,-0.05859020724892616,0.04823434725403786 -1769682113,47849216,0.0,0.0,0.0,1.0,0.001525992644019425,0.0014727015513926744,-0.0008951441268436611,-0.7775151133537292,0.03973688557744026,0.06220020353794098 -1769682113,71254016,0.0,0.0,0.0,1.0,0.0014730809489265084,-0.001209791051223874,-0.0005903224227949977,-0.690791666507721,-0.024434087797999382,0.06426986306905746 -1769682113,104519936,0.0,0.0,0.0,1.0,0.0009096930152736604,-0.004018938168883324,-0.0001330378872808069,-0.7887658476829529,0.11509320139884949,0.058050282299518585 -1769682113,152767744,0.0,0.0,0.0,1.0,0.0007562153623439372,-0.005982476752251387,0.0002483410353306681,-0.9622456431388855,0.24358384311199188,0.0612325482070446 -1769682113,170823936,0.0,0.0,0.0,1.0,0.0005552286165766418,-0.007464288733899593,0.0006806137389503419,-1.1546080112457275,-0.017298031598329544,0.03436735272407532 -1769682113,203958272,0.0,0.0,0.0,1.0,0.0003801132261287421,-0.007489364128559828,0.0013304268941283226,-1.1656707525253296,0.05733411759138107,-0.0028973519802093506 -1769682113,248002560,0.0,0.0,0.0,1.0,0.0005082341376692057,-0.006809843238443136,0.0018484118627384305,-1.2298511266708374,-0.029368892312049866,-0.003296228125691414 -1769682113,270798080,0.0,0.0,0.0,1.0,0.00034428268554620445,-0.006349155213683844,0.0023673686664551497,-1.0788484811782837,-0.007217776030302048,-0.021911069750785828 -1769682113,305039360,0.0,0.0,0.0,1.0,0.0003829917695838958,-0.005894998088479042,0.0031103924848139286,-1.2522660493850708,0.12126938998699188,-0.02554337866604328 -1769682113,348742400,0.0,0.0,0.0,1.0,0.0005439626984298229,-0.005180161911994219,0.0036850569304078817,-1.2409887313842773,0.0457899272441864,-0.030635740607976913 -1769682113,373098240,0.0,0.0,0.0,1.0,0.0003279372467659414,-0.003939079120755196,0.00424330634996295,-1.16548752784729,0.05700822174549103,-0.03755638748407364 -1769682113,405221888,0.0,0.0,0.0,1.0,0.00040835875552147627,-0.0022814269177615643,0.004970568232238293,-1.176705241203308,0.1326972246170044,-0.038088180124759674 -1769682113,451331584,0.0,0.0,0.0,1.0,0.00039952911902219057,-0.0016839231830090284,0.00550071382895112,-1.2409805059432983,0.04642953723669052,-0.027880322188138962 -1769682113,488581120,0.0,0.0,0.0,1.0,0.00026849331334233284,-0.000556869141291827,0.006169617176055908,-1.2184419631958008,-0.10502687096595764,-0.05984897166490555 -1769682113,514458624,0.0,0.0,0.0,1.0,0.0005415456253103912,0.0025227246806025505,0.006623353809118271,-1.0899181365966797,0.06874998658895493,-0.05159967020153999 -1769682113,547360000,0.0,0.0,0.0,1.0,0.0004558165674097836,0.005220918916165829,0.007158774882555008,-1.078742504119873,-0.006370164453983307,-0.04872671514749527 -1769682113,570248704,0.0,0.0,0.0,1.0,0.0006507523357868195,0.006605137139558792,0.0074050286784768105,-1.0676385164260864,-0.0814361721277237,-0.037464652210474014 -1769682113,604768768,0.0,0.0,0.0,1.0,0.0006926907226443291,0.008229875937104225,0.00786144845187664,-1.078816294670105,-0.005422867834568024,-0.030126428231596947 -1769682113,652306944,0.0,0.0,0.0,1.0,0.0007068632985465229,0.008696937002241611,0.008176272734999657,-0.8525051474571228,0.028814569115638733,-0.0026431092992424965 -1769682113,672175360,0.0,0.0,0.0,1.0,0.0007244219304993749,0.006125698797404766,0.008462567813694477,-0.8304826021194458,-0.12123395502567291,0.028333522379398346 -1769682113,704716032,0.0,0.0,0.0,1.0,-6.1871025536675e-05,0.0012775277718901634,0.008630020543932915,-0.8951423764228821,-0.20666968822479248,0.06333865970373154 -1769682113,753002496,0.0,0.0,0.0,1.0,-0.00019972931477241218,-0.0015096802962943912,0.008732493966817856,-0.8416506052017212,-0.04500482231378555,0.03709492087364197 -1769682113,777543424,0.0,0.0,0.0,1.0,-0.00026444814284332097,-0.0034488365054130554,0.0090553043410182,-1.003558874130249,0.008279344066977501,0.01598145253956318 -1769682113,803730176,0.0,0.0,0.0,1.0,-0.00020399277855176479,-0.00391129357740283,0.009440524503588676,-0.9389822483062744,0.09474072605371475,0.002427038736641407 -1769682113,851859200,0.0,0.0,0.0,1.0,-0.00018040860595647246,-0.003918955102562904,0.009888929314911366,-1.143473744392395,-0.08911358565092087,-0.004783225245773792 -1769682113,870750976,0.0,0.0,0.0,1.0,-0.00023709688684903085,-0.0038019255734980106,0.01033351756632328,-1.154420018196106,-0.013396922498941422,-0.011290905997157097 -1769682113,906595584,0.0,0.0,0.0,1.0,-0.00018280129006598145,-0.002987178973853588,0.010850469581782818,-1.0788614749908447,-0.0022759325802326202,-0.02295718342065811 -1769682113,953292288,0.0,0.0,0.0,1.0,-0.00043587241088971496,-0.002194735687226057,0.01114463061094284,-1.0033735036849976,0.009087398648262024,-0.018021367490291595 -1769682113,972210688,0.0,0.0,0.0,1.0,-0.0006044640322215855,-0.0016185807762667537,0.011295498348772526,-0.9278221726417542,0.02011951059103012,-0.025030385702848434 -1769682114,4076544,0.0,0.0,0.0,1.0,-0.0008405338739976287,-0.0010068155825138092,0.01130841113626957,-1.1760673522949219,0.13924789428710938,-0.020617926493287086 -1769682114,50973440,0.0,0.0,0.0,1.0,-0.000985883641988039,-0.0008709852118045092,0.011212161742150784,-1.0788898468017578,-0.0005848556756973267,-0.01797247864305973 -1769682114,72513792,0.0,0.0,0.0,1.0,-0.0011895759962499142,-0.0006640600040555,0.01100749708712101,-1.0681260824203491,-0.0756746232509613,-0.013707038946449757 -1769682114,104222976,0.0,0.0,0.0,1.0,-0.00136198615655303,-0.00040551667916588485,0.01056827511638403,-0.9926573038101196,-0.06429621577262878,-0.0064580561593174934 -1769682114,147123456,0.0,0.0,0.0,1.0,-0.0011411829618737102,-0.00021350366296246648,0.010211644694209099,-1.057436227798462,-0.150540292263031,-0.01778961345553398 -1769682114,174780416,0.0,0.0,0.0,1.0,-0.0020826533436775208,0.0004208386526443064,0.009720353409647942,-1.1543623208999634,-0.010060064494609833,-0.03349597752094269 -1769682114,205815552,0.0,0.0,0.0,1.0,-0.002006705617532134,0.0005229084054008126,0.009307158179581165,-1.089573621749878,0.07691709697246552,-0.016205983236432076 -1769682114,247209984,0.0,0.0,0.0,1.0,-0.0021509819198399782,0.0007354918052442372,0.008893653750419617,-0.9277533292770386,0.0226827971637249,-0.027328111231327057 -1769682114,283211264,0.0,0.0,0.0,1.0,-0.001969744451344013,0.0009701162343844771,0.008476347662508488,-1.0682655572891235,-0.07361625134944916,-0.014966216869652271 -1769682114,303800832,0.0,0.0,0.0,1.0,-0.0019314332166686654,0.001498327823355794,0.007952687330543995,-0.9384863972663879,0.09951820969581604,0.0029510613530874252 -1769682114,347444480,0.0,0.0,0.0,1.0,-0.0019033981952816248,0.001619603019207716,0.0075786663219332695,-0.9927505850791931,-0.062485966831445694,-0.017372053116559982 -1769682114,370785280,0.0,0.0,0.0,1.0,-0.0018471749499440193,0.0014517726376652718,0.0072274357080459595,-1.0350875854492188,0.24018870294094086,-0.011592024937272072 -1769682114,404231168,0.0,0.0,0.0,1.0,-0.001843802398070693,0.0013989299768581986,0.006778267677873373,-1.0139189958572388,0.08937019109725952,-0.009195797145366669 -1769682114,447459072,0.0,0.0,0.0,1.0,-0.001653551124036312,0.0013732712250202894,0.006452443078160286,-1.100018858909607,0.15468472242355347,-0.006388690322637558 -1769682114,471385088,0.0,0.0,0.0,1.0,-0.0016005747020244598,0.0013017901219427586,0.006144177634268999,-0.8417230844497681,-0.04025077819824219,-0.004236745648086071 -1769682114,504058112,0.0,0.0,0.0,1.0,-0.0015892600640654564,0.0012287836289033294,0.005833358038216829,-0.9823374152183533,-0.13674797117710114,-0.008669666945934296 -1769682114,572354560,0.0,0.0,0.0,1.0,-0.0014149637427181005,0.0012549509992823005,0.00570776779204607,-0.9383174777030945,0.10086357593536377,-0.0008864719420671463 -1769682114,581586944,0.0,0.0,0.0,1.0,-0.001412504119798541,0.0012982365442439914,0.005668616387993097,-0.9068373441696167,-0.12579606473445892,-0.005069689825177193 -1769682114,604965888,0.0,0.0,0.0,1.0,-0.0013443994102999568,0.0012702369131147861,0.005679359659552574,-0.9487113356590271,0.17667898535728455,-0.007522165309637785 -1769682114,649168128,0.0,0.0,0.0,1.0,-0.0015773444902151823,0.0015223956434056163,0.005670751444995403,-0.9277685284614563,0.025622189044952393,-0.008739357814192772 -1769682114,672048384,0.0,0.0,0.0,1.0,-0.0016471415292471647,0.0013362080790102482,0.005606339778751135,-1.1545230150222778,-0.005452744662761688,-0.005608053877949715 -1769682114,709130496,0.0,0.0,0.0,1.0,-0.0021270758006721735,0.0011951399501413107,0.005378628149628639,-0.9277636408805847,0.026010815054178238,-0.00762971630319953 -1769682114,753484544,0.0,0.0,0.0,1.0,-0.00227620592340827,0.001132627367042005,0.005085268057882786,-0.9929847121238708,-0.059595998376607895,0.003511001355946064 -1769682114,771805184,0.0,0.0,0.0,1.0,-0.0023506819270551205,0.0012589737307280302,0.004702891688793898,-0.938111424446106,0.1016930639743805,-0.016615640372037888 -1769682114,804791296,0.0,0.0,0.0,1.0,-0.0025888497475534678,0.0014526081504300237,0.004131197929382324,-0.917334794998169,-0.04927342012524605,-0.013121351599693298 -1769682114,848450304,0.0,0.0,0.0,1.0,-0.0013390871463343501,0.0019761158619076014,0.003966957796365023,-0.9485538005828857,0.1779928058385849,0.0017973072826862335 -1769682114,871776256,0.0,0.0,0.0,1.0,-0.001082899048924446,0.0023965518921613693,0.0037197135388851166,-1.099680781364441,0.1572587490081787,-0.0033523254096508026 -1769682114,905649920,0.0,0.0,0.0,1.0,-0.0005937471869401634,0.0028576997574418783,0.0033320703078061342,-0.9381141662597656,0.10247665643692017,-0.004938846454024315 -1769682114,947606528,0.0,0.0,0.0,1.0,-0.00021757170907221735,0.0030636233277618885,0.0029982631094753742,-1.0137121677398682,0.09229515492916107,-0.0016235224902629852 -1769682114,978339072,0.0,0.0,0.0,1.0,-0.00011270827963016927,0.0032284960616379976,0.0025764754973351955,-0.8418336510658264,-0.038132354617118835,-0.0014306660741567612 -1769682115,3894016,0.0,0.0,0.0,1.0,0.00034264629357494414,0.0032125527504831553,0.002331797732040286,-1.0239568948745728,0.16778415441513062,-0.015531817451119423 -1769682115,47395584,0.0,0.0,0.0,1.0,0.0005144425085745752,0.003275769529864192,0.002173034939914942,-0.9173955321311951,-0.0484810397028923,-0.007753761950880289 -1769682115,71294976,0.0,0.0,0.0,1.0,0.0005525083979591727,0.0032494403421878815,0.002092345617711544,-0.992954671382904,-0.05888381972908974,-0.014009729959070683 -1769682115,106278656,0.0,0.0,0.0,1.0,0.0008211211534217,0.0031408616341650486,0.00208178604952991,-0.9277058839797974,0.02719932422041893,-0.010920891538262367 -1769682115,145619456,0.0,0.0,0.0,1.0,0.0007929514395073056,0.0031769853085279465,0.00208358746021986,-0.7765746712684631,0.048103440552949905,-0.001026681624352932 -1769682115,173099520,0.0,0.0,0.0,1.0,0.0006998160970397294,0.0030853115022182465,0.0020485329441726208,-0.9380102157592773,0.10291561484336853,-0.011682911776006222 -1769682115,205480448,0.0,0.0,0.0,1.0,0.00041607936145737767,0.0030811119358986616,0.001922936411574483,-0.7662340402603149,-0.027497487142682076,-0.005375559441745281 -1769682115,252967168,0.0,0.0,0.0,1.0,-0.0005291402922011912,0.002839360386133194,0.0014719297178089619,-0.7663494944572449,-0.027039673179388046,0.01241071056574583 -1769682115,270200320,0.0,0.0,0.0,1.0,-0.0009940682211890817,0.0028455976862460375,0.001159628271125257,-0.7766243815422058,0.04850105941295624,0.00820353627204895 -1769682115,305437696,0.0,0.0,0.0,1.0,-0.002091968199238181,0.0027583250775933266,0.0005659890011884272,-0.7868008613586426,0.12372400611639023,-0.01034012995660305 -1769682115,364009472,0.0,0.0,0.0,1.0,-0.0024146626237779856,0.002759586786851287,0.00017592096992302686,-0.8418318033218384,-0.03768625855445862,-0.00593214388936758 -1769682115,372604160,0.0,0.0,0.0,1.0,-0.0027307718992233276,0.002823786111548543,-0.00016268111357931048,-0.8417587876319885,-0.037931010127067566,-0.016731085255742073 -1769682115,405048320,0.0,0.0,0.0,1.0,-0.0029536853544414043,0.0028082840144634247,-0.0005484676803462207,-0.852123498916626,0.03781706094741821,-0.010246271267533302 -1769682115,448686848,0.0,0.0,0.0,1.0,-0.002922074170783162,0.002855188213288784,-0.0007624244317412376,-0.7867842316627502,0.12365099042654037,-0.012965967878699303 -1769682115,470414848,0.0,0.0,0.0,1.0,-0.0031931016128510237,0.002848555101081729,-0.0009313028422184289,-0.8624231219291687,0.11346417665481567,-0.00736471451818943 -1769682115,504791040,0.0,0.0,0.0,1.0,-0.003009331878274679,0.0028509481344372034,-0.001101791043765843,-0.9276948571205139,0.02744523622095585,-0.010788153856992722 -1769682115,550242304,0.0,0.0,0.0,1.0,-0.0030894610099494457,0.002935383003205061,-0.0012077587889507413,-0.6905827522277832,-0.017352156341075897,-0.012943504378199577 -1769682115,572747520,0.0,0.0,0.0,1.0,-0.003090248443186283,0.0030103556346148252,-0.001323872827924788,-0.85210120677948,0.037686873227357864,-0.010618963278830051 -1769682115,605699840,0.0,0.0,0.0,1.0,-0.003033472690731287,0.003130305092781782,-0.0014982471475377679,-0.700863242149353,0.05811136215925217,-0.017196066677570343 -1769682115,654148352,0.0,0.0,0.0,1.0,-0.0030748313292860985,0.0033324547111988068,-0.0016872460255399346,-0.8417872190475464,-0.03801539167761803,-0.010306555777788162 -1769682115,670815488,0.0,0.0,0.0,1.0,-0.0031068562529981136,0.0033851575572043657,-0.0017861940432339907,-0.8623766899108887,0.11302851140499115,-0.017354527488350868 -1769682115,705445888,0.0,0.0,0.0,1.0,-0.002941335318610072,0.0027068976778537035,-0.0018884333549067378,-0.6903862953186035,-0.018042394891381264,-0.037158407270908356 -1769682115,763251456,0.0,0.0,0.0,1.0,-0.002601107582449913,0.0016435673460364342,-0.0019365663174539804,-0.8313288688659668,-0.11408346891403198,-0.025521170347929 -1769682115,772144384,0.0,0.0,0.0,1.0,-0.002558167790994048,0.000949937617406249,-0.001981850480660796,-0.7557687759399414,-0.10369516164064407,-0.02041839063167572 -1769682115,804379904,0.0,0.0,0.0,1.0,-0.0024093491956591606,0.00041727288044057786,-0.0020111631602048874,-0.7662582993507385,-0.027726804837584496,-0.0006750719621777534 -1769682115,846705408,0.0,0.0,0.0,1.0,-0.002476109191775322,0.000259527878370136,-0.0020239471923559904,-0.7009550929069519,0.05801799148321152,-0.007940842770040035 -1769682115,870438400,0.0,0.0,0.0,1.0,-0.0024025554303079844,0.00018233756418339908,-0.0020109510514885187,-0.7009679675102234,0.05800122767686844,-0.006749838590621948 -1769682115,904325376,0.0,0.0,0.0,1.0,-0.0005434898193925619,-0.0004889550036750734,-0.0019922470673918724,-0.7219908237457275,0.209962397813797,0.031637463718652725 -1769682115,948111872,0.0,0.0,0.0,1.0,-4.346996865933761e-05,-0.00107296509668231,-0.0019744245801120996,-0.7871929407119751,0.1238643005490303,0.026988031342625618 -1769682115,970185984,0.0,0.0,0.0,1.0,0.0002791541046462953,-0.0015818156534805894,-0.001990126445889473,-0.604938268661499,-0.08223851770162582,0.02918921783566475 -1769682116,7227648,0.0,0.0,0.0,1.0,0.00036120967706665397,-0.0018846626626327634,-0.0020997643005102873,-0.4743594527244568,0.08926571905612946,0.011145258322358131 -1769682116,49059328,0.0,0.0,0.0,1.0,0.00029874773463234305,-0.0019889934919774532,-0.0022216360084712505,-0.6151407361030579,-0.007159128785133362,0.008535943925380707 -1769682116,71005184,0.0,0.0,0.0,1.0,0.0004899850464425981,-0.0018683529924601316,-0.002365706954151392,-0.787002444267273,0.12304701656103134,-0.0014370987191796303 -1769682116,105738752,0.0,0.0,0.0,1.0,0.0005965591408312321,-0.0017442182870581746,-0.002550962381064892,-0.6905137896537781,-0.018227003514766693,-0.01914738491177559 -1769682116,150385920,0.0,0.0,0.0,1.0,0.000708782288711518,-0.001678762724623084,-0.0026650328654795885,-0.6253783106803894,0.06785337626934052,-0.012088279239833355 -1769682116,171870208,0.0,0.0,0.0,1.0,0.0007713472004979849,-0.0016615730710327625,-0.002725261962041259,-0.5602203607559204,0.15384255349636078,-0.009807365015149117 -1769682116,204529664,0.0,0.0,0.0,1.0,0.0010629052994772792,-0.0015032280934974551,-0.0027094935066998005,-0.7009811997413635,0.05735050141811371,-0.011170633137226105 -1769682116,250508800,0.0,0.0,0.0,1.0,0.0009280357626266778,-0.0014088659081608057,-0.00264408509247005,-0.776468813419342,0.04660261049866676,-0.024589113891124725 -1769682116,277114368,0.0,0.0,0.0,1.0,0.000776846194639802,-0.001442277804017067,-0.00258169905282557,-0.6046416163444519,-0.08332856744527817,-0.0002730637788772583 -1769682116,304531712,0.0,0.0,0.0,1.0,0.00038552930345758796,-0.0016216064104810357,-0.0025566238909959793,-0.5499038696289062,0.07819975912570953,-0.002074982039630413 -1769682116,349139456,0.0,0.0,0.0,1.0,0.00040160774369724095,-0.0016260978300124407,-0.002538006752729416,-0.529035210609436,-0.07303774356842041,-0.002271566540002823 -1769682116,370594816,0.0,0.0,0.0,1.0,0.0002212958934251219,-0.0017215600237250328,-0.0025421075988560915,-0.5602694749832153,0.15344756841659546,-0.014422924257814884 -1769682116,405300736,0.0,0.0,0.0,1.0,-3.791986819123849e-05,-0.0017129727639257908,-0.002571520861238241,-0.5394267439842224,0.0023246798664331436,-0.008649604395031929 -1769682116,453164800,0.0,0.0,0.0,1.0,-5.720688568544574e-05,-0.0018465140601620078,-0.002587196184322238,-0.6905918717384338,-0.018573282286524773,-0.006858828477561474 -1769682116,471867904,0.0,0.0,0.0,1.0,-0.00010314775863662362,-0.0017983413999900222,-0.0025871999096125364,-0.6905908584594727,-0.018626878038048744,-0.006820903159677982 -1769682116,503742976,0.0,0.0,0.0,1.0,-7.979471411090344e-05,-0.0018711083102971315,-0.0025244224816560745,-0.690589427947998,-0.018697429448366165,-0.006768973544239998 -1769682116,553402880,0.0,0.0,0.0,1.0,4.236914173816331e-05,-0.0019289195770397782,-0.00245879590511322,-0.4638255834579468,0.012517303228378296,-0.01298903301358223 -1769682116,573033472,0.0,0.0,0.0,1.0,0.00012735788186546415,-0.0012156128650531173,-0.002407260239124298,-0.44242537021636963,-0.14006301760673523,-0.07755562663078308 -1769682116,605474816,0.0,0.0,0.0,1.0,0.0006084077758714557,0.0002771357831079513,-0.0023436150513589382,-0.7006966471672058,0.0555511899292469,-0.0619940347969532 -1769682116,647301632,0.0,0.0,0.0,1.0,0.0005017513176426291,0.001096357824280858,-0.0022958579938858747,-0.4531354308128357,-0.0638023242354393,-0.04228692874312401 -1769682116,676742400,0.0,0.0,0.0,1.0,0.0003832340007647872,0.0015821295091882348,-0.0022554912138730288,-0.5393231511116028,0.001639610156416893,-0.024026088416576385 -1769682116,705732608,0.0,0.0,0.0,1.0,0.0006488669896498322,0.001746688736602664,-0.0022295599337667227,-0.4533030390739441,-0.06331828236579895,-0.01611408032476902 -1769682116,754630912,0.0,0.0,0.0,1.0,0.0006018636049702764,0.0018532825633883476,-0.0022040936164557934,-0.3882632851600647,0.0228097066283226,-0.012744998559355736 -1769682116,771280640,0.0,0.0,0.0,1.0,0.00043520511826500297,0.0018188116373494267,-0.0021641745697706938,-0.48489484190940857,0.16354703903198242,-0.00809828843921423 -1769682116,804513024,0.0,0.0,0.0,1.0,0.0006099425372667611,0.0015100378077477217,-0.002083628671243787,-0.398902028799057,0.09867984056472778,0.003399989567697048 -1769682116,849638656,0.0,0.0,0.0,1.0,0.0006819505360908806,0.0013566820416599512,-0.0020102178677916527,-0.474420964717865,0.08797968924045563,-0.004087098874151707 -1769682116,871604224,0.0,0.0,0.0,1.0,0.0006829536287114024,0.0012443724554032087,-0.0019467385718598962,-0.3338603675365448,0.18468108773231506,0.0008042226545512676 -1769682116,903796480,0.0,0.0,0.0,1.0,0.00046237086644396186,-0.00022508067195303738,-0.0018031670479103923,-0.24707092344760895,0.11753004044294357,-0.09611620754003525 -1769682116,951067392,0.0,0.0,0.0,1.0,-0.00018095099949277937,-0.0035282550379633904,-0.0016540817450731993,-0.45281729102134705,-0.06487950682640076,-0.07936681807041168 -1769682116,975905024,0.0,0.0,0.0,1.0,-0.0009726008283905685,-0.006043335422873497,-0.001631205785088241,-0.38797247409820557,0.02172008529305458,-0.055650558322668076 -1769682117,4865280,0.0,0.0,0.0,1.0,-0.0013434849679470062,-0.008161336183547974,-0.0015942109748721123,-0.2264271229505539,-0.03244994208216667,-0.038986120373010635 -1769682117,49024256,0.0,0.0,0.0,1.0,-0.0017195872496813536,-0.008947034366428852,-0.0015507542993873358,-0.31264543533325195,0.032890044152736664,-0.024179745465517044 -1769682117,71148032,0.0,0.0,0.0,1.0,-0.0020032764878124,-0.009190277196466923,-0.00148496450856328,-0.45318472385406494,-0.06392347812652588,-0.030063286423683167 -1769682117,105838080,0.0,0.0,0.0,1.0,-0.002326719928532839,-0.008885638788342476,-0.001441742293536663,-0.4638807475566864,0.012098649516701698,-0.0077244797721505165 -1769682117,147550208,0.0,0.0,0.0,1.0,-0.0024006771855056286,-0.008412894792854786,-0.0013911017449572682,-0.29168930649757385,-0.1177651435136795,0.002047126181423664 -1769682117,173863424,0.0,0.0,0.0,1.0,-0.002545691328123212,-0.007869030348956585,-0.0013279865961521864,-0.3128623962402344,0.03355862945318222,0.010772572830319405 -1769682117,205341696,0.0,0.0,0.0,1.0,-0.002584140282124281,-0.007541297934949398,-0.001306902151554823,-0.1618041694164276,0.054929062724113464,0.023082109168171883 -1769682117,252900352,0.0,0.0,0.0,1.0,-0.0026448164135217667,-0.0072285570204257965,-0.0012918091379106045,-0.4639533758163452,0.012292527593672276,0.005865783896297216 -1769682117,270604032,0.0,0.0,0.0,1.0,-0.002620808780193329,-0.007054002024233341,-0.0012914171675220132,-0.38842228055000305,0.022970810532569885,0.01205262541770935 -1769682117,304871424,0.0,0.0,0.0,1.0,-0.0025281019043177366,-0.006949909962713718,-0.0013003809144720435,-0.36726444959640503,-0.12818151712417603,0.012983407825231552 -1769682117,347797248,0.0,0.0,0.0,1.0,-0.002478760899975896,-0.007007749285548925,-0.0013049835106357932,-0.31282758712768555,0.03333800286054611,0.004018514417111874 -1769682117,370545664,0.0,0.0,0.0,1.0,-0.0025318884290754795,-0.006948282942175865,-0.0012990955729037523,-0.3883287012577057,0.02245411090552807,-0.010315566323697567 -1769682117,405909760,0.0,0.0,0.0,1.0,-0.0013818674487993121,-0.006754438858479261,-0.001110763754695654,-0.37779664993286133,-0.052836619317531586,0.00448073074221611 -1769682117,460466176,0.0,0.0,0.0,1.0,-0.0007840268663130701,-0.006459795404225588,-0.0009587568929418921,-0.30223044753074646,-0.04230763018131256,0.0022124960087239742 -1769682117,470945280,0.0,0.0,0.0,1.0,-0.0005038247327320278,-0.00615433044731617,-0.000851383781991899,-0.4533703029155731,-0.06330396234989166,0.011745920404791832 -1769682117,504361984,0.0,0.0,0.0,1.0,-0.00030323484679684043,-0.00601803045719862,-0.0007654062937945127,-0.312803715467453,0.03311695158481598,-0.003991927485913038 -1769682117,546299904,0.0,0.0,0.0,1.0,-0.0002231268590549007,-0.006028907373547554,-0.0007369288941845298,-0.3883465528488159,0.022418081760406494,-0.008699297904968262 -1769682117,585372416,0.0,0.0,0.0,1.0,-0.00014575249224435538,-0.006135288625955582,-0.0007321082521229982,-0.3339901864528656,0.18413200974464417,-0.00938364490866661 -1769682117,605332224,0.0,0.0,0.0,1.0,6.698224024148658e-05,-0.006299575325101614,-0.0007465161615982652,-0.3022252321243286,-0.042323462665081024,0.0037179943174123764 -1769682117,653357312,0.0,0.0,0.0,1.0,0.00026356737362220883,-0.0054419687949121,-0.0008138053817674518,-0.3231268525123596,0.10601102560758591,-0.13402009010314941 -1769682117,672647936,0.0,0.0,0.0,1.0,-0.00044142166734673083,-0.00182644696906209,-0.0009649053099565208,-0.3018125593662262,-0.0462820827960968,-0.19047163426876068 -1769682117,703911168,0.0,0.0,0.0,1.0,-0.0009852191433310509,0.001789896166883409,-0.0011019345838576555,-0.37744593620300293,-0.05607380345463753,-0.1499030590057373 -1769682117,754540288,0.0,0.0,0.0,1.0,-0.0012872955994680524,0.003581927390769124,-0.0011643536854535341,-0.3881066143512726,0.02008233591914177,-0.1205030232667923 -1769682117,771166208,0.0,0.0,0.0,1.0,-0.0015093769179657102,0.0045459214597940445,-0.001201766892336309,-0.3882095515727997,0.02108425833284855,-0.07049437612295151 -1769682117,805211648,0.0,0.0,0.0,1.0,-0.001996649894863367,0.004902360029518604,-0.00123058061581105,-0.29155802726745605,-0.11828428506851196,-0.012670871801674366 -1769682117,867138816,0.0,0.0,0.0,1.0,-0.001994702499359846,0.00469209486618638,-0.0012386988382786512,-0.12990987300872803,-0.172020822763443,0.017409615218639374 -1769682117,878182400,0.0,0.0,0.0,1.0,-0.0023034107871353626,0.00412358995527029,-0.0012476397678256035,-0.30227237939834595,-0.04201030358672142,0.02381923794746399 -1769682117,906778368,0.0,0.0,0.0,1.0,-0.0023557497188448906,0.0036316232290118933,-0.0012404926819726825,-0.39907875657081604,0.0984942615032196,0.024273648858070374 -1769682117,951342336,0.0,0.0,0.0,1.0,-0.002022751374170184,0.003926364704966545,-0.0012295246124267578,-0.32379594445228577,0.11078383773565292,0.10888255387544632 -1769682117,974122240,0.0,0.0,0.0,1.0,-0.0020832631271332502,0.012083443813025951,-0.00122813880443573,-0.5507749915122986,0.08048976957798004,0.1908564269542694 -1769682118,8905728,0.0,0.0,0.0,1.0,-0.001903104828670621,0.016595618799328804,-0.0012277180794626474,-0.47515711188316345,0.0902937799692154,0.15017332136631012 -1769682118,50814208,0.0,0.0,0.0,1.0,-0.0017270473763346672,0.01945185475051403,-0.0012174609582871199,-0.539969265460968,0.0032553542405366898,0.10840814560651779 -1769682118,75290368,0.0,0.0,0.0,1.0,-0.0014623923925682902,0.02107425220310688,-0.0011987461475655437,-0.23751525580883026,0.04452673718333244,0.04441944509744644 -1769682118,104094720,0.0,0.0,0.0,1.0,-0.0005678021116182208,0.021310675889253616,-0.0011571079958230257,-0.3024246096611023,-0.04180223494768143,0.038364849984645844 -1769682118,169719552,0.0,0.0,0.0,1.0,0.00011540550622157753,0.02048550173640251,-0.0010860126931220293,-0.23731009662151337,0.04369035363197327,0.0023555487859994173 -1769682118,177595392,0.0,0.0,0.0,1.0,0.0005656019202433527,0.019304554909467697,-0.0009674211032688618,-0.14032204449176788,-0.09717892855405807,-0.017017412930727005 -1769682118,204016896,0.0,0.0,0.0,1.0,0.0008152688387781382,0.01836673729121685,-0.0008814825559966266,-0.22642064094543457,-0.032488059252500534,-0.02858210913836956 -1769682118,247042048,0.0,0.0,0.0,1.0,0.0009923537727445364,0.017556894570589066,-0.0007991570746526122,-0.3126015365123749,0.032408494502305984,-0.029511861503124237 -1769682118,274503680,0.0,0.0,0.0,1.0,0.0010784328915178776,0.016981864348053932,-0.0007321656448766589,-0.3338716924190521,0.18346378207206726,-0.032831549644470215 -1769682118,306781952,0.0,0.0,0.0,1.0,0.0010274645173922181,0.016665372997522354,-0.0006787328748032451,-0.29135021567344666,-0.11853107810020447,-0.019555408507585526 -1769682118,348482048,0.0,0.0,0.0,1.0,0.001066908473148942,0.016638806089758873,-0.0006582965725101531,-0.22646239399909973,-0.0323018878698349,-0.018353963270783424 -1769682118,370758912,0.0,0.0,0.0,1.0,0.000972979876678437,0.016711631789803505,-0.0006571453996002674,-0.22656671702861786,-0.032095134258270264,-0.0077402545139193535 -1769682118,406373376,0.0,0.0,0.0,1.0,0.0008484629215672612,0.016929632052779198,-0.0006614639423787594,-0.06481607258319855,-0.08633296191692352,-0.006180891301482916 -1769682118,449083136,0.0,0.0,0.0,1.0,0.0009871628135442734,0.017160896211862564,-0.0006682395469397306,-0.24796144664287567,0.11914288997650146,-0.0017153043299913406 -1769682118,471622912,0.0,0.0,0.0,1.0,0.0007701034191995859,0.01721573993563652,-0.0006730457535013556,-0.1511419713497162,-0.021234016865491867,0.0033244933001697063 -1769682118,504370688,0.0,0.0,0.0,1.0,0.0007464080699719489,0.017481058835983276,-0.0006826191092841327,-0.17236192524433136,0.12970271706581116,-0.006015872582793236 -1769682118,553529856,0.0,0.0,0.0,1.0,0.000734726432710886,0.017447156831622124,-0.0006831996142864227,-0.22676585614681244,-0.03179052099585533,0.008287266828119755 -1769682118,571609344,0.0,0.0,0.0,1.0,0.0006727600703015924,0.017556799575686455,-0.0006736678187735379,-0.08618880063295364,0.06485956162214279,-0.002505357377231121 -1769682118,604399872,0.0,0.0,0.0,1.0,0.0008032267214730382,0.017528381198644638,-0.0006427296902984381,-0.0755561962723732,-0.010647718794643879,0.0002868747105821967 -1769682118,640574464,0.0,0.0,0.0,1.0,0.0006562083726748824,0.013229474425315857,-0.0006007928168401122,0.08013299852609634,-0.056937217712402344,0.39945167303085327 -1769682118,672621312,0.0,0.0,0.0,1.0,0.00019054088625125587,0.007832986302673817,-0.0005314784939400852,0.005519022699445486,-0.06893883645534515,0.33177781105041504 -1769682118,705362432,0.0,0.0,0.0,1.0,4.869904660154134e-05,0.0035115911159664392,-0.0004200562834739685,0.07168885320425034,0.015552985481917858,0.24527709186077118 -1769682118,750159616,0.0,0.0,0.0,1.0,5.7027376897167414e-05,0.0019797738641500473,-0.00033566777710802853,0.0731801763176918,0.013650608249008656,0.14994537830352783 -1769682118,781697792,0.0,0.0,0.0,1.0,4.0133672882802784e-05,-0.0008297843160107732,-0.0003001397126354277,-0.15313014388084412,-0.018760327249765396,0.12793071568012238 -1769682118,805010432,0.0,0.0,0.0,1.0,-0.00011349190754117444,-0.004853064194321632,-0.0003090412064921111,-0.06577906757593155,-0.08506359159946442,0.057905394583940506 -1769682118,851333888,0.0,0.0,0.0,1.0,-8.553273801226169e-05,-0.005997384898364544,-0.0003301073156762868,-0.15090732276439667,-0.021571563556790352,-0.012643172405660152 -1769682118,871002368,0.0,0.0,0.0,1.0,-5.8533249102765694e-05,-0.005819777958095074,-0.0003548101813066751,-0.301599383354187,-0.04343158006668091,-0.03953338414430618 -1769682118,905012992,0.0,0.0,0.0,1.0,0.00018702216038946062,-0.004501326009631157,-0.0003994579310528934,-0.38745975494384766,0.02095858007669449,-0.0647134780883789 -1769682118,954781952,0.0,0.0,0.0,1.0,2.754834531515371e-05,-0.001447221264243126,-0.00047824278590269387,-0.32293057441711426,0.1076127141714096,-0.04277627170085907 -1769682118,970632192,0.0,0.0,0.0,1.0,-3.852925874525681e-05,-9.958157170331106e-05,-0.0005363165982998908,-0.3983614146709442,0.09678388386964798,-0.050845321267843246 -1769682119,5620992,0.0,0.0,0.0,1.0,-3.992030906374566e-05,0.002074547577649355,-0.0006448879721574485,-0.32287850975990295,0.10753032565116882,-0.046365268528461456 -1769682119,63173632,0.0,0.0,0.0,1.0,0.00015119524323381484,0.0032663666643202305,-0.0006979822646826506,-0.21547436714172363,-0.10820350050926208,-0.03211216628551483 -1769682119,71416576,0.0,0.0,0.0,1.0,0.00024543574545532465,0.004777013789862394,-0.0007029575062915683,-0.31213465332984924,0.03189489245414734,-0.0495307557284832 -1769682119,104860416,0.0,0.0,0.0,1.0,0.00026915865601040423,0.007296807132661343,-0.000646169064566493,-0.2258836179971695,-0.03299785405397415,-0.04935761168599129 -1769682119,149005056,0.0,0.0,0.0,1.0,0.0003946376091334969,0.007622517645359039,-0.0006112802075222135,-0.07598616927862167,-0.010119606740772724,0.027622796595096588 -1769682119,170608128,0.0,0.0,0.0,1.0,0.0004282654554117471,0.005588551051914692,-0.0005632757092826068,-0.00026640130090527236,0.0003336310328450054,0.016683897003531456 -1769682119,204672512,0.0,0.0,0.0,1.0,0.0006176606984809041,0.0035541641991585493,-0.00036543127498589456,-0.0864928811788559,0.06518923491239548,0.01518680527806282 -1769682119,250166528,0.0,0.0,0.0,1.0,0.00042908225441351533,0.0025698011741042137,-0.00020760482584591955,-0.00046400484279729426,0.0005727516836486757,0.028600750491023064 -1769682119,270542080,0.0,0.0,0.0,1.0,0.0003549572138581425,0.0021713741589337587,-7.850959082134068e-05,-0.07572797685861588,-0.010456034913659096,0.010900754481554031 -1769682119,306578176,0.0,0.0,0.0,1.0,0.00018883154552895576,0.0018370718462392688,9.05707656784216e-06,-0.14057224988937378,-0.09669995307922363,0.010369982570409775 -1769682119,354455296,0.0,0.0,0.0,1.0,0.00016638838860671967,0.0019196404609829187,1.9289576812298037e-05,0.01059239637106657,-0.07542962580919266,0.006456262432038784 -1769682119,373160704,0.0,0.0,0.0,1.0,-2.075288830383215e-05,0.0020889986772090197,-7.079653187247459e-06,-0.07543543726205826,-0.010814289562404156,-0.006989104673266411 -1769682119,404863232,0.0,0.0,0.0,1.0,-9.13077310542576e-05,0.0025144927203655243,-7.008959073573351e-05,0.02116328291594982,-0.15083537995815277,0.01410695817321539 -1769682119,454989568,0.0,0.0,0.0,1.0,5.046407750342041e-05,0.0027514782268553972,-0.00011588294000830501,-0.06500175595283508,-0.08605314791202545,0.008989482186734676 -1769682119,472393984,0.0,0.0,0.0,1.0,7.077852205839008e-05,0.003065485041588545,-0.00015007476031314582,-0.2265399694442749,-0.03215818107128143,-0.006727094762027264 -1769682119,507426560,0.0,0.0,0.0,1.0,0.000210518017411232,0.003233111696317792,-0.00014017037756275386,-0.23725014925003052,0.04341331496834755,-0.0060668447986245155 -1769682119,547501824,0.0,0.0,0.0,1.0,0.00022710436314810067,0.003302369499579072,-0.00011247352813370526,-0.15086360275745392,-0.02163141593337059,-0.014052139595150948 -1769682119,576439552,0.0,0.0,0.0,1.0,0.00041279220022261143,0.0027300240471959114,-2.0415234757820144e-05,-0.0009577639866620302,0.0011236242717131972,0.056008949875831604 -1769682119,604532224,0.0,0.0,0.0,1.0,0.00031941564520820975,0.0017876920755952597,6.573085556738079e-05,-0.08700129389762878,0.0657612532377243,0.043695006519556046 -1769682119,648817664,0.0,0.0,0.0,1.0,0.00021163544442970306,0.001158007769845426,0.00015604501822963357,-0.07627071440219879,-0.009834866970777512,0.04181574285030365 -1769682119,671294720,0.0,0.0,0.0,1.0,4.773140244651586e-05,0.0006355195655487478,0.0002327204419998452,-0.08677762001752853,0.06549938023090363,0.030580326914787292 -1769682119,706362368,0.0,0.0,0.0,1.0,0.00010561156523181126,0.00021737471979577094,0.00032280030427500606,-0.010956788435578346,0.07586024701595306,0.014982718974351883 -1769682119,753533952,0.0,0.0,0.0,1.0,0.00026148484903387725,0.00010566340642981231,0.0003745096328202635,-0.07573847472667694,-0.010454539209604263,0.010829086415469646 -1769682119,773323008,0.0,0.0,0.0,1.0,0.0005760896601714194,5.68667528568767e-05,0.0006045080372132361,-0.02119072899222374,0.15088315308094025,-0.011745263822376728 -1769682119,805901568,0.0,0.0,0.0,1.0,3.130148979835212e-05,0.00023042304383125156,0.000861375592648983,0.00016446440713480115,-0.0001917733607115224,-0.009533403441309929 -1769682119,852177920,0.0,0.0,0.0,1.0,0.0005999954883009195,0.00034045043867081404,0.0013075231108814478,-0.07543101906776428,-0.0108075812458992,-0.007046885788440704 -1769682119,872797184,0.0,0.0,0.0,1.0,0.0006039386498741806,0.001559871481731534,0.001606346108019352,0.06436065584421158,0.0868111252784729,0.02917640469968319 -1769682119,904311808,0.0,0.0,0.0,1.0,0.0003645635151769966,0.0027944990433752537,0.0018696399638429284,-0.08639506250619888,0.06508877873420715,0.00911042746156454 -1769682119,954460160,0.0,0.0,0.0,1.0,0.00021861617278773338,0.0033437637612223625,0.0020087012089788914,-0.09704039990901947,0.1406218558549881,0.007391679100692272 -1769682119,972879104,0.0,0.0,0.0,1.0,0.00011657911818474531,0.0037523782812058926,0.002101802732795477,-0.08611658215522766,0.06478670984506607,-0.006399653386324644 -1769682120,4436736,0.0,0.0,0.0,1.0,-5.532929571927525e-05,0.0038985146675258875,0.0021701641380786896,-0.08611002564430237,0.06479409337043762,-0.00641313660889864 -1769682120,47702784,0.0,0.0,0.0,1.0,-0.0001503884996054694,0.0037862518802285194,0.0021861507557332516,-0.12968400120735168,-0.17252115905284882,-0.005988466087728739 -1769682120,73811712,0.0,0.0,0.0,1.0,-6.104270869400352e-05,0.0037524288054555655,0.002183485310524702,0.00010704956366680562,-0.00012024985335301608,-0.005958294030278921 -1769682120,106651136,0.0,0.0,0.0,1.0,-0.00016426669026259333,0.0034969784319400787,0.002136912662535906,0.08617985993623734,-0.06490906327962875,0.001677689841017127 -1769682120,154155776,0.0,0.0,0.0,1.0,-0.00024424894945695996,0.0033642950002104044,0.002084660343825817,-0.20549681782722473,-0.1828707903623581,0.005909077823162079 -1769682120,171787264,0.0,0.0,0.0,1.0,-0.0002983611193485558,0.0032368157990276814,0.002027470851317048,0.08614961802959442,-0.06489578634500504,0.0028858801815658808 -1769682120,204999936,0.0,0.0,0.0,1.0,-9.488762589171529e-05,0.0031279430259019136,0.0019493296276777983,-0.0753866657614708,-0.010799510404467583,-0.009519851766526699 -1769682120,252195584,0.0,0.0,0.0,1.0,-0.0003993803693447262,0.003110102377831936,0.0018887198530137539,-0.06491969525814056,-0.08618565648794174,-0.0006587310344912112 -1769682120,271371008,0.0,0.0,0.0,1.0,-0.00025624182308092713,0.003067584941163659,0.0018338034860789776,-0.010572629980742931,0.07551121711730957,-0.00291054742410779 -1769682120,304305920,0.0,0.0,0.0,1.0,-0.0002645046915858984,0.0029807770624756813,0.0017723330529406667,-0.0860196053981781,0.06479860842227936,-0.008879352360963821 -1769682120,358757888,0.0,0.0,0.0,1.0,-0.00014212903624866158,0.0029234399553388357,0.0017264833441004157,-0.07552006840705872,-0.010637441650032997,-0.002399918856099248 -1769682120,373471488,0.0,0.0,0.0,1.0,-0.0001600052637513727,0.0030128732323646545,0.001678499742411077,0.07556545734405518,0.010585611686110497,2.3427768610417843e-05 -1769682120,405176064,0.0,0.0,0.0,1.0,-0.0002255082072224468,0.0029434242751449347,0.0016042415518313646,-0.07554347813129425,-0.010604655370116234,-0.001224078587256372 -1769682120,461827584,0.0,0.0,0.0,1.0,-0.00017829175340011716,0.002911667339503765,0.0015506611671298742,-0.06499439477920532,-0.08611541241407394,0.0016830088570713997 -1769682120,469638400,0.0,0.0,0.0,1.0,-2.700522236409597e-05,0.002959413919597864,0.001487532164901495,0.07554423809051514,0.010597665794193745,0.0012375686783343554 -1769682120,505904896,0.0,0.0,0.0,1.0,-0.00022140568762551993,0.002009688876569271,0.0013830551179125905,-0.07660287618637085,-0.009490590542554855,0.05356979742646217 -1769682120,551435520,0.0,0.0,0.0,1.0,-0.00014381752407643944,0.0011414734181016684,0.0012884698808193207,0.07450772076845169,0.011668906547129154,0.05487178638577461 -1769682120,571155968,0.0,0.0,0.0,1.0,-0.00031213610782288015,0.00046085621579550207,0.00117558054625988,-0.06567934900522232,-0.08540910482406616,0.03622201830148697 -1769682120,605197312,0.0,0.0,0.0,1.0,-0.00031736373784951866,-0.00014529867621604353,0.0009949596133083105,0.01016283594071865,-0.07513370364904404,0.021979806944727898 -1769682120,649495552,0.0,0.0,0.0,1.0,-0.0004757677670568228,-0.0003327328886371106,0.0008301199995912611,-0.06529290974140167,-0.0858122855424881,0.015962496399879456 -1769682120,671953664,0.0,0.0,0.0,1.0,-0.0003458020801190287,-0.00041581771802157164,0.000511094112880528,0.08600608259439468,-0.0648643895983696,0.007736267521977425 -1769682120,704272640,0.0,0.0,0.0,1.0,0.0002886066504288465,-0.0003784601576626301,-0.0003206460678484291,-0.14042559266090393,-0.09682321548461914,-0.006731540895998478 -1769682120,749827328,0.0,0.0,0.0,1.0,8.376090409001336e-05,-0.00026809528935700655,-0.0008964370936155319,0.06526816636323929,0.08583676815032959,-0.014775015413761139 -1769682120,771568896,0.0,0.0,0.0,1.0,0.00014233510592021048,7.641252159373835e-05,-0.0011157268891111016,-0.08649288862943649,0.065362848341465,0.017289351671934128 -1769682120,804899072,0.0,0.0,0.0,1.0,-0.0003872882225550711,0.0016333883395418525,-0.0014666913775727153,-0.021396270021796227,0.15136738121509552,0.010856104083359241 -1769682120,862105600,0.0,0.0,0.0,1.0,-0.0004986486164852977,0.0025335673708468676,-0.0016583482502028346,-0.06521293520927429,-0.08589296787977219,0.012382591143250465 -1769682120,871430912,0.0,0.0,0.0,1.0,-0.0005487219896167517,0.003098325338214636,-0.0018044142052531242,-0.06516297906637192,-0.08594442903995514,0.009992026723921299 -1769682120,906861824,0.0,0.0,0.0,1.0,-0.0006886097835376859,0.0035126779694110155,-0.0019318392733111978,-0.07547276467084885,-0.010673768818378448,-0.004847282078117132 -1769682120,950645248,0.0,0.0,0.0,1.0,-0.0005720603512600064,0.0035632073413580656,-0.001978771761059761,0.010435524396598339,-0.07539468258619308,0.008869919925928116 -1769682120,970925824,0.0,0.0,0.0,1.0,-0.0007088002748787403,0.003587848274037242,-0.0020049898885190487,-0.07528102397918701,-0.01087308581918478,-0.01439683698117733 -1769682121,4650240,0.0,0.0,0.0,1.0,-0.000341228413162753,0.003399550449103117,-0.0019928463734686375,-0.08605587482452393,0.06484778970479965,-0.006594507955014706 -1769682121,54476800,0.0,0.0,0.0,1.0,-0.0005015825154259801,0.003286432707682252,-0.001982080517336726,0.07561159133911133,0.010550307109951973,-0.0022675134241580963 -1769682121,70783488,0.0,0.0,0.0,1.0,-0.0005228737718425691,0.0031134316232055426,-0.001971476711332798,0.07556302100419998,0.010602317750453949,0.0001230492489412427 -1769682121,105748992,0.0,0.0,0.0,1.0,-0.000475209963042289,0.00296197272837162,-0.0019741251599043608,0.0002907118760049343,-0.00028472888516262174,-0.014299335889518261 -1769682121,153266432,0.0,0.0,0.0,1.0,-0.00035176819073967636,0.0028866934590041637,-0.0019861524924635887,0.1511717140674591,0.021178103983402252,-0.0021049599163234234 -1769682121,172419072,0.0,0.0,0.0,1.0,-0.00026046857237815857,0.00286357500590384,-0.0020059768576174974,-0.01080554910004139,0.07572263479232788,0.007813254371285439 -1769682121,204939264,0.0,0.0,0.0,1.0,-0.0004076180048286915,0.002769240876659751,-0.002030991716310382,0.08600399643182755,-0.06474307924509048,0.010215362533926964 -1769682121,263363072,0.0,0.0,0.0,1.0,-0.0002404112892691046,0.0027712590526789427,-0.0020507515873759985,-0.06496354192495346,-0.08613596856594086,0.0027507790364325047 -1769682121,271829248,0.0,0.0,0.0,1.0,-0.0002559552958700806,0.0027841643895953894,-0.0020556808449327946,0.01082316692918539,-0.07572018355131149,-0.007812561467289925 -1769682121,307052032,0.0,0.0,0.0,1.0,-0.00011616612027864903,0.00280297570861876,-0.0020499543752521276,-0.010431711561977863,0.07534091174602509,-0.011253858916461468 -1769682121,350600704,0.0,0.0,0.0,1.0,-0.00010109929280588403,0.0028790305368602276,-0.0020289025269448757,0.010710487142205238,-0.07560036331415176,-0.0018531589303165674 -1769682121,371316480,0.0,0.0,0.0,1.0,-0.00010857790766749531,0.0028513974975794554,-0.0019989744760096073,-0.06511753797531128,-0.08598779886960983,0.011066244915127754 -1769682121,404295680,0.0,0.0,0.0,1.0,0.00013713283988181502,0.0026274637784808874,-0.0019355305703356862,0.05358262360095978,0.16234804689884186,0.028922999277710915 -1769682121,448612096,0.0,0.0,0.0,1.0,-5.07231306983158e-05,0.001556347357109189,-0.0018842574208974838,0.139092817902565,0.09812008589506149,0.06302481144666672 -1769682121,471294976,0.0,0.0,0.0,1.0,9.73599890130572e-06,0.0006772529450245202,-0.001840056967921555,-0.07636576890945435,-0.009906329214572906,0.03792720288038254 -1769682121,505141504,0.0,0.0,0.0,1.0,-3.803787330980413e-05,-0.00019092572620138526,-0.0017894994234666228,-0.0005579521530307829,0.0005196441779844463,0.026214974001049995 -1769682121,554880256,0.0,0.0,0.0,1.0,-0.00022256329248193651,-0.0005449447780847549,-0.0017610100330784917,-0.0654219314455986,-0.08570157736539841,0.026543840765953064 -1769682121,572073984,0.0,0.0,0.0,1.0,-0.00012317253276705742,-0.0006515112472698092,-0.0017357623437419534,0.08606794476509094,-0.06470736861228943,0.009074196219444275 -1769682121,605460480,0.0,0.0,0.0,1.0,-0.0001297698327107355,-0.0006308001466095448,-0.0017188478959724307,-0.07550116628408432,-0.010728323832154274,-0.0025831065140664577 -1769682121,661194752,0.0,0.0,0.0,1.0,-0.00010032855061581358,-0.0005455164355225861,-0.0017023782711476088,0.06502632051706314,0.08606712520122528,-0.008672282099723816 -1769682121,674567424,0.0,0.0,0.0,1.0,-0.00011330821143928915,-0.0002503308351151645,-0.001695220242254436,-0.05398489162325859,-0.16192463040351868,-0.006289397832006216 -1769682121,707147520,0.0,0.0,0.0,1.0,-0.00013690687774214894,0.00037297981907613575,-0.00167933595366776,-0.08623550087213516,0.06482844799757004,-0.0019185757264494896 -1769682121,752012544,0.0,0.0,0.0,1.0,-0.00020103697897866368,0.0009561809711158276,-0.0016677523963153362,0.054297301918268204,0.16162370145320892,-0.009198667481541634 -1769682121,785756416,0.0,0.0,0.0,1.0,-0.00014334532897919416,0.00143154663965106,-0.0016556769842281938,-0.010642308741807938,0.07547424733638763,-0.004103524144738913 -1769682121,805557760,0.0,0.0,0.0,1.0,-8.47748015075922e-05,0.001777393976226449,-0.001632552477531135,-0.05377107858657837,-0.16210104525089264,-0.01464006956666708 -1769682121,853636864,0.0,0.0,0.0,1.0,-5.806478293379769e-05,0.001879049465060234,-0.0016156226629391313,0.010650452226400375,-0.07547305524349213,0.004104183055460453 -1769682121,871475712,0.0,0.0,0.0,1.0,-8.536871609976515e-05,0.0018149222014471889,-0.0015860034618526697,-0.021282121539115906,0.15092159807682037,-0.009400599636137486 -1769682121,904689920,0.0,0.0,0.0,1.0,-5.732024146709591e-05,0.0017227140488103032,-0.0015385134611278772,0.010658256709575653,-0.0754719078540802,0.0041049811989068985 -1769682121,950520576,0.0,0.0,0.0,1.0,-0.00013976029003970325,0.0016377808060497046,-0.0015111586544662714,0.08631022274494171,-0.06484360992908478,-0.00043563125655055046 -1769682121,973177856,0.0,0.0,0.0,1.0,-0.00013287231558933854,0.0015330383321270347,-0.001481160637922585,0.16165247559547424,-0.053926266729831696,0.00932989176362753 -1769682122,6244352,0.0,0.0,0.0,1.0,-9.280332960770465e-06,0.001460449886508286,-0.0014619111316278577,-0.021260248497128487,0.1508701890707016,-0.011786134913563728 -1769682122,78446080,0.0,0.0,0.0,1.0,-0.00014427707355935127,0.0014129556948319077,-0.0014561170246452093,0.053941428661346436,0.16190797090530396,0.003941178321838379 -1769682122,90869504,0.0,0.0,0.0,1.0,-0.00017955186194740236,0.0014543875586241484,-0.0014524483121931553,0.1616336852312088,-0.05387695133686066,0.010546241886913776 -1769682122,102663680,0.0,0.0,0.0,1.0,-0.0002758967748377472,0.001485734130255878,-0.001457622624002397,-0.0861435979604721,0.06465891748666763,-0.007923985831439495 -1769682122,146914048,0.0,0.0,0.0,1.0,-0.00016218317614402622,0.0015922222519293427,-0.0014595617540180683,0.02139294520020485,-0.1509600728750229,0.007020246237516403 -1769682122,171669248,0.0,0.0,0.0,1.0,-0.00012188695109216496,0.0015398272080346942,-0.0014566712779924273,-0.07554221153259277,-0.010747365653514862,-0.00025174033362418413 -1769682122,208599552,0.0,0.0,0.0,1.0,-0.0001523784885648638,0.0016706170281395316,-0.001452148426324129,0.16185137629508972,-0.054034266620874405,0.0010448818793520331 -1769682122,249823232,0.0,0.0,0.0,1.0,-0.0002054628130281344,0.0017158379778265953,-0.001430880045518279,-0.04325296729803085,-0.23734354972839355,0.002525996183976531 -1769682122,272281088,0.0,0.0,0.0,1.0,-0.00010228955216007307,0.0017448051366955042,-0.0014085735892876983,0.06484495103359222,0.0862247496843338,-0.003842146135866642 -1769682122,304360704,0.0,0.0,0.0,1.0,-0.0001776401768438518,0.0017207404598593712,-0.0013696778332814574,0.07567206025123596,0.010645195841789246,-0.005687948316335678 -1769682122,360450048,0.0,0.0,0.0,1.0,-1.946805787156336e-05,0.0015185002703219652,-0.0013264429289847612,0.15015266835689545,0.022351358085870743,0.042252399027347565 -1769682122,371616768,0.0,0.0,0.0,1.0,-0.0001731643860694021,0.0009178959298878908,-0.0012944408226758242,0.010174978524446487,-0.07499640434980392,0.027939047664403915 -1769682122,405915392,0.0,0.0,0.0,1.0,-0.00023090174363460392,0.0002601706946734339,-0.0012561158509925008,0.08569027483463287,-0.06420033425092697,0.02940831519663334 -1769682122,447027968,0.0,0.0,0.0,1.0,-7.141958485590294e-05,7.935056783026084e-05,-0.0012213460868224502,0.06437522172927856,0.08663743734359741,0.016427570953965187 -1769682122,474732032,0.0,0.0,0.0,1.0,-0.00020513507479336113,4.731239459943026e-05,-0.0011904583079740405,-0.00013272560318000615,0.0001170638352050446,0.005957840476185083 -1769682122,507408128,0.0,0.0,0.0,1.0,-0.00017282486078329384,-6.790528459532652e-07,-0.0011730713304132223,0.010585304349660873,-0.07534635066986084,0.010064128786325455 -1769682122,553486336,0.0,0.0,0.0,1.0,-0.0003044283075723797,5.7527260651113465e-05,-0.001161292428150773,0.010720661841332912,-0.07546302676200867,0.004105820320546627 -1769682122,571810816,0.0,0.0,0.0,1.0,-0.00019346615590620786,0.00020367465913295746,-0.0011479078093543649,0.00010621539695421234,-9.356174268759787e-05,-0.004766273777931929 -1769682122,606214912,0.0,0.0,0.0,1.0,-0.00011175801046192646,0.0003023297758772969,-0.0011384051758795977,-0.0862361267209053,0.06464878469705582,-0.005576600320637226 -1769682122,671635968,0.0,0.0,0.0,1.0,-9.084476914722472e-05,0.000491483137011528,-0.0011221881723031402,0.08639848977327347,-0.06478516012430191,-0.0015718007925897837 -1769682122,678611968,0.0,0.0,0.0,1.0,-6.22747975285165e-05,0.0005581967998296022,-0.0011048910673707724,-0.010705840773880482,0.07543804496526718,-0.0052962652407586575 -1769682122,704504320,0.0,0.0,0.0,1.0,-4.60457886219956e-05,0.0005998884444124997,-0.001076027750968933,-0.09705774486064911,0.14017044007778168,-0.006109973415732384 -1769682122,761446400,0.0,0.0,0.0,1.0,-6.255021435208619e-05,0.0006979249883443117,-0.0010385233908891678,0.06493061780929565,0.08614476770162582,-0.009777052327990532 -1769682122,769458688,0.0,0.0,0.0,1.0,-0.00022179044026415795,0.0007038661860860884,-0.0010038396576419473,-0.06460802257061005,-0.0864269956946373,-0.004523536656051874 -1769682122,805737216,0.0,0.0,0.0,1.0,-0.00016496847092639655,0.0005165613838471472,-0.0009544407948851585,0.23745013773441315,-0.043135300278663635,0.00020466395653784275 -1769682122,849897984,0.0,0.0,0.0,1.0,-0.00018557868315838277,0.00043023659964092076,-0.0009285559644922614,0.22614581882953644,0.03282121941447258,0.021126531064510345 -1769682122,873952256,0.0,0.0,0.0,1.0,-0.00014883026597090065,0.0005437227082438767,-0.0009056791313923895,0.21574606001377106,0.10798349231481552,0.001535751624032855 -1769682122,905028864,0.0,0.0,0.0,1.0,-4.608225208357908e-05,0.0005361305666156113,-0.0008804579847492278,-8.032162440940738e-05,6.99658558005467e-05,0.003574694273993373 -1769682122,948330752,0.0,0.0,0.0,1.0,-0.00024099792062770575,0.0005903231212869287,-0.0008666174835525453,-0.08633674681186676,0.06469061970710754,-0.0020146516617387533 -1769682122,971231744,0.0,0.0,0.0,1.0,-0.00019437223090790212,0.00035826137172989547,-0.0008527797181159258,0.05365154892206192,0.16206037998199463,0.008770693093538284 -1769682123,14321152,0.0,0.0,0.0,1.0,-0.00019728443294297904,0.00014329369878396392,-0.0008373322780244052,0.140066996216774,0.09730669856071472,0.007213565520942211 -1769682123,48486144,0.0,0.0,0.0,1.0,-0.00016572805179748684,-4.4212345528649166e-05,-0.0008232525433413684,0.07561198621988297,0.010751351714134216,-0.0032783891074359417 -1769682123,70996224,0.0,0.0,0.0,1.0,-0.0002814080798998475,-0.00014846977137494832,-0.0008040004759095609,0.23735256493091583,-0.04298859462141991,0.004990234971046448 -1769682123,104962304,0.0,0.0,0.0,1.0,-3.869335341732949e-05,-0.000302920991089195,-0.0007717281114310026,0.1509009599685669,0.021790554746985435,0.0077398912981152534 -1769682123,164114432,0.0,0.0,0.0,1.0,-8.632100070826709e-05,-0.0003035346744582057,-0.0007348844083026052,-0.010843386873602867,0.07552707940340042,-0.0005264513893052936 -1769682123,174550016,0.0,0.0,0.0,1.0,-0.0001067709454218857,-0.00032368864049203694,-0.000698604213539511,0.07539650797843933,0.010945086367428303,0.006251716986298561 -1769682123,204349952,0.0,0.0,0.0,1.0,-0.0001673492370173335,-0.0004465871024876833,-0.0006326789734885097,0.010847000405192375,-0.07552656531333923,0.0005254887510091066 -1769682123,247801344,0.0,0.0,0.0,1.0,-9.624045560485683e-07,-0.000390712171792984,-0.0005769931012764573,-0.09703939408063889,0.14005784690380096,-0.009683210402727127 -1769682123,271202816,0.0,0.0,0.0,1.0,-8.900941611500457e-05,-0.00040570987039245665,-0.000527931668329984,0.0755297914147377,0.010833319276571274,0.00029098609229549766 -1769682123,308440832,0.0,0.0,0.0,1.0,-4.504049138631672e-05,-0.0003959887835662812,-0.0004740200820378959,-0.06457159668207169,-0.08645378053188324,-0.004531831946223974 -1769682123,357913856,0.0,0.0,0.0,1.0,-0.00015572496340610087,-0.0004422259808052331,-0.0004465666424948722,-0.010745317675173283,0.07543288171291351,-0.005289894063025713 -1769682123,372419584,0.0,0.0,0.0,1.0,-0.0002727175015024841,-0.00045583059545606375,-0.00043287946027703583,0.01082644797861576,-0.07550246268510818,0.0017145626479759812 -1769682123,406141440,0.0,0.0,0.0,1.0,-0.00012877208064310253,-0.000434837827924639,-0.0004367823130451143,-0.02162892371416092,0.1509813666343689,-0.0046190135180950165 -1769682123,453977856,0.0,0.0,0.0,1.0,-0.0003244215913582593,-0.00048210148815996945,-0.00045932165812700987,-7.996303611434996e-05,6.963260238990188e-05,0.0035747087094932795 -1769682123,472190976,0.0,0.0,0.0,1.0,-0.0003239572106394917,-0.0005008391453884542,-0.0004844038048759103,0.1510576605796814,0.02168048545718193,0.0005693900166079402 -1769682123,505093888,0.0,0.0,0.0,1.0,-0.0003487978538032621,-0.0005828975117765367,-0.000532936246600002,0.07563505321741104,0.010749032720923424,-0.004483072552829981 -1769682123,548013056,0.0,0.0,0.0,1.0,-0.0003249191795475781,-0.0005904024001210928,-0.0005712456186302006,0.2264789193868637,0.032621853053569794,0.005612642504274845 -1769682123,573974016,0.0,0.0,0.0,1.0,-0.00028056916198693216,-0.0009990750113502145,-0.0006001184810884297,0.08662809431552887,-0.06488871574401855,-0.009926105849444866 -1769682123,606787584,0.0,0.0,0.0,1.0,-0.0002590914664324373,-0.0015009636990725994,-0.0006306790164671838,0.07581951469182968,0.010591617785394192,-0.012830808758735657 -1769682123,639700992,0.0,0.0,0.0,1.0,-0.00040269180317409337,-0.0017653219401836395,-0.0006430846406146884,0.00015865273599047214,-0.00013882690109312534,-0.0071494546718895435 -1769682123,670886400,0.0,0.0,0.0,1.0,-0.00036944958264939487,-0.001987675903365016,-0.0006443791789934039,0.09746984392404556,-0.140383780002594,-0.008236724883317947 -1769682123,709760512,0.0,0.0,0.0,1.0,-0.0002507655881345272,-0.002172286855056882,-0.0006329923053272069,0.0754222497344017,0.010943553410470486,0.005028577987104654 -1769682123,749627904,0.0,0.0,0.0,1.0,-0.0002072350907837972,-0.0021547318901866674,-0.0006103852647356689,-0.1293686181306839,-0.1727057695388794,0.0028900427278131247 -1769682123,773331200,0.0,0.0,0.0,1.0,-0.00015488150529563427,-0.002165710087865591,-0.0005740294000133872,0.15108010172843933,0.02168455719947815,-0.0006865030154585838 -1769682123,805691904,0.0,0.0,0.0,1.0,-0.0002017073566094041,-0.0021081974264234304,-0.0005147896590642631,-0.06455062329769135,-0.08647088706493378,-0.004504335578531027 -1769682123,869608448,0.0,0.0,0.0,1.0,-2.627882349770516e-05,-0.0020919686648994684,-0.00046844009193591774,-0.15092355012893677,-0.021828535944223404,-0.006440893746912479 -1769682123,877088512,0.0,0.0,0.0,1.0,-0.00010833086707862094,-0.0019953588489443064,-0.00042270394624210894,0.06485866755247116,0.08619599044322968,-0.00980319082736969 -1769682123,906696704,0.0,0.0,0.0,1.0,-0.00022223632549867034,-0.0019108615815639496,-0.000398851465433836,7.733671372989193e-05,-6.920738815097138e-05,-0.003574775066226721 -1769682123,951458048,0.0,0.0,0.0,1.0,-0.00019649781461339444,-0.0018900299910455942,-0.00038220814894884825,0.06457266211509705,0.08645133674144745,0.003297997172921896 -1769682123,979408128,0.0,0.0,0.0,1.0,-0.000323315616697073,-0.0018024417804554105,-0.00037252894253470004,-7.687068136874586e-05,6.914436380611733e-05,0.003574786242097616 -1769682124,5885184,0.0,0.0,0.0,1.0,-0.00021075294353067875,-0.0017279188614338636,-0.0003669446741696447,2.5561490474501625e-05,-2.3040909582050517e-05,-0.0011915969662368298 -1769682124,53936384,0.0,0.0,0.0,1.0,-0.00021488135098479688,-0.0017198120476678014,-0.0003670675796456635,-0.07547486573457718,-0.010908534750342369,-0.002596850972622633 -1769682124,72290048,0.0,0.0,0.0,1.0,-0.00021718777134083211,-0.0017652572132647038,-0.0003643165109679103,0.07570382207632065,0.010702138766646385,-0.008131397888064384 -1769682124,109234944,0.0,0.0,0.0,1.0,-0.0001070816651917994,-0.0017247986979782581,-0.00036078126868233085,-0.08628015220165253,0.06454237550497055,-0.006659922190010548 -1769682124,141402112,0.0,0.0,0.0,1.0,-0.00027550337836146355,-0.0017469606827944517,-0.0003591689164750278,-0.07539904862642288,-0.01098020188510418,-0.006158731412142515 -1769682124,171046144,0.0,0.0,0.0,1.0,-0.0003395032836124301,-0.001590639934875071,-0.00036581343738362193,0.07547493278980255,0.010912002064287663,0.002580266445875168 -1769682124,207423232,0.0,0.0,0.0,1.0,-0.0004725008038803935,-0.0013888335088267922,-0.0003997438179794699,0.0003522448823787272,-0.00032163041760213673,-0.016682494431734085 -1769682124,254526464,0.0,0.0,0.0,1.0,-0.00026099657407030463,-0.000775266787968576,-0.0004340053419582546,-0.07504773139953613,-0.011304432526230812,-0.02283099666237831 -1769682124,272474368,0.0,0.0,0.0,1.0,-0.00015377132513094693,-0.0003444150206632912,-0.0004765259800478816,-0.1614590734243393,0.053346678614616394,-0.023511001840233803 -1769682124,304687616,0.0,0.0,0.0,1.0,-0.0002688980021048337,4.778341099154204e-05,-0.0005492573254741728,-0.0214743223041296,0.15076658129692078,-0.015280544757843018 -1769682124,349755648,0.0,0.0,0.0,1.0,-0.0003731480101123452,0.00020890578161925077,-0.0006039320142008364,-0.08618766069412231,0.06444230675697327,-0.011404329910874367 -1769682124,376330496,0.0,0.0,0.0,1.0,-0.00030510182841680944,0.00029857433401048183,-0.0006760614924132824,0.010815693065524101,-0.07545171678066254,0.004064131993800402 -1769682124,407263488,0.0,0.0,0.0,1.0,-0.00037571266875602305,0.00029383902437984943,-0.0007251798524521291,-0.1617898941040039,0.05363152548670769,-0.008021614514291286 -1769682124,449783552,0.0,0.0,0.0,1.0,-0.00018864875892177224,0.0002226249489467591,-0.0007662635180167854,-0.0647551417350769,-0.08628285676240921,0.006254249252378941 -1769682124,471452416,0.0,0.0,0.0,1.0,-0.00022549401910509914,0.00013870133261661977,-0.0008091723429970443,0.06452673673629761,0.08649042993783951,0.0044712526723742485 -1769682124,510793216,0.0,0.0,0.0,1.0,-0.0001548157597426325,-0.0006599370390176773,-0.0008557605906389654,0.129877507686615,0.1722303181886673,-0.03037966787815094 -1769682124,552145920,0.0,0.0,0.0,1.0,-0.00016807155043352395,-0.0015897767152637243,-0.0008686442743055522,0.15137207508087158,0.021470069885253906,-0.015112118795514107 -1769682124,573139712,0.0,0.0,0.0,1.0,-0.00027862112619914114,-0.0023298116866499186,-0.0008667287183925509,0.043139807879924774,0.23714493215084076,-0.016760636121034622 -1769682124,604727296,0.0,0.0,0.0,1.0,-0.0002584301691967994,-0.003006717888638377,-0.0008585404139012098,-0.010656431317329407,0.0752900242805481,-0.012398991733789444 -1769682124,650157824,0.0,0.0,0.0,1.0,-0.00025116530014202,-0.0031153797172009945,-0.0008463847916573286,-0.0756211206316948,-0.010798812843859196,0.0045970226638019085 -1769682124,672017664,0.0,0.0,0.0,1.0,-0.000250262237386778,-0.003183088731020689,-0.0008344665402546525,0.06471113860607147,0.08631864190101624,-0.005083922296762466 -1769682124,707794688,0.0,0.0,0.0,1.0,-0.00021083763567730784,-0.0030464131850749254,-0.0008154138340614736,-0.06473219394683838,-0.08629800379276276,0.006282737012952566 -1769682124,749490176,0.0,0.0,0.0,1.0,-0.00021416856907308102,-0.0029747369699180126,-0.0008033888298086822,0.07532582432031631,0.011078765615820885,0.009679281152784824 -1769682124,772829952,0.0,0.0,0.0,1.0,-0.0001787174987839535,-0.0028339698910713196,-0.000783564813900739,0.010672390460968018,-0.07528909295797348,0.012390907853841782 -1769682124,805603328,0.0,0.0,0.0,1.0,-0.00023077434161677957,-0.002671666909009218,-0.0007714158855378628,0.08631757646799088,-0.0645022988319397,0.006562594324350357 -1769682124,847856640,0.0,0.0,0.0,1.0,-7.003339123912156e-05,-0.0025717748794704676,-0.0007626814767718315,-0.07530350238084793,-0.01110717561095953,-0.01085065770894289 -1769682124,883617792,0.0,0.0,0.0,1.0,-0.00025775612448342144,-0.0025692787021398544,-0.0007639700197614729,0.08622553944587708,-0.06440737098455429,0.011314966715872288 -1769682124,905838848,0.0,0.0,0.0,1.0,-0.0002880283282138407,-0.0025823323521763086,-0.000775184715166688,0.02699127048254013,0.08082112669944763,-0.008157440461218357 -1769682124,952316160,0.0,0.0,0.0,1.0,-0.0002499310066923499,-0.002571332035586238,-0.0007948625716380775,-0.037724073976278305,-0.005488147493451834,-0.0018409444019198418 -1769682124,971933696,0.0,0.0,0.0,1.0,-0.00019036603043787181,-0.002532484708353877,-0.0008305423543788493,-0.03781887888908386,-0.005398144945502281,0.0029284260235726833 -1769682125,7853824,0.0,0.0,0.0,1.0,-0.00020995621162001044,-0.00255547184497118,-0.0008946644375100732,0.12431466579437256,-0.05924833193421364,-0.00475867697969079 -1769682125,57958912,0.0,0.0,0.0,1.0,-0.00043525081127882004,-0.002585090696811676,-0.0009556129807606339,-7.037372415652499e-05,6.808571924921125e-05,0.003574940375983715 -1769682125,70828800,0.0,0.0,0.0,1.0,-0.000301326101180166,-0.002623122651129961,-0.0009892022935673594,-0.048565078526735306,0.06993113458156586,-0.007055047899484634 -1769682125,106045952,0.0,0.0,0.0,1.0,-0.0003219286445528269,-0.002588644390925765,-0.0010411250405013561,0.010984298773109913,-0.07555925846099854,-0.0019254949875175953 -1769682125,162515712,0.0,0.0,0.0,1.0,-0.0004091644659638405,-0.0025839589070528746,-0.0010708890622481704,-0.026760613545775414,-0.08103139698505402,-0.0025572767481207848 -1769682125,173944832,0.0,0.0,0.0,1.0,-0.00017021253006532788,-0.0018721063388511539,-0.0011046602157875896,-0.09624745696783066,0.13896915316581726,-0.06055620685219765 -1769682125,207365632,0.0,0.0,0.0,1.0,-0.00012688389688264579,-0.0006762992707081139,-0.00110942916944623,-0.03687087073922157,-0.00633567851036787,-0.04590906202793121 -1769682125,252471296,0.0,0.0,0.0,1.0,-0.00026455754414200783,5.085503289592452e-07,-0.0011084962170571089,0.03843797370791435,0.004797694273293018,-0.03512372821569443 -1769682125,271886336,0.0,0.0,0.0,1.0,-0.00028611955349333584,0.0004460980126168579,-0.0011025313287973404,0.011481367982923985,-0.07603242993354797,-0.02695491909980774 -1769682125,305239040,0.0,0.0,0.0,1.0,-6.011050572851673e-05,0.0006764566642232239,-0.0010933845769613981,0.027138130739331245,0.08065174520015717,-0.017700809985399246 -1769682125,350075648,0.0,0.0,0.0,1.0,-0.0001469613634981215,0.0007600686512887478,-0.001092275488190353,0.011095511727035046,-0.07564688473939896,-0.006696708034723997 -1769682125,372334848,0.0,0.0,0.0,1.0,-0.00021079361613374203,0.0006933717522770166,-0.0011011805618181825,-9.255836630472913e-05,9.044804755831137e-05,0.004766617901623249 -1769682125,404889856,0.0,0.0,0.0,1.0,-0.00019652652554214,0.0005484838038682938,-0.00111687695607543,0.010684611275792122,-0.07523908466100693,0.014752800576388836 -1769682125,452325632,0.0,0.0,0.0,1.0,-0.0001669377088546753,0.0003942285547964275,-0.001148455892689526,-0.03783809393644333,-0.005394588690251112,0.004136187024414539 -1769682125,473708800,0.0,0.0,0.0,1.0,-0.0002516937965992838,-0.0005945878219790757,-0.0011649454245343804,0.07565256208181381,0.010814479552209377,-0.0070812031626701355 -1769682125,505076992,0.0,0.0,0.0,1.0,-0.0002679795725271106,-0.0015488736098632216,-0.0012029993813484907,-0.0484851635992527,0.06979523599147797,-0.012995749711990356 -1769682125,565016832,0.0,0.0,0.0,1.0,-0.00018597234156914055,-0.0020761743653565645,-0.0012239668285474181,0.02681662328541279,0.08095299452543259,-0.002206664765253663 -1769682125,574283264,0.0,0.0,0.0,1.0,-0.00023851000878494233,-0.0023787720128893852,-0.0012489946093410254,0.000137850089231506,-0.00013532726734410971,-0.007149952929466963 -1769682125,607272704,0.0,0.0,0.0,1.0,-0.0002146035258192569,-0.0024660294875502586,-0.0012844728771597147,0.026626253500580788,0.08113573491573334,0.007323680445551872 -1769682125,653944832,0.0,0.0,0.0,1.0,-0.0004004434449598193,-0.002500904956832528,-0.0013073571026325226,-0.02671472355723381,-0.08104658126831055,-0.002555747050791979 -1769682125,671280128,0.0,0.0,0.0,1.0,-0.00015965377679094672,-0.002440888434648514,-0.001330269267782569,0.08627092093229294,-0.06431270390748978,0.012397698126733303 -1769682125,708405504,0.0,0.0,0.0,1.0,-0.000274992868071422,-0.002299385378137231,-0.001359456917271018,-0.059590552002191544,0.14537972211837769,-0.0086445901542902 -1769682125,760570368,0.0,0.0,0.0,1.0,-0.00011914490460185334,-0.0022300402633845806,-0.0013845328940078616,-0.037788599729537964,-0.005454326514154673,0.0017747636884450912 -1769682125,772547328,0.0,0.0,0.0,1.0,-0.000190457227290608,-0.0020779550541192293,-0.0014047132572159171,-0.03785550594329834,-0.005388460587710142,0.0053521920926868916 -1769682125,805271552,0.0,0.0,0.0,1.0,-5.4986332543194294e-05,-0.0020286848302930593,-0.0014255783753469586,-0.08653273433446884,0.06454361230134964,0.000739178853109479 -1769682125,868014592,0.0,0.0,0.0,1.0,-0.00017614112584851682,-0.001977444626390934,-0.0014358785701915622,-0.010916044004261494,0.07541437447071075,-0.0052034854888916016 -1769682125,878562816,0.0,0.0,0.0,1.0,-0.00017413355817552656,-0.0019822942558676004,-0.001441134954802692,-0.04857488349080086,0.06981709599494934,-0.010566680692136288 -1769682125,906842880,0.0,0.0,0.0,1.0,-6.678790668956935e-05,-0.0020389046985656023,-0.0014366324758157134,-0.08656395971775055,0.06455360352993011,0.0019493766594678164 -1769682125,948020992,0.0,0.0,0.0,1.0,-8.906625589588657e-05,-0.0019880742765963078,-0.0014322376810014248,0.011104057542979717,-0.07559248059988022,-0.004333393648266792 -1769682125,978262528,0.0,0.0,0.0,1.0,-0.00011826175614260137,-0.001980400178581476,-0.0014153668889775872,-0.0864386186003685,0.0644102692604065,-0.005188049282878637 -1769682126,6418688,0.0,0.0,0.0,1.0,-0.00025711397756822407,-0.0019411110552027822,-0.0014012842439115047,0.011001689359545708,-0.07547915726900101,0.0016228151507675648 -1769682126,54949632,0.0,0.0,0.0,1.0,-0.0001706941402517259,-0.0020218873396515846,-0.0013848680537194014,0.04865943267941475,-0.06987359374761581,0.006974611431360245 -1769682126,71228928,0.0,0.0,0.0,1.0,-0.00019206431170459837,-0.001968367723748088,-0.0013789955992251635,0.01122527476400137,-0.07570250332355499,-0.010295933112502098 -1769682126,109978112,0.0,0.0,0.0,1.0,-0.0002009673771681264,-0.0016644110437482595,-0.0013870159164071083,0.0763472467660904,0.010141432285308838,-0.046505510807037354 -1769682126,148706304,0.0,0.0,0.0,1.0,-3.0443639843724668e-05,-0.0008981400751508772,-0.0013929179403930902,-0.04797963798046112,0.06914989650249481,-0.045099250972270966 -1769682126,173530368,0.0,0.0,0.0,1.0,-0.00010902370559051633,-0.0003279638185631484,-0.0014102575369179249,-0.021498560905456543,0.15039344131946564,-0.03302876278758049 -1769682126,205193984,0.0,0.0,0.0,1.0,-2.621379098854959e-05,0.00019470491679385304,-0.0014284186763688922,0.04906552657485008,-0.07026536762714386,-0.01448629517108202 -1769682126,255370496,0.0,0.0,0.0,1.0,-0.00021034352539572865,0.0004015372833237052,-0.0014537014067173004,-0.015406826511025429,-0.15676835179328918,-0.012836025096476078 -1769682126,272190208,0.0,0.0,0.0,1.0,-0.00024740758817642927,0.000472316489322111,-0.0014814558671787381,0.037912726402282715,0.005348550621420145,-0.008953269571065903 -1769682126,305806336,0.0,0.0,0.0,1.0,-0.00014481401012744755,0.00044741720193997025,-0.0015302064130082726,0.022090064361691475,-0.1509714275598526,0.002043056068941951 -1769682126,347817472,0.0,0.0,0.0,1.0,-0.000215077685425058,0.00033424608409404755,-0.0015936926938593388,-0.011081029660999775,0.07551874220371246,0.0007664670702069998 -1769682126,376873984,0.0,0.0,0.0,1.0,-0.0002622444008011371,0.00015662256919313222,-0.001693523838184774,0.05326254293322563,0.16214905679225922,0.005080784671008587 -1769682126,406652416,0.0,0.0,0.0,1.0,-0.0002226777869509533,-0.0004307276103645563,-0.0017711372347548604,0.04898013919591904,-0.07013770937919617,-0.008527816273272038 -1769682126,453689600,0.0,0.0,0.0,1.0,-0.00021696531621273607,-0.0010329252108931541,-0.0018433500081300735,0.015701519325375557,0.15641549229621887,-0.006224098149687052 -1769682126,472549120,0.0,0.0,0.0,1.0,-0.00028176719206385314,-0.0014494635397568345,-0.0019062993815168738,0.011141453869640827,-0.07556083053350449,-0.0031529159750789404 -1769682126,508629248,0.0,0.0,0.0,1.0,-0.00020015519112348557,-0.0017611992079764605,-0.0019493360305204988,-0.022057777270674706,0.15087443590164185,-0.006800154224038124 -1769682126,554710528,0.0,0.0,0.0,1.0,-7.102279778337106e-05,-0.00187493150588125,-0.0019640768878161907,0.0,-0.0,0.0 -1769682126,573568000,0.0,0.0,0.0,1.0,-2.4819159079925157e-05,-0.0018427218310534954,-0.0019484834047034383,0.010942026972770691,-0.07533558458089828,0.00876098033040762 -1769682126,606455552,0.0,0.0,0.0,1.0,-5.637496360577643e-05,-0.0017284577479586005,-0.0018933572573587298,0.07528197020292282,0.011301795020699501,0.011864906176924706 -1769682126,660505344,0.0,0.0,0.0,1.0,2.2051328414818272e-05,-0.001660871203057468,-0.0018448607297614217,-0.059812359511852264,0.14529404044151306,-0.008553028106689453 -1769682126,677649152,0.0,0.0,0.0,1.0,-0.00010341891902498901,-0.0015489753568544984,-0.0017614312237128615,-0.11329279839992523,-0.01657690480351448,0.0030703574884682894 -1769682126,705066240,0.0,0.0,0.0,1.0,-9.589782712282613e-05,-0.0014893452171236277,-0.0017024698900058866,-4.217523382976651e-05,4.45905898232013e-05,0.0023833971936255693 -1769682126,751187456,0.0,0.0,0.0,1.0,-0.00010513590677874163,-0.001437360537238419,-0.0016593176405876875,0.07555527240037918,0.011029225774109364,-0.003642556257545948 -1769682126,776412416,0.0,0.0,0.0,1.0,-4.452027496881783e-05,-0.0014605369651690125,-0.0016116214683279395,0.08646432310342789,-0.0642305314540863,0.008685300126671791 -1769682126,808542208,0.0,0.0,0.0,1.0,-0.00017996082897298038,-0.001386202871799469,-0.0015924430917948484,-0.026548918336629868,-0.08111738413572311,-0.003718981519341469 -1769682126,848169984,0.0,0.0,0.0,1.0,-0.0001308865030296147,-0.0013909153640270233,-0.0015833054203540087,0.0,-0.0,0.0 -1769682126,871336704,0.0,0.0,0.0,1.0,-0.0001607779850019142,-0.001433842466212809,-0.001576347858645022,0.03763040900230408,0.005678440444171429,0.006513721309602261 -1769682126,908286976,0.0,0.0,0.0,1.0,-0.00018167556845583022,-0.0014573734952136874,-0.0015635467134416103,-4.150684253545478e-05,4.4543434341903776e-05,0.0023834097664803267 -1769682126,945145856,0.0,0.0,0.0,1.0,-0.00013603086699731648,-0.001515635522082448,-0.0015435406239703298,0.022238608449697495,-0.1509246975183487,0.003205825574696064 -1769682126,971371776,0.0,0.0,0.0,1.0,-0.00013530639989767224,-0.0014948609750717878,-0.001535424729809165,-0.03777502477169037,-0.0055283852852880955,0.001833674730733037 -1769682127,4908288,0.0,0.0,0.0,1.0,-0.00022478794562630355,-0.0014693762641400099,-0.0015165002550929785,-0.06419642269611359,-0.0867675244808197,-0.007835648953914642 -1769682127,53456896,0.0,0.0,0.0,1.0,-0.00011146236647618935,-0.0015058241551741958,-0.0015187675599008799,0.01104776468127966,-0.07537183910608292,0.006367427762597799 -1769682127,72970496,0.0,0.0,0.0,1.0,-0.00011787028779508546,-0.0009354667272418737,-0.0015396213857457042,0.0004917247570119798,-0.0005338392220437527,-0.028601041063666344 -1769682127,105736448,0.0,0.0,0.0,1.0,-0.0002019731909967959,-0.0002643005282152444,-0.0015825355658307672,-0.010769744403660297,0.0750594213604927,-0.023049987852573395 -1769682127,148875008,0.0,0.0,0.0,1.0,-8.560599235352129e-05,7.634670328116044e-05,-0.0016242294805124402,-0.07089164853096008,0.2205055058002472,-0.020833181217312813 -1769682127,179725568,0.0,0.0,0.0,1.0,-0.0001710707147140056,0.000359238067176193,-0.001681979396380484,0.022498393431305885,-0.15113897621631622,-0.008719767443835735 -1769682127,205750528,0.0,0.0,0.0,1.0,-2.1804007701575756e-05,0.0004075807810295373,-0.0017153301741927862,-0.03760869428515434,-0.005720573477447033,-0.007695043925195932 -1769682127,254395648,0.0,0.0,0.0,1.0,-3.914565604645759e-05,0.0003713360638357699,-0.0017374346498399973,0.02651529759168625,0.08111310750246048,0.0025219512172043324 -1769682127,272672256,0.0,0.0,0.0,1.0,9.884827886708081e-05,0.00033224403159692883,-0.0017394657479599118,-0.07554426044225693,-0.011093556880950928,0.0036754717584699392 -1769682127,306609152,0.0,0.0,0.0,1.0,-9.881405276246369e-07,0.00015118489682208747,-0.0017062061233446002,0.0641334056854248,0.08682117611169815,0.009027068503201008 -1769682127,355213824,0.0,0.0,0.0,1.0,3.205534449080005e-05,-2.3694867195445113e-05,-0.0016677477397024632,0.048712972551584244,-0.06965971738100052,0.012870344333350658 -1769682127,372339968,0.0,0.0,0.0,1.0,0.0001086972260964103,-0.00039700785418972373,-0.001604770659469068,0.037730131298303604,0.005597549024969339,0.0005458340747281909 -1769682127,405731072,0.0,0.0,0.0,1.0,0.00014116166858002543,-0.0006696117925457656,-0.0015136564616113901,-0.00010255005327053368,0.00011107228783657774,0.005958551540970802 -1769682127,454409472,0.0,0.0,0.0,1.0,-9.273084287997335e-05,-0.0008173657115548849,-0.0014572805957868695,0.02659129723906517,0.08101070672273636,-0.0034379782155156136 -1769682127,472937216,0.0,0.0,0.0,1.0,-6.160551492939703e-06,-0.00091409997548908,-0.0014053715858608484,-0.04891183227300644,0.06984994560480118,-0.0021415231749415398 -1769682127,505891328,0.0,0.0,0.0,1.0,-0.00015234762395266443,-0.0009754029451869428,-0.0013611973263323307,-0.015396464616060257,-0.1564657837152481,0.005037877708673477 -1769682127,553967360,0.0,0.0,0.0,1.0,-6.219168426468968e-05,-0.0009577631135471165,-0.0013459965121001005,-0.02666129730641842,-0.08092553168535233,0.008207360282540321 -1769682127,581316352,0.0,0.0,0.0,1.0,-0.00017422871314920485,-0.0009299041121266782,-0.0013475508894771338,-0.048719145357608795,0.06962057203054428,-0.01405335869640112 -1769682127,607460608,0.0,0.0,0.0,1.0,-0.00013386335922405124,-0.0008674134151078761,-0.0013629202730953693,-0.04882385954260826,0.06972964853048325,-0.008093303069472313 -1769682127,649123584,0.0,0.0,0.0,1.0,-0.0001076871485565789,-0.0007978564244695008,-0.0013883394422009587,-0.07557790726423264,-0.011090591549873352,0.00607557687908411 -1769682127,671356672,0.0,0.0,0.0,1.0,-0.0001505094114691019,-0.0007360024028457701,-0.0014133290387690067,-0.07551655173301697,-0.011160371825098991,0.002502134069800377 -1769682127,708547072,0.0,0.0,0.0,1.0,-0.00014187982014846057,-0.0006557918386533856,-0.0014392668381333351,0.037747811526060104,0.005593442358076572,-0.0006562083726748824 -1769682127,748354816,0.0,0.0,0.0,1.0,-1.2636861356440932e-05,-0.0006388730835169554,-0.0014576490502804518,-0.08674658834934235,0.06430314481258392,0.002102842088788748 -1769682127,773103360,0.0,0.0,0.0,1.0,-5.504737055161968e-05,-0.0005877182120457292,-0.0014727399684488773,-0.04880032688379288,0.0696742981672287,-0.010470068082213402 -1769682127,805035520,0.0,0.0,0.0,1.0,-4.8481771955266595e-05,-0.0005754673038609326,-0.0014995496021583676,0.01138016302138567,-0.07562517374753952,-0.007940252311527729 -1769682127,867000576,0.0,0.0,0.0,1.0,-4.8999296268448234e-05,-0.0006096625002101064,-0.0015242267400026321,0.011223578825592995,-0.07544711977243423,0.001592978835105896 -1769682127,874965248,0.0,0.0,0.0,1.0,1.1821766747743823e-05,-0.0006010840879753232,-0.0015448746271431446,0.04899352416396141,-0.06986573338508606,-0.0002589948708191514 -1769682127,906221056,0.0,0.0,0.0,1.0,4.018581239506602e-05,-0.0005688188830390573,-0.0015627703396603465,0.026635920628905296,0.08091792464256287,-0.009403068572282791 -1769682127,948387840,0.0,0.0,0.0,1.0,-1.3297973055159673e-05,-0.0006165870581753552,-0.0015636582393199205,-0.03790630027651787,-0.005429305136203766,0.010194927453994751 -1769682127,983342336,0.0,0.0,0.0,1.0,-6.219315764610656e-06,-0.0006049976800568402,-0.0015503307804465294,0.022275034338235855,-0.15066847205162048,0.015100927092134953 -1769682128,7412224,0.0,0.0,0.0,1.0,4.031717253383249e-06,-0.0003658825298771262,-0.0015212581492960453,0.037965405732393265,0.005366917233914137,-0.013771502301096916 -1769682128,50231808,0.0,0.0,0.0,1.0,0.00018626140081323683,-0.00015441171126440167,-0.0014875122578814626,-0.06408383697271347,-0.08684580773115158,-0.006616335827857256 -1769682128,71814400,0.0,0.0,0.0,1.0,6.9950983743183315e-06,2.9129285394446924e-05,-0.0014556603273376822,0.026555560529232025,0.08099085837602615,-0.005829914472997189 -1769682128,105555200,0.0,0.0,0.0,1.0,-1.7003876564558595e-06,0.00011413318861741573,-0.0014187665656208992,0.011253450065851212,-0.07544269412755966,0.0015921912854537368 -1769682128,152706048,0.0,0.0,0.0,1.0,-2.9156970413168892e-05,0.00023096826043911278,-0.0014025737764313817,-0.011137489229440689,0.07530906796455383,-0.008742669597268105 -1769682128,172002304,0.0,0.0,0.0,1.0,-3.6024834116688e-05,0.00023891888849902898,-0.0014059575041756034,4.007538882433437e-05,-4.432740752235986e-05,-0.0023834386374801397 -1769682128,205656832,0.0,0.0,0.0,1.0,-1.63746444741264e-05,0.00023084282292984426,-0.0014422681415453553,0.06007121503353119,-0.14503908157348633,0.014440066181123257 -1769682128,267421952,0.0,0.0,0.0,1.0,-9.798677638173103e-05,0.00012162046186858788,-0.0014835514593869448,-0.03770318627357483,-0.005667482037097216,-0.001721627777442336 -1769682128,275255808,0.0,0.0,0.0,1.0,5.123731170897372e-06,0.000133126275613904,-0.001544324099086225,-0.04919552430510521,0.07001382857561111,0.00979494396597147 -1769682128,307961600,0.0,0.0,0.0,1.0,1.5821829947526567e-05,0.00017400519573129714,-0.001596026006154716,0.06400913745164871,0.08691538870334625,0.00900251604616642 -1769682128,352194560,0.0,0.0,0.0,1.0,-9.744089766172692e-05,0.00021249889687169343,-0.0016380640445277095,0.0980432853102684,-0.13961949944496155,0.0018611557316035032 -1769682128,373667840,0.0,0.0,0.0,1.0,-5.833179602632299e-05,0.00022139083012007177,-0.0016728827031329274,-0.04896485060453415,0.0697408989071846,-0.004505886230617762 -1769682128,409361408,0.0,0.0,0.0,1.0,-3.42764105880633e-05,0.0001943149691214785,-0.0017089804168790579,-0.04907004162669182,0.06984826922416687,0.0014524287544190884 -1769682128,447949568,0.0,0.0,0.0,1.0,-5.194060577196069e-06,0.0002543776645325124,-0.0017271266551688313,0.00020109745673835278,-0.0002213587868027389,-0.011917279101908207 -1769682128,471462656,0.0,0.0,0.0,1.0,-1.991119461308699e-05,0.00021906106849201024,-0.001739697763696313,0.011376341804862022,-0.07552489638328552,-0.0031751336064189672 -1769682128,507758336,0.0,0.0,0.0,1.0,6.731403118465096e-05,0.00018711399752646685,-0.0017362928483635187,0.03768042474985123,0.005706482101231813,0.0029154084622859955 -1769682128,554980352,0.0,0.0,0.0,1.0,-2.002808469114825e-05,0.00020418960775714368,-0.0017318439204245806,-0.048924706876277924,0.06966011226177216,-0.008083109743893147 -1769682128,572884480,0.0,0.0,0.0,1.0,2.5906389055307955e-05,0.00018553023983258754,-0.0017179076094180346,0.011288758367300034,-0.07541225105524063,0.0027841099072247744 -1769682128,605774080,0.0,0.0,0.0,1.0,8.594294195063412e-05,0.0001770123199094087,-0.0016920572379603982,-4.030796844745055e-05,4.428512693266384e-05,0.0023834353778511286 -1769682128,650366464,0.0,0.0,0.0,1.0,0.00018139142775908113,0.0001640849222894758,-0.001671212026849389,-0.026341119781136513,-0.08117005974054337,-0.002514803782105446 -1769682128,673097984,0.0,0.0,0.0,1.0,0.00013701256830245256,0.00011767518299166113,-0.001639948575757444,-0.04887932911515236,0.06958284229040146,-0.011660141870379448 -1769682128,708559872,0.0,0.0,0.0,1.0,6.649376882705837e-05,0.00016406908980570734,-0.0015946169150993228,-0.03777928650379181,-0.005608445964753628,0.003042066004127264 -1769682128,749796864,0.0,0.0,0.0,1.0,9.488752402830869e-05,0.00018274695321451873,-0.0015740359667688608,-0.011329962871968746,0.07543119788169861,-0.0015941438032314181 -1769682128,771860224,0.0,0.0,0.0,1.0,3.355894659762271e-05,0.00015352439368143678,-0.0015460483264178038,0.026364557445049286,0.08113126456737518,0.00013081880751997232 -1769682128,805732608,0.0,0.0,0.0,1.0,0.0001230298075824976,0.00016156895435415208,-0.001523378537967801,-0.037596676498651505,-0.005813713185489178,-0.007683958858251572 -1769682128,849983488,0.0,0.0,0.0,1.0,4.2174528061877936e-05,0.0001884096855064854,-0.0015225232345983386,0.02651752345263958,0.08095680922269821,-0.009402976371347904 -1769682128,872113408,0.0,0.0,0.0,1.0,1.5895844626356848e-05,0.00016894296277314425,-0.0015261337393894792,-0.03773755952715874,-0.005662052426487207,0.0006576595478691161 -1769682128,906299648,0.0,0.0,0.0,1.0,4.8364337999373674e-05,0.00023271137615665793,-0.001563602825626731,0.0113294068723917,-0.07540605217218399,0.002786817029118538 -1769682128,953310208,0.0,0.0,0.0,1.0,-2.270598452014383e-05,0.00023057784710545093,-0.0016072823200374842,-0.00012140748731326312,0.00013294367818161845,0.00715038925409317 -1769682128,973181696,0.0,0.0,0.0,1.0,-6.29117275821045e-05,0.000121322475024499,-0.0016571343876421452,-0.00010120664956048131,0.00011076463852077723,0.005958579480648041 -1769682129,9169152,0.0,0.0,0.0,1.0,-0.00012768358283210546,5.856535426573828e-05,-0.0017105996375903487,-0.0264350026845932,-0.08103051781654358,0.005826716776937246 -1769682129,68503552,0.0,0.0,0.0,1.0,-3.191032010363415e-05,1.8051197912427597e-05,-0.0017423998797312379,0.04908169433474541,-0.06973104178905487,0.0021298392675817013 -1769682129,77847296,0.0,0.0,0.0,1.0,1.332340525550535e-05,-3.0401824915315956e-05,-0.0017608848866075277,0.037816595286130905,0.005586642771959305,-0.005423592869192362 -1769682129,106179072,0.0,0.0,0.0,1.0,2.0467945432756096e-05,-4.374987111077644e-05,-0.0017577281687408686,0.03771504759788513,0.0056993598118424416,0.0005349512211978436 -1769682129,149028096,0.0,0.0,0.0,1.0,1.3437640518532135e-05,-4.029043338960037e-06,-0.0017403245437890291,-0.00010124897380592301,0.00011073875066358596,0.005958579480648041 -1769682129,173148160,0.0,0.0,0.0,1.0,0.00011176894622622058,-5.014115959056653e-05,-0.0017108262982219458,-0.022887663915753365,0.15097925066947937,0.0039594462141394615 -1769682129,208470016,0.0,0.0,0.0,1.0,0.00022230682952795178,-8.719321158423554e-06,-0.001660339767113328,-0.01136790681630373,0.07540023326873779,-0.002787642879411578 -1769682129,248468480,0.0,0.0,0.0,1.0,0.0001228185137733817,0.00039201119216158986,-0.0016108202980831265,-0.03793656826019287,-0.005464504472911358,0.012573817744851112 -1769682129,271870976,0.0,0.0,0.0,1.0,0.00028200983069837093,0.0006444698083214462,-0.001583579578436911,-0.08698465675115585,0.06417962908744812,0.006866006646305323 -1769682129,306362624,0.0,0.0,0.0,1.0,0.00016395849524997175,0.0008785377140156925,-0.0015293981414288282,-4.0631894080433995e-05,4.435069058672525e-05,0.0023834286257624626 -1769682129,372595456,0.0,0.0,0.0,1.0,0.00023012535530142486,0.0010061373468488455,-0.0014943554997444153,-0.022806834429502487,0.15084005892276764,-0.003196961944922805 -1769682129,378826496,0.0,0.0,0.0,1.0,0.00021021973225288093,0.0011051301844418049,-0.0014508644817396998,-0.05252782627940178,-0.16235895454883575,-0.002646752167493105 -1769682129,404849408,0.0,0.0,0.0,1.0,0.00017446067067794502,0.0011729042744264007,-0.0014292061096057296,0.04908231273293495,-0.0696570947766304,0.0045241485349833965 -1769682129,449946880,0.0,0.0,0.0,1.0,0.00011441813694545999,0.0011170983780175447,-0.0014039394445717335,0.026461781933903694,0.08095978945493698,-0.010592611506581306 -1769682129,476844544,0.0,0.0,0.0,1.0,0.00015805818838998675,0.0010501521173864603,-0.0013770870864391327,-0.03771163523197174,-0.0057210722006857395,-0.000543461472261697 -1769682129,507228416,0.0,0.0,0.0,1.0,4.6928777010180056e-05,0.001008890918456018,-0.0013613152550533414,-0.049173805862665176,0.06973904371261597,0.00023663206957280636 -1769682129,548747776,0.0,0.0,0.0,1.0,0.00011221211752854288,0.0010016027372330427,-0.0013404694618657231,-0.022745463997125626,0.15072254836559296,-0.009164033457636833 -1769682129,571443200,0.0,0.0,0.0,1.0,7.751956582069397e-05,0.0009260271908715367,-0.0013243096182122827,-0.02634560689330101,-0.08107535541057587,0.004631809890270233 -1769682129,607863552,0.0,0.0,0.0,1.0,7.826832006685436e-05,0.000890907715074718,-0.0013123955577611923,0.00010346343333367258,-0.00011105919838882983,-0.005958535708487034 -1769682129,660630528,0.0,0.0,0.0,1.0,6.903217581566423e-05,0.0009055892005562782,-0.0013063607038930058,0.026400620117783546,0.081011101603508,-0.008205778896808624 -1769682129,671787520,0.0,0.0,0.0,1.0,5.759164196206257e-05,0.0009055426344275475,-0.001308843377046287,0.026314621791243553,0.08110098540782928,-0.0034384692553430796 -1769682129,706416640,0.0,0.0,0.0,1.0,4.714047827292234e-05,0.0008557525579817593,-0.0013322466984391212,0.00014560887939296663,-0.00015552421973552555,-0.008341935463249683 -1769682129,754501376,0.0,0.0,0.0,1.0,2.4342569304280914e-05,0.0009104216005653143,-0.0013525837566703558,-2.0834277165704407e-05,2.2220243408810347e-05,0.0011917045339941978 -1769682129,773877504,0.0,0.0,0.0,1.0,-6.269041477935389e-06,0.0008672188268974423,-0.0013687952887266874,0.037792742252349854,0.005646793637424707,-0.004213453736156225 -1769682129,806055168,0.0,0.0,0.0,1.0,0.00023872364545240998,0.0008842721581459045,-0.0013718532864004374,0.011471960693597794,-0.0754348486661911,0.00041555752977728844 -1769682129,849377792,0.0,0.0,0.0,1.0,0.00014834225294180214,0.0008902703411877155,-0.0013608136214315891,-0.022908197715878487,0.15082430839538574,-0.0032155970111489296 -1769682129,875398656,0.0,0.0,0.0,1.0,7.024556543910876e-05,0.0008422050159424543,-0.0013209307799115777,-0.02310502529144287,0.15102314949035645,0.007508147973567247 -1769682129,906379264,0.0,0.0,0.0,1.0,0.00019067707762587816,0.0004717277188319713,-0.001267065410502255,0.026079099625349045,0.0813317522406578,0.008481936529278755 -1769682129,952313088,0.0,0.0,0.0,1.0,0.00011527699825819582,0.0001970928133232519,-0.0012006836477667093,-0.011800039559602737,0.07576654106378555,0.017457451671361923 -1769682129,973698304,0.0,0.0,0.0,1.0,0.00035708333598449826,-9.707026038086042e-05,-0.0010870159603655338,0.06380103528499603,0.08705763518810272,0.00784726720303297 -1769682130,8850688,0.0,0.0,0.0,1.0,0.00021423297584988177,-0.00018209198606200516,-0.0009959365706890821,-0.026448186486959457,-0.08093418180942535,0.01297029573470354 -1769682130,48732928,0.0,0.0,0.0,1.0,0.00028350326465442777,-0.00024933842360042036,-0.0009085106430575252,-0.014806164428591728,-0.15652240812778473,0.0050488184206187725 -1769682130,72746496,0.0,0.0,0.0,1.0,0.0002445043355692178,-0.00027186068473383784,-0.0008343446534126997,8.399663056479767e-05,-8.910580072551966e-05,-0.004766801837831736 -1769682130,105718016,0.0,0.0,0.0,1.0,4.6468183427350596e-05,-0.00022163597168400884,-0.0007539288490079343,2.0988158212276176e-05,-2.2282360077952035e-05,-0.0011917005758732557 -1769682130,170824960,0.0,0.0,0.0,1.0,0.000168761340319179,-0.00017930618196260184,-0.00069975241785869,0.011603438295423985,-0.07554222643375397,-0.005537677556276321 -1769682130,179972864,0.0,0.0,0.0,1.0,3.7469391827471554e-05,0.00033192604314535856,-0.0006655670586042106,-0.03789558634161949,-0.00555146811529994,0.010168945416808128 -1769682130,206369280,0.0,0.0,0.0,1.0,8.477806113660336e-05,0.0009867498883977532,-0.0006611880380660295,-0.06073172762989998,0.14512991905212402,-0.00020842329831793904 -1769682130,248521472,0.0,0.0,0.0,1.0,-2.443383345962502e-05,0.0014724290231242776,-0.0006657936028204858,-0.11320362240076065,-0.017171604558825493,0.003090804908424616 -1769682130,278109952,0.0,0.0,0.0,1.0,2.6177400286542252e-05,0.0018532524118199944,-0.0006807985482737422,-0.026412146165966988,-0.08096130937337875,0.011778763495385647 -1769682130,307334912,0.0,0.0,0.0,1.0,5.81387103011366e-05,0.0020212724339216948,-0.0006895172991789877,0.02297172322869301,-0.15081430971622467,0.003231203183531761 -1769682130,349436672,0.0,0.0,0.0,1.0,0.00013331366062629968,0.0020188128110021353,-0.0007007128442637622,-0.04902302846312523,0.0694722831249237,-0.011715883389115334 -1769682130,371943424,0.0,0.0,0.0,1.0,0.00010703867155825719,0.0020007574930787086,-0.0007007785607129335,0.00012814727961085737,-0.00013385072816163301,-0.007150161080062389 -1769682130,411387136,0.0,0.0,0.0,1.0,0.0001852664427133277,0.0018883974989876151,-0.0006951509858481586,0.06398474425077438,0.0868554562330246,-0.004052169620990753 -1769682130,450676224,0.0,0.0,0.0,1.0,0.00018435427045915276,0.0018048655474558473,-0.0006833905354142189,-0.026299238204956055,-0.08107561618089676,0.0058136917650699615 -1769682130,472628992,0.0,0.0,0.0,1.0,5.4872572945896536e-05,0.0017654087860137224,-0.0006782484124414623,-0.07538903504610062,-0.011541496030986309,-0.0023415847681462765 -1769682130,506315520,0.0,0.0,0.0,1.0,0.00018998044834006578,0.001685380470007658,-0.0006563735660165548,0.08688417822122574,-0.06386201828718185,0.003968925215303898 -1769682130,556299008,0.0,0.0,0.0,1.0,0.00022486227680929005,0.0016582104144617915,-0.0006400401471182704,0.026316599920392036,0.0810549184679985,-0.00700230710208416 -1769682130,573087488,0.0,0.0,0.0,1.0,0.000207938501262106,0.0015977526782080531,-0.0006268362631089985,0.026097580790519714,0.08127883821725845,0.004915488883852959 -1769682130,606004736,0.0,0.0,0.0,1.0,4.983948383596726e-05,0.0015894972020760179,-0.0006005573668517172,-0.060595519840717316,0.14493483304977417,-0.009792574681341648 -1769682130,651429888,0.0,0.0,0.0,1.0,0.0002506278397049755,0.00163327157497406,-0.0005777395563200116,-0.011413655243813992,0.07531511783599854,-0.006393187213689089 -1769682130,680135680,0.0,0.0,0.0,1.0,0.00012071566743543372,0.0016501086065545678,-0.0005627473583444953,0.023115847259759903,-0.15092042088508606,-0.002703057136386633 -1769682130,705448448,0.0,0.0,0.0,1.0,0.0002459634270053357,0.0016323360614478588,-0.0005450777825899422,0.011393819004297256,-0.07529222220182419,0.007587072905153036 -1769682130,749203200,0.0,0.0,0.0,1.0,0.00015390040061902255,0.0016152929747477174,-0.000534784805495292,-4.4229822378838435e-05,4.4760134187527e-05,0.0023833569139242172 -1769682130,771888128,0.0,0.0,0.0,1.0,5.861672980245203e-05,0.0016612948384135962,-0.0005244782660156488,-0.02608676254749298,-0.08128196746110916,-0.0049211857840418816 -1769682130,806841088,0.0,0.0,0.0,1.0,0.00021355766511987895,0.0016543444944545627,-0.0004917657352052629,0.0262850821018219,0.08108098804950714,-0.005802917294204235 -1769682130,848870912,0.0,0.0,0.0,1.0,0.0001310785737587139,0.001281039323657751,-0.0004646692832466215,0.0108841797336936,-0.07477619498968124,0.03499945253133774 -1769682130,872473088,0.0,0.0,0.0,1.0,0.00012302192044444382,0.0006236053886823356,-0.0004300143918953836,0.025345122441649437,0.08202255517244339,0.04424864798784256 -1769682130,905477888,0.0,0.0,0.0,1.0,6.129438406787813e-05,2.6821122446563095e-05,-0.00038130831671878695,0.04876750707626343,-0.06918607652187347,0.02606569603085518 -1769682130,950472192,0.0,0.0,0.0,1.0,0.00012299083755351603,-0.00027619083994068205,-0.0003318164381198585,-0.049528200179338455,0.06994727998971939,0.014451156370341778 -1769682130,972484608,0.0,0.0,0.0,1.0,0.00013073396985419095,-0.00038470953586511314,-0.0003060447925236076,0.04926055669784546,-0.06967801600694656,-0.00015123008051887155 -1769682131,6371840,0.0,0.0,0.0,1.0,1.4126879250397906e-05,-0.00038340932223945856,-0.0002655418938957155,-2.2312315195449628e-05,2.24200794036733e-05,0.0011916740331798792 -1769682131,50773248,0.0,0.0,0.0,1.0,0.00011487884330563247,-0.0003682738752104342,-0.00023889711883384734,0.0001560909004183486,-0.00015697695198468864,-0.008341718465089798 -1769682131,73175040,0.0,0.0,0.0,1.0,3.1503054742643144e-06,-0.0002627887006383389,-0.0002183240867452696,-0.03754729777574539,-0.005927463062107563,-0.008938257582485676 -1769682131,107220736,0.0,0.0,0.0,1.0,0.00018623184587340802,-4.186328442301601e-05,-0.00019640197569970042,0.037747822701931,0.005725913215428591,-0.0017871075542643666 -1769682131,158266368,0.0,0.0,0.0,1.0,0.00011469117453088984,0.000795123225543648,-0.00018743763212114573,0.02276337519288063,-0.15053518116474152,0.017570510506629944 -1769682131,173870848,0.0,0.0,0.0,1.0,0.00015658076154068112,0.001476125093176961,-0.00017859571380540729,-0.011917968280613422,0.07580608874559402,0.01981423795223236 -1769682131,209767424,0.0,0.0,0.0,1.0,9.657073678681627e-05,0.0020231169182807207,-0.00015963075566105545,0.026029877364635468,0.08133066445589066,0.0073054940439760685 -1769682135,206176768,0.0,0.0,0.0,1.0,0.00010796443530125543,0.0006270327139645815,0.00014319349429570138,0.0,-0.0,0.0 -1769682135,268644352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682135,278599168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682135,305750016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682135,353288192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682135,373659648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.517884710570797e-05,4.617815648089163e-05,0.0023831031285226345 -1769682135,406767872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682135,463384576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682135,469104640,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,2.7589378078118898e-05,-2.308908005943522e-05,-0.0011915515642613173 -1769682135,508369920,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682135,555499264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-2.7589347155299038e-05,2.308908551640343e-05,0.0011915515642613173 -1769682135,573111552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682135,605796352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.517862882697955e-05,-4.617817103280686e-05,-0.0023831031285226345 -1769682135,652794368,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682135,672740608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.5178570619318634e-05,4.617818194674328e-05,0.0023831031285226345 -1769682135,705798912,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682135,748889088,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-2.7589252567850053e-05,2.3089083697414026e-05,0.0011915515642613173 -1769682135,773230336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682135,808034560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682135,871100928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682135,876546816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.5178345064632595e-05,4.6178163756849244e-05,0.0023831031285226345 -1769682135,906259456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,2.7589145247475244e-05,-2.3089081878424622e-05,-0.0011915515642613173 -1769682135,950782976,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682135,977829632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682136,8216576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682136,51127552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682136,72933888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.517801037058234e-05,-4.6178189222700894e-05,-0.0023831031285226345 -1769682136,106181376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682136,161505280,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682136,173460224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,2.7588914235820994e-05,-2.3089100068318658e-05,-0.0011915515642613173 -1769682136,206231040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-2.7588879675022326e-05,2.3089100068318658e-05,0.0011915515642613173 -1769682136,255074048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.517769022844732e-05,-4.617820741259493e-05,-0.0023831031285226345 -1769682136,273503744,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.517765384865925e-05,-4.617820741259493e-05,-0.0023831031285226345 -1769682136,307613952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.517758472706191e-05,4.6178211050573736e-05,0.0023831031285226345 -1769682136,351697408,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682136,380146176,0.0,0.0,0.0,1.0,-0.003983581438660622,-0.0015931444941088557,-0.00011476226791273803,-0.08732053637504578,0.06426568329334259,0.01582440175116062 -1769682136,407035904,0.0,0.0,0.0,1.0,-0.003801055485382676,-0.011262516491115093,-0.0004280477296561003,-0.10950096696615219,0.06417102366685867,0.1608433723449707 -1769682136,452483072,0.0,0.0,0.0,1.0,-0.0029165290761739016,-0.019499847665429115,-0.0007668595644645393,-0.3155055046081543,0.03140956163406372,0.09966851770877838 -1769682136,472954624,0.0,0.0,0.0,1.0,-0.001950010540895164,-0.02224811539053917,-0.001034882152453065,-0.5666674375534058,-0.08537005633115768,0.04057762026786804 -1769682136,511994880,0.0,0.0,0.0,1.0,-0.0007911009015515447,-0.020171500742435455,-0.0013165404088795185,-0.7391451597213745,0.04122927784919739,-0.025767242535948753 -1769682136,545243904,0.0,0.0,0.0,1.0,0.0001714335521683097,-0.014796840026974678,-0.0015436095418408513,-0.7501024603843689,0.1160726547241211,-0.05433288589119911 -1769682136,572322816,0.0,0.0,0.0,1.0,0.0004817940352950245,-0.011758972890675068,-0.0016444862121716142,-0.7614466547966003,0.19129499793052673,-0.06414518505334854 -1769682136,606430976,0.0,0.0,0.0,1.0,0.0010489663109183311,-0.00605389941483736,-0.0018127358052879572,-0.7685048580169678,0.11263658106327057,-0.07924744486808777 -1769682136,655677696,0.0,0.0,0.0,1.0,0.0013418832095339894,-0.002770002232864499,-0.0019147454295307398,-0.7194535136222839,0.043088797479867935,-0.06972961127758026 -1769682136,674328832,0.0,0.0,0.0,1.0,0.0013761221198365092,-0.00024819886311888695,-0.002007385017350316,-0.6630880236625671,0.05187777429819107,-0.05923731252551079 -1769682136,706199296,0.0,0.0,0.0,1.0,0.001376227824948728,0.001978240441530943,-0.00210975157096982,-0.6747223734855652,0.12733463943004608,-0.054981160908937454 -1769682136,739168768,0.0,0.0,0.0,1.0,0.0012484518811106682,0.0022605464328080416,-0.0021844429429620504,-0.6145681142807007,-0.017168141901493073,-0.021273255348205566 -1769682136,775657216,0.0,0.0,0.0,1.0,0.001017567701637745,0.000788830395322293,-0.002314104000106454,-0.5889781713485718,0.06452392786741257,0.00744234211742878 -1769682136,807176704,0.0,0.0,0.0,1.0,0.0007448052638210356,-0.0003673793689813465,-0.002409970387816429,-0.6340495347976685,-0.019541358575224876,0.010553297586739063 -1769682136,843711488,0.0,0.0,0.0,1.0,0.0006599900661967695,-0.0009925569174811244,-0.0024969272781163454,-0.6036583781242371,-0.09209422767162323,0.012560766190290451 -1769682136,872548352,0.0,0.0,0.0,1.0,0.0004903869703412056,-0.001925224787555635,-0.0026019783690571785,-0.6381906270980835,0.13395828008651733,0.002793530933558941 -1769682136,908998144,0.0,0.0,0.0,1.0,0.00028354726964607835,-0.0029881629161536694,-0.002749799285084009,-0.71369469165802,0.1224023774266243,0.006375427357852459 -1769682136,956275712,0.0,0.0,0.0,1.0,0.00018322055984754115,-0.003701108507812023,-0.002867826260626316,-0.721160352230072,0.04420994222164154,0.01615723967552185 -1769682136,974583040,0.0,0.0,0.0,1.0,4.1672406950965524e-05,-0.004307618830353022,-0.0029950274620205164,-0.716763436794281,-0.10965389758348465,0.013330213725566864 -1769682137,6374400,0.0,0.0,0.0,1.0,-6.229435530258343e-05,-0.004180125426501036,-0.003148820949718356,-0.7772995233535767,0.034942373633384705,-0.00599246472120285 -1769682137,60358144,0.0,0.0,0.0,1.0,-7.535910117439926e-05,-0.003919695969671011,-0.0033057399559766054,-0.7845040559768677,-0.043521638959646225,-0.008075140416622162 -1769682137,68318976,0.0,0.0,0.0,1.0,-5.0949322030646726e-05,-0.0038097198121249676,-0.0033858988899737597,-0.8074991703033447,0.1070232093334198,-0.020887941122055054 -1769682137,107492096,0.0,0.0,0.0,1.0,-5.255891301203519e-05,-0.003977248445153236,-0.0035599772818386555,-0.8529077172279358,0.023258963599801064,0.0038483310490846634 -1769682137,152023808,0.0,0.0,0.0,1.0,-0.00022330251522362232,-0.004023985471576452,-0.00369097082875669,-0.909165620803833,0.014140542596578598,-0.012424214743077755 -1769682137,181085184,0.0,0.0,0.0,1.0,-0.00012445097672753036,-0.0037480820901691914,-0.003848482621833682,-0.9323458075523376,0.16470491886138916,-0.0191861130297184 -1769682137,208863232,0.0,0.0,0.0,1.0,-8.386594709008932e-05,-0.003322738455608487,-0.003957120701670647,-0.8786951303482056,-0.05857395380735397,-0.010237008333206177 -1769682137,252887808,0.0,0.0,0.0,1.0,-0.00010646534792613238,-0.003440727712586522,-0.004082832485437393,-0.9280877709388733,0.010938117280602455,-0.008811533451080322 -1769682137,273435904,0.0,0.0,0.0,1.0,-0.00011006544809788465,-0.003324884455651045,-0.004192446358501911,-0.9585207104682922,0.08321617543697357,-0.014237632043659687 -1769682137,310188032,0.0,0.0,0.0,1.0,-2.4624903744552284e-05,-0.002468372229486704,-0.004310763906687498,-0.9610278010368347,-0.1491578221321106,-0.021639598533511162 -1769682137,352156416,0.0,0.0,0.0,1.0,-3.928314981749281e-05,-0.0022413244005292654,-0.00439868401736021,-0.9281805157661438,0.01063396967947483,-0.0037837326526641846 -1769682137,373305088,0.0,0.0,0.0,1.0,5.833989416714758e-05,-0.0012449747882783413,-0.004450461361557245,-1.0146902799606323,0.0735836774110794,-0.037504203617572784 -1769682137,406407936,0.0,0.0,0.0,1.0,0.000189193116966635,0.0002371571899857372,-0.004495067521929741,-0.9653823971748352,0.00395691953599453,-0.031697794795036316 -1769682137,450761984,0.0,0.0,0.0,1.0,9.356149530503899e-05,0.0007851589471101761,-0.00451604463160038,-0.965639054775238,0.004100808873772621,-0.017416736111044884 -1769682137,473907712,0.0,0.0,0.0,1.0,0.00027839874383062124,0.0023566982708871365,-0.004491198342293501,-0.8970900177955627,-0.06291493028402328,-0.03164035081863403 -1769682137,507447552,0.0,0.0,0.0,1.0,0.00036670485860668123,0.004526521544903517,-0.004412050824612379,-0.8947312831878662,0.1690683662891388,-0.0278521329164505 -1769682137,539924992,0.0,0.0,0.0,1.0,0.00044560752576217055,0.004873557481914759,-0.004346319939941168,-0.8456240296363831,0.09978793561458588,-0.009058443829417229 -1769682137,573205504,0.0,0.0,0.0,1.0,0.00039493030635640025,0.003555918112397194,-0.004299016669392586,-0.8459874391555786,0.10004537552595139,0.009901254437863827 -1769682137,608945152,0.0,0.0,0.0,1.0,0.0002968914923258126,0.001137261395342648,-0.004251035396009684,-0.8459612131118774,0.09985523670911789,0.007448170334100723 -1769682137,639890688,0.0,0.0,0.0,1.0,0.0001878128678072244,-0.0002402140380581841,-0.004200358875095844,-0.8155161738395691,0.02749619260430336,0.017746055498719215 -1769682137,673739264,0.0,0.0,0.0,1.0,0.00015868362970650196,-0.0010531431762501597,-0.0041071888990700245,-0.8647432327270508,0.09656387567520142,0.0024102237075567245 -1769682137,706749184,0.0,0.0,0.0,1.0,0.00018863372679334134,-0.0017284239875152707,-0.00404451135545969,-0.859951376914978,-0.057283416390419006,0.001920357346534729 -1769682137,758165248,0.0,0.0,0.0,1.0,0.00013816298451274633,-0.002024913439527154,-0.003975261468440294,-0.9024695754051208,0.09046368300914764,0.0031101349741220474 -1769682137,772513024,0.0,0.0,0.0,1.0,0.00021389484754763544,-0.0010178163647651672,-0.003867452498525381,-0.9277595281600952,0.008463559672236443,-0.0279336329549551 -1769682137,806862592,0.0,0.0,0.0,1.0,0.00028571367147378623,0.0005394851323217154,-0.0036851223558187485,-0.87828129529953,-0.06108318269252777,-0.02449434995651245 -1769682137,851207168,0.0,0.0,0.0,1.0,0.00028278594254516065,0.0011669276282191277,-0.003506967332214117,-0.8339584469795227,0.023428332060575485,-0.005076766014099121 -1769682137,872945152,0.0,0.0,0.0,1.0,0.0002492508210707456,0.0008100762497633696,-0.0034202635288238525,-0.871726393699646,0.017530813813209534,-0.0009052380919456482 -1769682137,907435776,0.0,0.0,0.0,1.0,0.00023405480897054076,0.0004380708560347557,-0.003245958825573325,-0.8527357578277588,0.020222926512360573,-0.008975177071988583 -1769682137,969116928,0.0,0.0,0.0,1.0,0.00018715739133767784,-4.637853999156505e-05,-0.0031215560156852007,-0.8716422319412231,0.017240630462765694,-0.005694274324923754 -1769682137,979914752,0.0,0.0,0.0,1.0,0.000169770501088351,-0.0003348016180098057,-0.0029581009875983,-0.8953059315681458,0.16776087880134583,-0.012607649900019169 -1769682138,10613248,0.0,0.0,0.0,1.0,0.00020037942158523947,-0.0003546451043803245,-0.002832273952662945,-0.8834283351898193,0.0923142284154892,-0.012115865014493465 -1769682138,57497600,0.0,0.0,0.0,1.0,0.00022909065592102706,-0.00021904753521084785,-0.0026927320286631584,-0.8409332633018494,-0.05538124218583107,-0.003703285939991474 -1769682138,73588992,0.0,0.0,0.0,1.0,0.0002272071287734434,-0.0001957396016223356,-0.0025469984393566847,-0.8715608716011047,0.01682836189866066,-0.010429727844893932 -1769682138,112862720,0.0,0.0,0.0,1.0,0.0002181228919653222,-0.00018285853730048984,-0.0023299166932702065,-0.8528351783752441,0.019838456064462662,-0.004175576381385326 -1769682138,149309952,0.0,0.0,0.0,1.0,0.00023868477728683501,-0.0002253524580737576,-0.002171281957998872,-0.8972771763801575,-0.06468621641397476,-0.012895639054477215 -1769682138,174433024,0.0,0.0,0.0,1.0,0.00022002402693033218,-0.00030263341614045203,-0.0020063493866473436,-0.90934818983078,0.010784287005662918,-0.005031176842749119 -1769682138,208907776,0.0,0.0,0.0,1.0,0.00023212541418615729,-7.745484617771581e-05,-0.0017836976330727339,-0.8972685933113098,-0.0648089349269867,-0.012880783528089523 -1769682138,274003456,0.0,0.0,0.0,1.0,0.00018357340013608336,-3.692875543492846e-05,-0.001625186763703823,-0.878450870513916,-0.0618472620844841,-0.0113991629332304 -1769682138,281123072,0.0,0.0,0.0,1.0,0.00013385276542976499,0.0002514767402317375,-0.0014144995948299766,-0.8595128655433655,-0.05903211236000061,-0.017072021961212158 -1769682138,306526208,0.0,0.0,0.0,1.0,0.0001535195333417505,0.0004048720293212682,-0.0012490252265706658,-0.9212008118629456,0.08585023880004883,-0.010291272774338722 -1769682138,339412480,0.0,0.0,0.0,1.0,0.0001910420396598056,0.00046355099766515195,-0.0010834040585905313,-0.9093508720397949,0.010549364611506462,-0.005050265230238438 -1769682138,374392576,0.0,0.0,0.0,1.0,0.00015272195741999894,0.0002242952468805015,-0.0009289683657698333,-0.897254228591919,-0.06500029563903809,-0.012911956757307053 -1769682138,408961536,0.0,0.0,0.0,1.0,0.0001275532995350659,-0.00011749298573704436,-0.0007288481574505568,-0.9093955159187317,0.010539468377828598,-0.002673730254173279 -1769682138,454582016,0.0,0.0,0.0,1.0,0.00017287168884649873,-0.00015126238577067852,-0.0005815734621137381,-0.9212110042572021,0.08574727177619934,-0.010308375582098961 -1769682138,473248256,0.0,0.0,0.0,1.0,0.00016056661843322217,-3.341323463246226e-05,-0.0004312925157137215,-0.8785682916641235,-0.06190945580601692,-0.004272026009857655 -1769682138,509086464,0.0,0.0,0.0,1.0,0.00013756526459474117,0.00029909811564721167,-0.0002317432372365147,-0.9024210572242737,0.08875425159931183,-0.007639783434569836 -1769682138,556420864,0.0,0.0,0.0,1.0,0.0002212922991020605,0.0003972066624555737,-8.148492634063587e-05,-0.8783471584320068,-0.0621548667550087,-0.016203779727220535 -1769682138,575136768,0.0,0.0,0.0,1.0,0.00019880011677742004,0.0004819643800146878,6.401529390132055e-05,-0.8525805473327637,0.01913636177778244,-0.018508993089199066 -1769682138,607512832,0.0,0.0,0.0,1.0,0.00021578946325462312,0.0004834278079215437,0.0002621360763441771,-0.8785235285758972,-0.06196308508515358,-0.006698275450617075 -1769682138,655717120,0.0,0.0,0.0,1.0,0.00019869129755534232,0.0005067564197815955,0.0004573076730594039,-0.8458012342453003,0.09761983156204224,-0.012785034254193306 -1769682138,672186112,0.0,0.0,0.0,1.0,0.00012892132508568466,0.0006078579463064671,0.0005492763011716306,-0.9024398922920227,0.08880408108234406,-0.006517909932881594 -1769682138,706640128,0.0,0.0,0.0,1.0,0.00018937760614790022,0.0006727962754666805,0.0007284195744432509,-0.8477902412414551,-0.13424457609653473,-0.003578939475119114 -1769682138,755239936,0.0,0.0,0.0,1.0,0.00018347382138017565,0.0007307165651582181,0.0008540830458514392,-0.8527098894119263,0.01934657245874405,-0.01144260074943304 -1769682138,780961280,0.0,0.0,0.0,1.0,0.00013156005297787488,0.0007722439477220178,0.001016068970784545,-0.9261336326599121,0.2394225150346756,-0.01711316965520382 -1769682138,807920384,0.0,0.0,0.0,1.0,0.00019022861670237035,0.0008137416443787515,0.0011330277193337679,-0.9140549302101135,0.16395160555839539,-0.02379056252539158 -1769682138,841831936,0.0,0.0,0.0,1.0,0.00016438576858490705,0.0007979893125593662,0.0012447494082152843,-0.8220028877258301,-0.052870284765958786,-0.007144221570342779 -1769682138,872576000,0.0,0.0,0.0,1.0,0.0001674197119427845,0.0007547397399321198,0.0013571740128099918,-0.8408856987953186,-0.05577550828456879,-0.005073236767202616 -1769682138,908722688,0.0,0.0,0.0,1.0,0.00011251328396610916,0.0007291542715393007,0.0014935916988179088,-0.8100137114524841,-0.128223717212677,-0.010262991301715374 -1769682138,944224768,0.0,0.0,0.0,1.0,0.00020694492559414357,0.0008542549912817776,0.0016273504588752985,-0.8031964302062988,-0.04973338544368744,-0.00572527851909399 -1769682138,973081344,0.0,0.0,0.0,1.0,0.00016116378537844867,0.0008919452666305006,0.0016952779842540622,-0.8457403779029846,0.09790278226137161,-0.014183010905981064 -1769682139,6284288,0.0,0.0,0.0,1.0,0.00019313901429995894,0.0009179974440485239,0.0018126923823729157,-0.8456881642341614,0.09791605919599533,-0.016597826033830643 -1769682139,55278080,0.0,0.0,0.0,1.0,0.00018378871027380228,0.0009152964339591563,0.0018967625219374895,-0.7962770462036133,0.028740569949150085,-0.00599499000236392 -1769682139,73756160,0.0,0.0,0.0,1.0,0.00015344779239967465,0.000981335761025548,0.001983488444238901,-0.8268836140632629,0.10103710740804672,-0.013965873047709465 -1769682139,106530304,0.0,0.0,0.0,1.0,0.00014365723473019898,0.0010979382786899805,0.0020961035043001175,-0.8267397880554199,0.10096538811922073,-0.021151229739189148 -1769682139,139432448,0.0,0.0,0.0,1.0,0.0001600693358341232,0.0010180753888562322,0.002176156733185053,-0.8151082396507263,0.025928925722837448,-0.0063744657672941685 -1769682139,175528192,0.0,0.0,0.0,1.0,0.0002226895885542035,0.0008980751154012978,0.0022605638951063156,-0.8150837421417236,0.02596021443605423,-0.007589332293719053 -1769682139,208233472,0.0,0.0,0.0,1.0,0.0001882710203062743,0.0008345009991899133,0.002361510181799531,-0.7771562337875366,0.03172377124428749,-0.02012644335627556 -1769682139,251500544,0.0,0.0,0.0,1.0,0.00026474351761862636,0.0009555737487971783,0.0024377552326768637,-0.770395815372467,0.11033163219690323,-0.009629510343074799 -1769682139,272984576,0.0,0.0,0.0,1.0,0.0001968997239600867,0.0011158334091305733,0.002506860066205263,-0.7843667268753052,-0.04624767601490021,-0.0068584345281124115 -1769682139,307121408,0.0,0.0,0.0,1.0,0.00019165550475008786,0.0011002154788002372,0.0025762354489415884,-0.7961667776107788,0.02913595549762249,-0.010975442826747894 -1769682139,356473856,0.0,0.0,0.0,1.0,9.282621613238007e-05,0.0010616716463118792,0.002626184606924653,-0.746559739112854,-0.040314674377441406,-0.013464333489537239 -1769682139,374838784,0.0,0.0,0.0,1.0,0.00015079317381605506,0.0009930426022037864,0.002683867234736681,-0.7584361433982849,0.03516388684511185,-0.012812684290111065 -1769682139,406447872,0.0,0.0,0.0,1.0,0.00010986431880155578,0.0010260379640385509,0.002721223747357726,-0.758478581905365,0.03527206927537918,-0.01045250054448843 -1769682139,453388032,0.0,0.0,0.0,1.0,0.00012910242367070168,0.0009334750939160585,0.0027540731243789196,-0.7892213463783264,0.1078215092420578,-0.007714180741459131 -1769682139,473722624,0.0,0.0,0.0,1.0,9.728535223985091e-05,0.0008638942381367087,0.00279400497674942,-0.7772665619850159,0.032391779124736786,-0.01318177580833435 -1769682139,510251520,0.0,0.0,0.0,1.0,0.0001658405817579478,0.0009998611640185118,0.002846818882972002,-0.7702674269676208,0.11083998531103134,-0.01222765538841486 -1769682139,567262976,0.0,0.0,0.0,1.0,0.00014709346578456461,0.0011427131248638034,0.002886839909479022,-0.689988374710083,-0.031106527894735336,-0.016269216313958168 -1769682139,576922880,0.0,0.0,0.0,1.0,0.00015558782615698874,0.001237814431078732,0.002937430515885353,-0.7397337555885315,0.038707174360752106,-0.004321551416069269 -1769682139,608261120,0.0,0.0,0.0,1.0,0.0001887259422801435,0.0012022764421999454,0.0029707869980484247,-0.7255566716194153,0.19534935057163239,-0.009531490504741669 -1769682139,653533184,0.0,0.0,0.0,1.0,0.00014852717868052423,0.001206460758112371,0.0029961769469082355,-0.7018356323242188,0.044528208673000336,-0.014485102146863937 -1769682139,672922112,0.0,0.0,0.0,1.0,0.00014297878078650683,0.0011294230353087187,0.0030215755105018616,-0.7395377159118652,0.038718730211257935,-0.013933783397078514 -1769682139,708724992,0.0,0.0,0.0,1.0,0.0001247843320015818,0.0010234862565994263,0.003039705567061901,-0.6760810017585754,0.12611928582191467,-0.006097795441746712 -1769682139,758487040,0.0,0.0,0.0,1.0,0.00015682046068832278,0.0009311342728324234,0.0030533745884895325,-0.6783747673034668,-0.1059212014079094,-0.008762801997363567 -1769682139,768467456,0.0,0.0,0.0,1.0,0.0001566702703712508,0.0009187760297209024,0.003052009269595146,-0.6641772389411926,0.05073659121990204,-0.01157616637647152 -1769682139,806728960,0.0,0.0,0.0,1.0,0.0001097297717933543,0.0011283657513558865,0.0030569215305149555,-0.7135880589485168,0.12030471861362457,-0.013937941752374172 -1769682139,855738112,0.0,0.0,0.0,1.0,0.00012149449321441352,0.0011726892553269863,0.0030560349114239216,-0.6596531867980957,-0.10270262509584427,-0.0037485011853277683 -1769682139,874114560,0.0,0.0,0.0,1.0,0.0001550842571305111,0.0011841984232887626,0.003058303613215685,-0.6829572319984436,0.047955937683582306,-0.014347371645271778 -1769682139,906727680,0.0,0.0,0.0,1.0,0.00012017488188575953,0.0012095231795683503,0.003051202744245529,-0.6571118235588074,0.12941953539848328,-0.008318589068949223 -1769682139,940334848,0.0,0.0,0.0,1.0,0.0001437688188161701,0.0011731716804206371,0.0030458495020866394,-0.6264604330062866,0.056946560740470886,-0.011080807074904442 -1769682139,979224320,0.0,0.0,0.0,1.0,0.00011412664025556296,0.0011700238101184368,0.0030235194135457277,-0.6782214045524597,0.20349079370498657,-0.009054300375282764 -1769682140,10031616,0.0,0.0,0.0,1.0,0.00010213644418399781,0.0011671371757984161,0.003001491306349635,-0.6147858500480652,-0.018271874636411667,-0.00822452548891306 -1769682140,52047616,0.0,0.0,0.0,1.0,0.00011721358896465972,0.0012594128493219614,0.0029897617641836405,-0.6263001561164856,0.056994274258613586,-0.01830468513071537 -1769682140,74118656,0.0,0.0,0.0,1.0,9.073915134649724e-05,0.0012923028552904725,0.0029629990458488464,-0.6288705468177795,0.13423652946949005,-0.003213491290807724 -1769682140,107696896,0.0,0.0,0.0,1.0,8.464639540761709e-05,0.0013371624518185854,0.0029500385280698538,-0.5937285423278809,-0.09198199957609177,-0.005233812611550093 -1769682140,145931520,0.0,0.0,0.0,1.0,0.00016231661720667034,0.001321930903941393,0.0029322162736207247,-0.6286523342132568,0.13417813181877136,-0.012805618345737457 -1769682140,173316352,0.0,0.0,0.0,1.0,0.00011551647912710905,0.0012552258558571339,0.002925548702478409,-0.6170673966407776,0.05891156196594238,-0.007527616340667009 -1769682140,208838400,0.0,0.0,0.0,1.0,0.00018309189181309193,0.0011743434006348252,0.0029234790708869696,-0.5931760668754578,0.21698683500289917,-0.012583325617015362 -1769682140,254802944,0.0,0.0,0.0,1.0,0.00010577603825367987,0.0012425276217982173,0.002919059945270419,-0.6215939521789551,0.2128295600414276,-0.004745050799101591 -1769682140,274500352,0.0,0.0,0.0,1.0,0.00011642183380899951,0.00129184580873698,0.002912735566496849,-0.6215033531188965,0.21281324326992035,-0.00834488682448864 -1769682140,307814656,0.0,0.0,0.0,1.0,6.761511758668348e-05,0.0013381644384935498,0.002895441371947527,-0.5352129340171814,-0.1595749706029892,0.005487145856022835 -1769682140,349155584,0.0,0.0,0.0,1.0,0.00012066788622178137,0.0012855872046202421,0.0028790005017071962,-0.5583056807518005,-0.008898915722966194,-0.005130622535943985 -1769682140,379971840,0.0,0.0,0.0,1.0,6.825744640082121e-05,0.0012423942098394036,0.0028505679219961166,-0.5351249575614929,-0.1595851331949234,-0.0005179215222597122 -1769682140,409790208,0.0,0.0,0.0,1.0,0.00010950813884846866,0.001164030283689499,0.002821466652676463,-0.5488105416297913,-0.007404997944831848,-0.008591446094214916 -1769682140,454160384,0.0,0.0,0.0,1.0,4.271926445653662e-05,0.0010834732092916965,0.0027903816662728786,-0.5700668096542358,0.06681296229362488,0.0014177234843373299 -1769682140,474836480,0.0,0.0,0.0,1.0,4.757502756547183e-05,0.0009660697542130947,0.0027499860152602196,-0.5320717096328735,0.07239919900894165,-0.012252843007445335 -1769682140,509142272,0.0,0.0,0.0,1.0,8.794839231995866e-05,0.0008461151155643165,0.002707005012780428,-0.513313889503479,0.07543836534023285,-0.007174408063292503 -1769682140,544544512,0.0,0.0,0.0,1.0,8.36649996927008e-05,0.0006792239146307111,0.0026476895436644554,-0.5227786302566528,0.0740906372666359,-0.004970065783709288 -1769682140,572817152,0.0,0.0,0.0,1.0,5.533524017664604e-05,0.0006490415544249117,0.0026183100417256355,-0.5321507453918457,0.07262169569730759,-0.007523564156144857 -1769682140,608681216,0.0,0.0,0.0,1.0,2.7584912459133193e-05,0.0007445151568390429,0.002572174184024334,-0.4879303276538849,-0.1521749645471573,-0.008147701621055603 -1769682140,654484736,0.0,0.0,0.0,1.0,6.370688788592815e-05,0.0007916923495940864,0.0025364134926348925,-0.5131900906562805,0.0755181834101677,-0.011989433318376541 -1769682140,675808000,0.0,0.0,0.0,1.0,3.389179255464114e-05,0.0007774002151563764,0.0024812694173306227,-0.5112360119819641,-0.0011079348623752594,-0.002099737524986267 -1769682140,706533888,0.0,0.0,0.0,1.0,7.391862163785845e-05,0.0007686672615818679,0.002437766408547759,-0.49228811264038086,0.0017270762473344803,-0.0065484498627483845 -1769682140,749674752,0.0,0.0,0.0,1.0,2.9656599508598447e-05,0.0007450912380591035,0.002385537140071392,-0.4850662350654602,0.0801452174782753,-0.003193426411598921 -1769682140,778254848,0.0,0.0,0.0,1.0,3.3254629670409486e-05,0.0006848177290521562,0.0023145212326198816,-0.4736083149909973,0.0048627303913235664,0.0020981524139642715 -1769682140,808084480,0.0,0.0,0.0,1.0,5.145765680936165e-05,0.0006954226410016418,0.0022551645524799824,-0.47336292266845703,0.004658995196223259,-0.009827487170696259 -1769682140,843429376,0.0,0.0,0.0,1.0,4.2434603528818116e-05,0.0007034974405542016,0.0021979426965117455,-0.47350960969924927,0.004832153208553791,-0.002687727101147175 -1769682140,872866048,0.0,0.0,0.0,1.0,7.01480166753754e-05,0.0007572080940008163,0.002143296878784895,-0.49645280838012695,0.15559419989585876,-0.009735798463225365 -1769682140,908909056,0.0,0.0,0.0,1.0,5.998877895763144e-05,0.0007732292870059609,0.002076164586469531,-0.45668473839759827,0.0845823884010315,-0.006330257281661034 -1769682140,961595136,0.0,0.0,0.0,1.0,8.815506589598954e-05,0.0007734508253633976,0.0020294850692152977,-0.45458295941352844,0.007742890156805515,-0.005966258235275745 -1769682140,970416384,0.0,0.0,0.0,1.0,8.051586337387562e-05,0.0007338650757446885,0.0019935511518269777,-0.4565756022930145,0.08454330265522003,-0.01111752912402153 -1769682141,6811136,0.0,0.0,0.0,1.0,0.00012629244884010404,0.0006498581496998668,0.0019464032957330346,-0.43776601552963257,0.08750592172145844,-0.008413569070398808 -1769682141,56705024,0.0,0.0,0.0,1.0,0.00011070035543525591,0.0005784814129583538,0.0019074123119935393,-0.4377344250679016,0.08751591295003891,-0.009615685790777206 -1769682141,73560832,0.0,0.0,0.0,1.0,4.6500957978423685e-05,0.0005354955792427063,0.0018893418600782752,-0.42630207538604736,0.012174098752439022,-0.005503435153514147 -1769682141,108634880,0.0,0.0,0.0,1.0,5.326849714037962e-05,0.00042022307752631605,0.0018593487329781055,-0.43557897210121155,0.010626141913235188,-0.012827647849917412 -1769682141,141266176,0.0,0.0,0.0,1.0,9.072174725588411e-05,0.00045681872870773077,0.0018451000796630979,-0.39804619550704956,0.016565702855587006,-0.0038234416861087084 -1769682141,174512384,0.0,0.0,0.0,1.0,0.00013613754708785564,0.00042626261711120605,0.0018295291811227798,-0.4209250807762146,0.16736173629760742,-0.009682411327958107 -1769682141,207034112,0.0,0.0,0.0,1.0,9.539058373775333e-05,0.0004762874450534582,0.0018116772407665849,-0.39177364110946655,-0.2140837162733078,-0.007473836187273264 -1769682141,251878912,0.0,0.0,0.0,1.0,0.00011312911374261603,0.0005385284894146025,0.0017996678361669183,-0.3659054934978485,-0.13255535066127777,0.009329341351985931 -1769682141,273235968,0.0,0.0,0.0,1.0,3.225976615794934e-05,0.0005805269465781748,0.0017778802430257201,-0.4074438214302063,0.015200464986264706,-0.005209134425967932 -1769682141,311072000,0.0,0.0,0.0,1.0,5.3316827688831836e-05,0.0007168113952502608,0.0017503082053735852,-0.39385467767715454,-0.13714508712291718,-0.007872316986322403 -1769682141,350669568,0.0,0.0,0.0,1.0,-7.278133853105828e-05,0.0007810314418748021,0.0017028757138177752,-0.41850993037223816,0.09030625224113464,-0.024839947000145912 -1769682141,374333696,0.0,0.0,0.0,1.0,2.983952253998723e-05,0.0008507220190949738,0.001648270757868886,-0.42066478729248047,0.16731466352939606,-0.019269680604338646 -1769682141,409253120,0.0,0.0,0.0,1.0,-4.6799446863587946e-05,0.0008743164944462478,0.0015666797989979386,-0.4301303029060364,0.16595588624477386,-0.017069481313228607 -1769682141,456752640,0.0,0.0,0.0,1.0,4.512887971941382e-05,0.0008966780733317137,0.0015076696872711182,-0.3997891843318939,0.0933803841471672,-0.01738804578781128 -1769682141,474422016,0.0,0.0,0.0,1.0,4.215843364363536e-05,0.0009009635541588068,0.0014549961779266596,-0.34162309765815735,0.025529250502586365,0.004248687997460365 -1769682141,506940160,0.0,0.0,0.0,1.0,2.7556323402677663e-05,0.0008091863710433245,0.0014254441484808922,-0.3698284327983856,0.021177999675273895,0.0001564333215355873 -1769682141,543975936,0.0,0.0,0.0,1.0,0.00010720090358518064,0.0007854755385778844,0.001408684067428112,-0.36037495732307434,0.02260628715157509,-0.0008771633729338646 -1769682141,573416192,0.0,0.0,0.0,1.0,9.120481263380498e-05,0.0007500730571337044,0.0014073813799768686,-0.3697513937950134,0.02113821730017662,-0.003435986815020442 -1769682141,606984192,0.0,0.0,0.0,1.0,0.00012603271170519292,0.0007349586812779307,0.0014144330052658916,-0.34881171584129333,-0.052921220660209656,-0.006302608642727137 -1769682141,639943936,0.0,0.0,0.0,1.0,0.00012621242785826325,0.00042861478868871927,0.0014293689746409655,-0.3599948585033417,0.022296667098999023,-0.01877327263355255 -1769682141,684148480,0.0,0.0,0.0,1.0,0.00011410027946112677,0.00012855140084866434,0.0014414455508813262,-0.33381372690200806,0.10356538742780685,-0.013876715674996376 -1769682141,709945088,0.0,0.0,0.0,1.0,7.27474907762371e-05,-0.00013978932111058384,0.0014487272128462791,-0.3298635184764862,-0.050108134746551514,-0.010734744369983673 -1769682141,757782528,0.0,0.0,0.0,1.0,9.283910185331479e-05,-0.0001954636536538601,0.001446520909667015,-0.3184693455696106,-0.12551173567771912,-0.008991426788270473 -1769682141,773110016,0.0,0.0,0.0,1.0,-8.208384315366857e-06,-0.00019668656750582159,0.0014419034123420715,-0.3393208086490631,-0.05148393660783768,-0.00970962829887867 -1769682141,812912384,0.0,0.0,0.0,1.0,-5.92289688938763e-06,-0.0002402020472800359,0.0014274996938183904,-0.3131272494792938,0.02978351153433323,-0.004808441270142794 -1769682141,855344896,0.0,0.0,0.0,1.0,2.7006328309653327e-05,-0.00022264555445872247,0.0014134031953290105,-0.33203184604644775,0.02698986977338791,-0.002763490192592144 -1769682141,874957312,0.0,0.0,0.0,1.0,3.207050758646801e-05,-0.0002049061586149037,0.0014002058887854218,-0.3205980360507965,-0.04846362769603729,-0.0034035304561257362 -1769682141,907467776,0.0,0.0,0.0,1.0,-6.023517926223576e-05,-0.00018918154819402844,0.0013839160092175007,-0.3112214505672455,-0.04699935019016266,-0.0020397300831973553 -1769682141,958400256,0.0,0.0,0.0,1.0,-1.8947685020975769e-07,-0.0001696282997727394,0.0013769230572506785,-0.30723029375076294,-0.20074810087680817,-0.0024705773685127497 -1769682141,989505792,0.0,0.0,0.0,1.0,-2.4512472009519115e-05,-8.195358532248065e-05,0.0013689578045159578,-0.3170563876628876,0.18359926342964172,-0.005557030905038118 -1769682142,8060416,0.0,0.0,0.0,1.0,-4.3701129470719025e-06,-8.26318864710629e-05,0.0013572880998253822,-0.30165085196495056,-0.04564676061272621,-0.007823153398931026 -1769682142,45873920,0.0,0.0,0.0,1.0,-1.5938068827381358e-05,-9.061487799044698e-05,0.0013394124107435346,-0.3337341845035553,0.10371953248977661,-0.015048443339765072 -1769682142,75364096,0.0,0.0,0.0,1.0,-3.7089288525749e-05,-6.140724144643173e-05,0.0013145277043804526,-0.2829239070415497,-0.0426516979932785,-0.001523673301562667 -1769682142,108732416,0.0,0.0,0.0,1.0,-7.235460361698642e-05,-4.795250060851686e-05,0.0012744928244501352,-0.28488025069236755,0.034230440855026245,-0.0019024128559976816 -1769682142,141243904,0.0,0.0,0.0,1.0,-6.601968925679103e-05,-3.4236061765113845e-05,0.0012238952331244946,-0.2867557108402252,0.11104114353656769,-0.005855725612491369 -1769682142,183380224,0.0,0.0,0.0,1.0,-7.586161518702284e-05,-3.8707319617969915e-05,0.0011649871012195945,-0.27347517013549805,-0.04122084006667137,-0.002544386312365532 -1769682142,207630080,0.0,0.0,0.0,1.0,-0.00012531592801678926,-4.053644443047233e-05,0.0010776958661153913,-0.2733516991138458,-0.04132729768753052,-0.008502354845404625 -1769682142,252285184,0.0,0.0,0.0,1.0,-7.956338959047571e-05,-3.118106906185858e-05,0.0010147766442969441,-0.28671836853027344,0.11104927957057953,-0.007045459467917681 -1769682142,274393344,0.0,0.0,0.0,1.0,-4.834538049180992e-05,2.9527134756790474e-05,0.0009416808607056737,-0.25467273592948914,-0.03829823434352875,0.0001787042710930109 -1769682142,307058688,0.0,0.0,0.0,1.0,-4.569717566482723e-05,2.893005876103416e-05,0.0008947547757998109,-0.2565368711948395,0.03850918635725975,-0.0037742999847978354 -1769682142,345698560,0.0,0.0,0.0,1.0,-3.810987254837528e-05,9.544202475808561e-05,0.0008466169820167124,-0.25467509031295776,-0.03828250616788864,0.0001780178863555193 -1769682142,373649664,0.0,0.0,0.0,1.0,-3.92630354326684e-05,0.00034504462382756174,0.0008262881310656667,-0.25241562724113464,-0.11545827239751816,-0.014936434105038643 -1769682142,409064448,0.0,0.0,0.0,1.0,7.199773244792596e-05,0.0007231933996081352,0.0008055689977481961,-0.23077897727489471,-0.03502603620290756,-0.014894595369696617 -1769682142,465725440,0.0,0.0,0.0,1.0,4.8155110562220216e-05,0.0008986839675344527,0.0007901964709162712,-0.25643208622932434,0.03844184800982475,-0.008555242791771889 -1769682142,473909504,0.0,0.0,0.0,1.0,9.613324073143303e-05,0.0009788471506908536,0.0007899041520431638,-0.23095586895942688,-0.03484907001256943,-0.0065657529048621655 -1769682142,507573760,0.0,0.0,0.0,1.0,4.255733801983297e-05,0.0010675089433789253,0.0007750808726996183,-0.2215278148651123,-0.033421698957681656,-0.006404154933989048 -1769682142,555158016,0.0,0.0,0.0,1.0,7.17002694727853e-05,0.0010209878673776984,0.0007737688138149679,-0.20766262710094452,-0.031025581061840057,0.006953688338398933 -1769682142,575501056,0.0,0.0,0.0,1.0,1.0357201063015964e-05,0.0009434831445105374,0.0007566537242382765,-0.2010277956724167,-0.10718140751123428,0.007410882040858269 -1769682142,609958912,0.0,0.0,0.0,1.0,2.362372470088303e-05,0.0008545390446670353,0.0007487632683478296,-0.21694183349609375,-0.03257641941308975,-0.00038139685057103634 -1769682142,655060992,0.0,0.0,0.0,1.0,3.120831388514489e-05,0.0008196540293283761,0.0007358156726695597,-0.223575159907341,0.04359087347984314,-0.0008526153396815062 -1769682142,673330688,0.0,0.0,0.0,1.0,4.8386791604571044e-05,0.0006978882593102753,0.0007190870819613338,-0.20461471378803253,0.046338874846696854,-0.005279208533465862 -1769682142,708480512,0.0,0.0,0.0,1.0,-3.316109359730035e-05,0.00035437196493148804,0.0006883479072712362,-0.19321919977664948,-0.02915629744529724,-0.0071137892082333565 -1769682142,754449664,0.0,0.0,0.0,1.0,1.5540526874247007e-06,8.500556577928364e-05,0.0006604819209314883,-0.19059538841247559,0.048596594482660294,0.0009325593709945679 -1769682142,773736192,0.0,0.0,0.0,1.0,-5.7426473176747095e-06,6.67002586851595e-06,0.0006424628663808107,-0.18200697004795074,-0.10448379069566727,-0.0006046365015208721 -1769682142,808638208,0.0,0.0,0.0,1.0,-4.5408647565636784e-05,-7.252716750372201e-05,0.0006235093460418284,-0.1773204356431961,-0.10374635457992554,0.0006736896466463804 -1769682142,873238784,0.0,0.0,0.0,1.0,-6.574474355147686e-06,-9.463064634473994e-05,0.0006158248288556933,-0.19515487551689148,0.04775597155094147,-0.006302159279584885 -1769682142,882188032,0.0,0.0,0.0,1.0,1.454068024031585e-05,-4.3404776079114527e-05,0.0006173147121444345,-0.20465907454490662,0.046414248645305634,-0.0028994898311793804 -1769682142,909500160,0.0,0.0,0.0,1.0,-1.2011152648483403e-05,1.9211774997529574e-06,0.0006112344563007355,-0.1971081644296646,0.12468431144952774,-0.0042981551960110664 -1769682142,943146496,0.0,0.0,0.0,1.0,-1.1025192179658916e-05,3.220516737201251e-05,0.0005966806202195585,-0.18775279819965363,0.12617655098438263,-0.0005510887131094933 -1769682142,972983552,0.0,0.0,0.0,1.0,-2.8249485694686882e-05,0.00016256928211078048,0.0005773649318143725,-0.19515110552310944,0.047771353274583817,-0.006302329711616039 -1769682143,11548160,0.0,0.0,0.0,1.0,-5.0901013310067356e-05,0.00023201503790915012,0.000525902898516506,-0.1604505181312561,-0.02394731715321541,0.0042130607180297375 -1769682143,52226560,0.0,0.0,0.0,1.0,-0.00010288378689438105,0.0002611173258628696,0.00046532542910426855,-0.18103069067001343,0.049927614629268646,-0.004854321945458651 -1769682143,74118912,0.0,0.0,0.0,1.0,-9.007287735585123e-05,0.00025767620536498725,0.00041228302870877087,-0.13766953349113464,-0.1749732345342636,-0.0006429001223295927 -1769682143,106794240,0.0,0.0,0.0,1.0,-5.490209878189489e-05,0.00019700484699569643,0.0003232065646443516,-0.16870583593845367,0.1288589984178543,-0.00855125579982996 -1769682143,159040000,0.0,0.0,0.0,1.0,-0.00013441524060908705,0.00013642416161019355,0.00022576277842745185,-0.14618068933486938,-0.021932799369096756,-0.0014902944676578045 -1769682143,169015808,0.0,0.0,0.0,1.0,-7.561919483123347e-05,9.395949018653482e-05,0.0001759962469805032,-0.17062516510486603,0.20575781166553497,-0.007738861721009016 -1769682143,208113152,0.0,0.0,0.0,1.0,-6.619826308451593e-05,0.0001472456060582772,9.294154006056488e-05,-0.11597186326980591,-0.09457851201295853,-0.0017855094047263265 -1769682143,257210368,0.0,0.0,0.0,1.0,-3.4544096706667915e-05,0.00026268992223776877,4.5460485125659034e-05,-0.12734758853912354,-0.01907454989850521,4.514853935688734e-05 -1769682143,281195264,0.0,0.0,0.0,1.0,6.057283826521598e-06,0.00023248681100085378,2.658723678905517e-05,-0.11123201251029968,-0.0938936173915863,-0.0028923931531608105 -1769682143,308089856,0.0,0.0,0.0,1.0,7.059353811200708e-05,0.0001640382397454232,2.349933492951095e-05,-0.11786730587482452,-0.017705343663692474,-0.0021663520019501448 -1769682143,345397504,0.0,0.0,0.0,1.0,5.024761048844084e-05,0.00023212669475469738,4.4296968553680927e-05,-0.1175871267914772,-0.01796618103981018,-0.015274498611688614 -1769682143,373058048,0.0,0.0,0.0,1.0,6.929407390998676e-05,0.00039042840944603086,5.9272366343066096e-05,-0.1335240751504898,0.056687090545892715,-0.020680535584688187 -1769682143,410330880,0.0,0.0,0.0,1.0,0.000168184022186324,0.000666863052174449,0.00010067594121210277,-0.1034681648015976,-0.01581748202443123,-0.013825892470777035 -1769682143,453864704,0.0,0.0,0.0,1.0,0.00016421196050941944,0.0007815802819095552,0.00012921438610646874,-0.12606428563594818,0.13504807651042938,-0.017318176105618477 -1769682143,474204928,0.0,0.0,0.0,1.0,0.00016142477397806942,0.0008338643237948418,0.00015630156849510968,-0.1007491946220398,0.06185907498002052,-0.00935722142457962 -1769682143,509330944,0.0,0.0,0.0,1.0,9.943263285094872e-05,0.0008317988249473274,0.00017735021538101137,-0.06703595072031021,-0.16427220404148102,0.004218887537717819 -1769682143,556339200,0.0,0.0,0.0,1.0,6.092037438065745e-05,0.0008055137586779892,0.00019920364138670266,-0.09183405339717865,-0.013902626931667328,-0.006469593849033117 -1769682143,574079744,0.0,0.0,0.0,1.0,8.084468572633341e-05,0.0007520586950704455,0.00021332611504476517,-0.10991685092449188,0.13786178827285767,-0.0003459622384980321 -1769682143,607497728,0.0,0.0,0.0,1.0,2.6779000108945183e-05,0.0007133254548534751,0.0002324498345842585,-0.08255872875452042,-0.012342864647507668,0.0008508834289386868 -1769682143,641371904,0.0,0.0,0.0,1.0,7.567012653453276e-05,0.0007038921467028558,0.00025922199711203575,-0.07548676431179047,-0.011280265636742115,0.000980663811787963 -1769682143,677117184,0.0,0.0,0.0,1.0,4.382492625154555e-05,0.0004048670525662601,0.0002936679811682552,-0.0705147385597229,-0.010809101164340973,-0.010848911479115486 -1769682143,709833472,0.0,0.0,0.0,1.0,6.527059213112807e-06,0.00023931896430440247,0.00032343881321139634,-0.04580255225300789,-0.1611071527004242,0.00341574614867568 -1769682143,743177728,0.0,0.0,0.0,1.0,1.8571005057310686e-05,6.28293928457424e-05,0.00034464854979887605,-0.05667975917458534,-0.008399027399718761,0.0037126424722373486 -1769682143,773417728,0.0,0.0,0.0,1.0,-2.8975082386750728e-05,1.0255987490381813e-06,0.00035604022559709847,-0.05458573251962662,-0.08546139299869537,-0.005438641645014286 -1769682143,807965952,0.0,0.0,0.0,1.0,-8.002436516107991e-06,-3.284436752437614e-05,0.00036106296465732157,-0.06126591935753822,-0.009224163368344307,-0.002333039650693536 -1769682143,851998976,0.0,0.0,0.0,1.0,-3.8129641325213015e-05,-8.519175935362e-06,0.0003602088545449078,-0.08146258443593979,0.14197413623332977,-0.0069776903837919235 -1769682143,875218432,0.0,0.0,0.0,1.0,1.0060109161713626e-05,-4.735612674267031e-05,0.0003628888516686857,-0.03166799619793892,-0.1589815765619278,0.0036787232384085655 -1769682143,908066816,0.0,0.0,0.0,1.0,3.499092417769134e-05,-4.302751403884031e-05,0.000372632232028991,-0.06985234469175339,0.1439114511013031,0.001583104021847248 -1769682143,951781888,0.0,0.0,0.0,1.0,1.9662586055346765e-05,3.397609543753788e-05,0.0004052802105434239,-0.05961325764656067,0.06818260252475739,-0.002648330759257078 -1769682143,973653504,0.0,0.0,0.0,1.0,4.4172069465275854e-05,4.473551962291822e-05,0.00043516093865036964,-0.05314438417553902,-0.007863611914217472,0.0037785677704960108 -1769682144,7457024,0.0,0.0,0.0,1.0,5.725687151425518e-05,0.00010989396105287597,0.0004940989310853183,-0.06417163461446762,0.06733425706624985,-0.009886079467833042 -1769682144,68528384,0.0,0.0,0.0,1.0,5.405307820183225e-05,9.954085544450209e-05,0.0005402386304922402,-0.05130784958600998,0.06937535852193832,-0.004878520034253597 -1769682144,77259520,0.0,0.0,0.0,1.0,4.316508420743048e-05,0.00010458500764798373,0.0006001178990118206,-0.05095549672842026,0.14672207832336426,0.0007411262486129999 -1769682144,108832000,0.0,0.0,0.0,1.0,7.689277117606252e-05,7.565641135443002e-05,0.0006322651752270758,-0.021157778799533844,-0.08029988408088684,0.0011447628494352102 -1769682144,152535296,0.0,0.0,0.0,1.0,-3.867365012411028e-05,4.087246998096816e-05,0.0006447381456382573,-0.03059500642120838,-0.004642972722649574,-0.0029542723204940557 -1769682144,174610944,0.0,0.0,0.0,1.0,-3.9840298995841295e-05,-4.018423715024255e-05,0.0006366170127876103,-0.023522820323705673,-0.0035818833857774734,-0.0028224748093634844 -1769682144,209388800,0.0,0.0,0.0,1.0,-1.8886708858190104e-05,-8.557182445656508e-05,0.000615003751590848,-0.02472737990319729,-0.0037343590520322323,-0.001652817940339446 -1769682144,250377216,0.0,0.0,0.0,1.0,-6.746361032128334e-05,-6.813844811404124e-05,0.0005771505529992282,-0.021726947277784348,-0.0033669453114271164,-0.005173018667846918 -1769682144,275538176,0.0,0.0,0.0,1.0,-0.00010796930291689932,-8.676627476233989e-05,0.0005566935869865119,-0.00587279349565506,-0.07792293280363083,0.005005090031772852 -1769682144,306929920,0.0,0.0,0.0,1.0,-7.799468585290015e-05,-5.9842743212357163e-05,0.0005383135285228491,-0.02067713439464569,-0.003070745849981904,0.000806905678473413 -1769682144,354522112,0.0,0.0,0.0,1.0,-2.0388139091664925e-05,0.0002295477461302653,0.0005351663567125797,-0.02044535055756569,-0.0032841775100678205,-0.009917397983372211 -1769682144,375150080,0.0,0.0,0.0,1.0,2.549666169215925e-05,0.00039724179077893496,0.000544393842574209,-0.02164505608379841,0.07363388687372208,-0.012670149095356464 -1769682144,407633152,0.0,0.0,0.0,1.0,1.0494024536455981e-05,0.000529227836523205,0.0005646063946187496,0.005321801640093327,-0.07627248764038086,0.004021590109914541 -1769682144,441204224,0.0,0.0,0.0,1.0,5.5123065976658836e-05,0.0005624298355542123,0.0005811062874272466,-0.006891780067235231,-0.001225626445375383,-0.008473296649754047 -1769682144,475282176,0.0,0.0,0.0,1.0,3.156993989250623e-05,0.0005816978518851101,0.0005895759677514434,-0.010557047091424465,-0.0016361736925318837,-0.002581497188657522 -1769682144,507539456,0.0,0.0,0.0,1.0,3.4433665859978646e-05,0.0005397031200118363,0.0005852858885191381,-0.009466324001550674,0.07565151900053024,-0.004099688492715359 -1769682144,552427520,0.0,0.0,0.0,1.0,-7.031067070784047e-05,0.000533103768248111,0.0005738120526075363,0.013860690407454967,-0.15233872830867767,-0.0038160420954227448 -1769682144,573853952,0.0,0.0,0.0,1.0,-4.263910886947997e-05,0.0004510910948738456,0.0005505491863004863,-0.007800956256687641,0.07603894174098969,0.0018916993867605925 -1769682144,607501056,0.0,0.0,0.0,1.0,-2.750373096205294e-05,0.00035184918669983745,0.0005344715318642557,0.017177995294332504,-0.0745801031589508,0.0006683543906547129 -1769682144,641572352,0.0,0.0,0.0,1.0,-2.0140214473940432e-05,0.00010020458284998313,0.0005311159184202552,0.009481924585998058,0.001363749266602099,-0.002206182572990656 -1769682144,673568256,0.0,0.0,0.0,1.0,3.887069397023879e-05,-0.00010609882156131789,0.0005421286914497614,0.014196999371051788,0.002069157548248768,-0.0021177143789827824 -1769682144,709023232,0.0,0.0,0.0,1.0,2.8958071197848767e-05,-0.00027329300064593554,0.0005817253841087222,0.00020724369096569717,-0.00019011374388355762,-0.009532601572573185 -1769682144,754450688,0.0,0.0,0.0,1.0,3.227565321139991e-05,-0.00033437242382206023,0.000646879430860281,0.01596740633249283,-0.07473403960466385,0.001837496878579259 -1769682144,773623808,0.0,0.0,0.0,1.0,8.488414459861815e-05,-0.00037047002115286887,0.0006873345701023936,0.01950274035334587,-0.07420529425144196,0.0019037388265132904 -1769682144,807286272,0.0,0.0,0.0,1.0,4.122105019632727e-05,-0.0003869906940963119,0.0007607316365465522,0.011736083775758743,0.0018103846814483404,0.0026038330979645252 -1769682144,856226816,0.0,0.0,0.0,1.0,1.1277006706222892e-05,-0.00034811472869478166,0.0008040011744014919,7.754674879834056e-05,-7.131951861083508e-05,-0.0035747287329286337 -1769682144,875024896,0.0,0.0,0.0,1.0,-6.073575059417635e-05,-0.000360698759322986,0.0008292148704640567,0.015934228897094727,-0.07471185177564621,0.0030285711400210857 -1769682144,908362752,0.0,0.0,0.0,1.0,-7.613842171849683e-05,-0.0003672406019177288,0.0008305995725095272,0.027720360085368156,-0.07295037806034088,0.003248535795137286 -1769682144,942237696,0.0,0.0,0.0,1.0,-8.537499525118619e-05,-0.00038417603354901075,0.0008143200539052486,0.0005210023955442011,0.0772264152765274,-0.0003364694130141288 -1769682144,974901248,0.0,0.0,0.0,1.0,-0.00018791720503941178,-0.00036240729968994856,0.0007749565993435681,0.007124410476535559,0.0010092058219015598,-0.002251173136755824 -1769682145,9637632,0.0,0.0,0.0,1.0,-0.0001318917638855055,-0.000356037839083001,0.0007511158473789692,0.004818330053240061,0.0006093496340326965,-0.004678374156355858 -1769682145,41490176,0.0,0.0,0.0,1.0,-3.220977305318229e-05,-0.00036652348353527486,0.0007404081989079714,0.023126661777496338,-0.07377627491950989,-0.0027997647412121296 -1769682145,73781504,0.0,0.0,0.0,1.0,-9.746998694026843e-05,-0.0003945293719880283,0.0007450451957993209,0.006570030469447374,-0.07619387656450272,-0.0007245276938192546 -1769682145,109693184,0.0,0.0,0.0,1.0,-7.010529952822253e-05,-0.000408041087212041,0.0007686500903218985,0.007047224789857864,0.0010797865688800812,0.0013232219498604536 -1769682145,140069120,0.0,0.0,0.0,1.0,-4.184346835245378e-05,-0.0004001704801339656,0.0008000871166586876,0.004792442079633474,0.0006326636648736894,-0.003487036097794771 -1769682145,173979392,0.0,0.0,0.0,1.0,-3.3330716178170405e-06,-0.00043901000753976405,0.0008454754715785384,0.02291293628513813,-0.0735887885093689,0.006731092929840088 -1769682145,210306816,0.0,0.0,0.0,1.0,-1.2862616131315008e-05,-0.0004562322865240276,0.0008755443268455565,0.0046896906569600105,0.0007273845258168876,0.0012791394256055355 -1769682145,254159616,0.0,0.0,0.0,1.0,-3.731519609573297e-05,-0.00047196392551995814,0.0008992168004624546,0.007150030694901943,0.0009840147104114294,-0.003443502588197589 -1769682145,273792512,0.0,0.0,0.0,1.0,-6.219052011147141e-05,-0.0004195091314613819,0.0009266643901355565,0.013732152059674263,-0.07523501664400101,-0.005360810551792383 -1769682145,308748032,0.0,0.0,0.0,1.0,-8.544750744476914e-05,-0.0002569633652456105,0.000940262689255178,0.02266770228743553,-0.15110273659229279,-0.007234837859869003 -1769682145,350953472,0.0,0.0,0.0,1.0,-4.7832552809268236e-05,-0.00013343890896067023,0.0009581511840224266,-0.017614947631955147,0.1514977514743805,-0.008168108761310577 -1769682145,373996544,0.0,0.0,0.0,1.0,-2.2834419723949395e-05,-4.915221506962553e-05,0.0009864240419119596,-0.015775321051478386,0.07459991425275803,-0.008981226943433285 -1769682145,407057152,0.0,0.0,0.0,1.0,-7.163959526224062e-05,6.031624252500478e-06,0.0010150743182748556,0.011262424290180206,-0.07549310475587845,-0.0006388546898961067 -1769682145,440354560,0.0,0.0,0.0,1.0,-4.8866575525607914e-05,1.596258516656235e-05,0.0010443378705531359,0.006518955808132887,-0.07617229968309402,0.0004653295618481934 -1769682145,475312640,0.0,0.0,0.0,1.0,-2.7980187951470725e-05,-3.245277184760198e-07,0.0010914038866758347,-0.004715550225228071,-0.0007023921934887767,-8.732941932976246e-05 -1769682145,508546816,0.0,0.0,0.0,1.0,-7.109349826350808e-05,-3.0070736102061346e-05,0.00113075808621943,-5.1205533964093775e-05,4.748683932120912e-05,0.0023831643629819155 -1769682145,565629952,0.0,0.0,0.0,1.0,-3.9705650124233216e-05,-6.57420459901914e-05,0.0011730650439858437,0.011174009181559086,-0.07542359828948975,0.002935580210760236 -1769682145,574131456,0.0,0.0,0.0,1.0,-8.900059037841856e-05,-0.00013652959023602307,0.0011854019248858094,0.01586225815117359,-0.07469821721315384,0.004214317072182894 -1769682145,607990784,0.0,0.0,0.0,1.0,-0.00011670665116980672,-0.0003016799164470285,0.001208771369419992,0.004766826052218676,0.0006541988113895059,-0.002295896876603365 -1769682145,653996800,0.0,0.0,0.0,1.0,-0.00011521538544911891,-0.00040300004184246063,0.0012181061320006847,0.016009440645575523,-0.07484200596809387,-0.002936017932370305 -1769682145,675954944,0.0,0.0,0.0,1.0,-0.00010450957779539749,-0.00048005106509663165,0.0012219606433063745,0.00461353175342083,0.0007962011732161045,0.004853471647948027 -1769682145,707587840,0.0,0.0,0.0,1.0,-0.0001655972737353295,-0.0005213016411289573,0.0012098266743123531,-0.006469352170825005,0.07615064084529877,-0.0016549370484426618 -1769682145,740752128,0.0,0.0,0.0,1.0,-0.0001563566183904186,-0.000510308425873518,0.0011866448912769556,-0.00461373757570982,-0.0007958202622830868,-0.004853338003158569 -1769682145,774750976,0.0,0.0,0.0,1.0,-0.0001946173724718392,-0.0004721847362816334,0.0011412696912884712,0.0017728203674778342,-0.07687561959028244,0.0003752906632144004 -1769682145,808774400,0.0,0.0,0.0,1.0,-0.00014404808462131768,-0.00045850727474316955,0.0010970872826874256,-0.00010186631698161364,9.483947360422462e-05,0.0047663431614637375 -1769682145,843620608,0.0,0.0,0.0,1.0,-0.00021247152471914887,-0.00042735383613035083,0.001050582155585289,-0.02055487409234047,0.07400301843881607,-0.004296288825571537 -1769682145,874230272,0.0,0.0,0.0,1.0,-0.0002024703862844035,-0.0004027315881103277,0.0009835637174546719,0.015836076810956,-0.07470409572124481,0.004208663944154978 -1769682145,907290112,0.0,0.0,0.0,1.0,-0.00023496705398429185,-0.000377520511392504,0.0009356736554764211,-0.0047667371109128,-0.0006527010118588805,0.0022965080570429564 -1769682145,942445312,0.0,0.0,0.0,1.0,-0.00013619172386825085,-0.0003504041815176606,0.000896938203368336,-0.009584262035787106,-0.001257796655409038,0.0069762892089784145 -1769682145,975867136,0.0,0.0,0.0,1.0,-0.00017866755661088973,-0.0003441128646954894,0.000854808371514082,0.0223793126642704,-0.15095281600952148,0.0010909729171544313 -1769682146,8877824,0.0,0.0,0.0,1.0,-0.00012815056834369898,-0.0003399157430976629,0.0008315242012031376,-0.004792083986103535,-0.0006286469870246947,0.003488254500553012 -1769682146,58461440,0.0,0.0,0.0,1.0,-0.00010502859367989004,-0.0003381040587555617,0.0008145276224240661,0.0016772454837337136,-0.07680507749319077,0.0039464570581912994 -1769682146,81386496,0.0,0.0,0.0,1.0,-9.089829836739227e-05,-0.0004031322314403951,0.0008085028966888785,0.011158131062984467,-0.07545367628335953,0.001735841273330152 -1769682146,107397632,0.0,0.0,0.0,1.0,-8.852651808410883e-05,-0.00037682955735363066,0.0008067807066254318,-0.020613716915249825,0.07407904416322708,-0.0007166285649873316 -1769682146,145744640,0.0,0.0,0.0,1.0,-8.398119825869799e-05,-0.0003849727218039334,0.0008107578614726663,-0.015971191227436066,0.07484983652830124,0.0029449723660945892 -1769682146,174754560,0.0,0.0,0.0,1.0,-3.0951021471992135e-05,-0.0004120464436709881,0.0008196316193789244,-0.031786900013685226,0.14955845475196838,-0.0012588831596076488 -1769682146,210935040,0.0,0.0,0.0,1.0,-9.381979907630011e-05,-0.00042473740177229047,0.0008324669906869531,-0.0030485866591334343,-0.0775042474269867,0.0038592510391026735 -1769682146,248008704,0.0,0.0,0.0,1.0,-8.94566546776332e-05,-0.000336871191393584,0.0008384614484384656,0.008424950763583183,-0.15326690673828125,-0.009897527284920216 -1769682146,273724416,0.0,0.0,0.0,1.0,-0.00015094754053279757,-0.00019777331908699125,0.0008331940043717623,-0.013971678912639618,-0.002261406509205699,-0.008599305525422096 -1769682146,307240192,0.0,0.0,0.0,1.0,-0.00014294024731498212,-9.523100015940145e-05,0.0008191484375856817,0.00010096433834405616,-9.459369903197512e-05,-0.0047663673758506775 -1769682146,353687296,0.0,0.0,0.0,1.0,-0.0001486471010139212,-7.380729584838264e-06,0.0007697815890423954,-0.010990183800458908,0.07531432807445526,-0.008882655762135983 -1769682146,374619904,0.0,0.0,0.0,1.0,-0.00021608846145682037,7.331107917707413e-05,0.0007151116733439267,-0.011013745330274105,0.07533825933933258,-0.007690679747611284 -1769682146,407325696,0.0,0.0,0.0,1.0,-0.00018967522191815078,9.325384598923847e-05,0.0006604641093872488,-0.018789086490869522,-0.002863488160073757,-0.003919029142707586 -1769682146,440922112,0.0,0.0,0.0,1.0,-0.0002327195106772706,6.591519922949374e-05,0.0006038012797944248,0.01113698910921812,-0.0754568874835968,0.00173186045140028 -1769682146,475478272,0.0,0.0,0.0,1.0,-0.0001958157226908952,4.9710331950336695e-05,0.000544289534445852,-0.01891542226076126,-0.0027445845771580935,0.0020388192497193813 -1769682146,509550592,0.0,0.0,0.0,1.0,-0.00014654554252047092,1.974618135136552e-05,0.0005106627941131592,0.009306250140070915,0.0015138100134208798,0.006130159832537174 -1769682146,541965056,0.0,0.0,0.0,1.0,-0.000166804384207353,-8.772945147939026e-05,0.000486246106447652,2.5244946300517768e-05,-2.3605054593645036e-05,-0.0011915926588699222 -1769682146,573847040,0.0,0.0,0.0,1.0,-0.00020515269716270268,-0.00024297204799950123,0.0004614979261532426,-0.00943253468722105,-0.0013954403111711144,-0.00017213280079886317 -1769682146,613693952,0.0,0.0,0.0,1.0,-0.00021968796500004828,-0.00034139654599130154,0.0004465820384211838,-0.03009658306837082,0.07276163250207901,0.0026928409934043884 -1769682146,643536384,0.0,0.0,0.0,1.0,-0.00025437137810513377,-0.0003942814946640283,0.000435982015915215,0.020461320877075195,-0.0739685446023941,0.006667084526270628 -1769682146,675286016,0.0,0.0,0.0,1.0,-0.0002711676643230021,-0.0003858486597891897,0.0004214709915686399,-0.020485352724790573,0.0739925280213356,-0.005474391859024763 -1769682146,707783936,0.0,0.0,0.0,1.0,-0.0002879335661418736,-0.0003785229055210948,0.0004200881812721491,0.02050965093076229,-0.07401639223098755,0.004282026551663876 -1769682146,753044992,0.0,0.0,0.0,1.0,-0.0002800108049996197,-0.0003594759909901768,0.0004282885347492993,-0.007688845973461866,-0.07829519361257553,-0.0010002359049394727 -1769682146,775906816,0.0,0.0,0.0,1.0,-0.000262533692875877,-0.0003661156806629151,0.000442174932686612,-0.017122555524110794,-0.07968970388174057,-0.0011722245253622532 -1769682146,807600896,0.0,0.0,0.0,1.0,-0.0002730113628786057,-0.00035841454518958926,0.00046428237692452967,0.001716586179099977,-0.07687696069478989,0.0003617741749621928 -1769682146,841241856,0.0,0.0,0.0,1.0,-0.00019806143245659769,-0.00034327656612731516,0.0004869576951023191,-0.02839861623942852,-0.004088942892849445,0.004252387676388025 -1769682146,876611584,0.0,0.0,0.0,1.0,-0.00023621231957804412,-0.000317161378916353,0.000520741508807987,-0.01891569420695305,-0.0027412790805101395,0.002040744526311755 -1769682146,908591616,0.0,0.0,0.0,1.0,-0.00026124718715436757,-0.0003040842420887202,0.0005468426970764995,0.02221563272178173,-0.1508956104516983,0.00463690934702754 -1769682146,945888000,0.0,0.0,0.0,1.0,-0.00022390797676052898,-0.000275676604360342,0.0005852439790032804,-0.0598682276904583,0.14525052905082703,-0.008894302882254124 -1769682146,974249728,0.0,0.0,0.0,1.0,-0.00010622918489389122,-0.00021387987362686545,0.0006257434724830091,-0.03944085165858269,0.07130268216133118,-0.0010427741799503565 -1769682147,9896704,0.0,0.0,0.0,1.0,-0.00011643821198958904,-0.00016258606046903878,0.0006631599389947951,-0.007699739187955856,-0.07829407602548599,-0.0010040294146165252 -1769682147,46952704,0.0,0.0,0.0,1.0,-0.00010869662219192833,-0.00012773914204444736,0.0006947239162400365,-0.007827180437743664,-0.07817646116018295,0.004953679628670216 -1769682147,73960448,0.0,0.0,0.0,1.0,-0.00012539180170278996,-7.305467443075031e-05,0.0007065142854116857,-0.050422921776771545,0.1466488093137741,-0.008719894103705883 -1769682147,107541248,0.0,0.0,0.0,1.0,-0.0001373648556182161,-7.134549377951771e-05,0.000708115694578737,-0.02819865196943283,-0.0042721922509372234,-0.0052790213376283646 -1769682147,153977600,0.0,0.0,0.0,1.0,-0.00019973833695985377,-5.0563998229335994e-05,0.0006766581791453063,-0.03007468208670616,0.07277023047208786,0.0027050364296883345 -1769682147,175843584,0.0,0.0,0.0,1.0,-0.00016741969739086926,-5.525286906049587e-05,0.0006309691816568375,0.0015738490037620068,-0.07676006108522415,0.006314779166132212 -1769682147,208137728,0.0,0.0,0.0,1.0,-0.00020475254859775305,-1.3046354069956578e-05,0.0005751691060140729,0.00020034184854011983,-0.00018764402193482965,-0.009532799012959003 -1769682147,240642816,0.0,0.0,0.0,1.0,-0.0002923124993685633,0.00010006393858930096,0.0005142997833900154,-0.018740909174084663,-0.0029012244194746017,-0.006299743428826332 -1769682147,274599168,0.0,0.0,0.0,1.0,-0.00031274501816369593,0.00015685646212659776,0.00043326709419488907,-0.018740929663181305,-0.0029008060228079557,-0.006299874745309353 -1769682147,308062976,0.0,0.0,0.0,1.0,-0.00032789362012408674,0.00016792396490927786,0.00038692416273988783,-0.007738999091088772,-0.07826919853687286,0.0001831597473938018 -1769682147,341893888,0.0,0.0,0.0,1.0,-0.0002269932592753321,0.00017316965386271477,0.0003528775123413652,-0.009282748214900494,-0.0015320804668590426,-0.007320658769458532 -1769682147,374262016,0.0,0.0,0.0,1.0,-0.00025028406525962055,0.00018668189295567572,0.0003337934613227844,-0.00771584315225482,-0.07829242199659348,-0.001009976607747376 -1769682147,408459008,0.0,0.0,0.0,1.0,-0.00022848270600661635,0.0002015100617427379,0.00033561920281499624,-0.017099618911743164,-0.07973049581050873,-0.003564937738701701 -1769682147,443219712,0.0,0.0,0.0,1.0,-0.00017950199253391474,0.0001678205735515803,0.00034897090517915785,0.00943316612392664,0.0013912776485085487,0.00017126250895671546 -1769682147,476277760,0.0,0.0,0.0,1.0,-0.00021342314721550792,0.00017090083565562963,0.0003783094580285251,-0.02058097906410694,0.0741187185049057,0.0004977184580639005 -1769682147,510864128,0.0,0.0,0.0,1.0,-0.0004257995169609785,0.0001342095638392493,0.00038981009856797755,-0.009232430718839169,-0.0015779533423483372,-0.009704199619591236 -1769682147,543187200,0.0,0.0,0.0,1.0,-0.0005507842288352549,1.7598458725842647e-05,0.000403268844820559,-0.020604336634278297,0.07414253056049347,0.0016910245176404715 -1769682147,574124288,0.0,0.0,0.0,1.0,-0.0006651045405305922,-6.629830750171095e-05,0.0004183652636129409,0.031697697937488556,-0.14960646629333496,1.780287129804492e-05 -1769682147,607372032,0.0,0.0,0.0,1.0,-0.0006469032960012555,-0.00011504918802529573,0.0004324102192185819,-0.009408165700733662,-0.0014139254344627261,-0.0013630498433485627 -1769682147,644502528,0.0,0.0,0.0,1.0,-0.0006730785826221108,-0.0001853332796599716,0.000447684433311224,-0.009383116848766804,-0.0014369883574545383,-0.002554627601057291 -1769682147,676570112,0.0,0.0,0.0,1.0,-0.0006737593794241548,-0.00023691046226304024,0.0004660161503124982,-0.018766308203339577,-0.0028736162930727005,-0.005109186749905348 -1769682147,709025536,0.0,0.0,0.0,1.0,-0.0006370577029883862,-0.0002689115353859961,0.0004875222803093493,-0.04102197661995888,0.14812526106834412,-0.004941905848681927 -1769682147,742170880,0.0,0.0,0.0,1.0,-0.0006023937021382153,-0.0002712446148507297,0.0005074852961115539,-0.00948345847427845,-0.001343641895800829,0.0022119174245744944 -1769682147,774993664,0.0,0.0,0.0,1.0,-0.000641736201941967,-0.00027755129849538207,0.0005240985192358494,-0.02054595574736595,0.07409822195768356,-0.0006798654212616384 -1769682147,809539584,0.0,0.0,0.0,1.0,-0.0006806424935348332,-0.00025060962070710957,0.0005257842713035643,-0.026747381314635277,-0.08093126118183136,0.005780377890914679 -1769682147,853755904,0.0,0.0,0.0,1.0,-0.0007407772936858237,-0.0002647780056577176,0.0005095578380860388,0.0032026839908212423,-0.153617262840271,0.00781725998967886 -1769682147,874274304,0.0,0.0,0.0,1.0,-0.0007240995182655752,-0.0002505849115550518,0.0004777667054440826,-0.05046780779957771,0.14676310122013092,-0.003902953118085861 -1769682147,907922432,0.0,0.0,0.0,1.0,-0.0006476608105003834,-0.00023390684509649873,0.0004469416744541377,-0.03938313201069832,0.07129810750484467,-0.002206390257924795 -1769682147,959487744,0.0,0.0,0.0,1.0,-0.0003771046467591077,-6.089529051678255e-05,0.0004294005630072206,-0.026427648961544037,-0.081229567527771,-0.009716571308672428 -1769682147,973541632,0.0,0.0,0.0,1.0,-0.0002571330696810037,1.3708765436604153e-05,0.0004093817842658609,0.022160904482007027,-0.15093226730823517,0.0033825822174549103 -1769682148,8073472,0.0,0.0,0.0,1.0,-0.00023040478117763996,0.00010004255454987288,0.0003895058180205524,0.010929574258625507,-0.07532810419797897,0.008840504102408886 -1769682148,53896960,0.0,0.0,0.0,1.0,-0.00010123558604391292,0.00011503854329930618,0.0003651958832051605,-0.007888397201895714,-0.07815171778202057,0.006114873569458723 -1769682148,74143232,0.0,0.0,0.0,1.0,-7.392106635961682e-05,0.00012477606651373208,0.0003499082231428474,-0.018817121163010597,-0.002823186106979847,-0.0027254910673946142 -1769682148,109031680,0.0,0.0,0.0,1.0,-9.749293894856237e-06,0.00010561302042333409,0.0003341651754453778,-0.02991899475455284,0.0726667121052742,-0.0032243402674794197 -1769682148,143643392,0.0,0.0,0.0,1.0,8.904951755539514e-06,0.0001285446633119136,0.00032993245986290276,-0.009558663703501225,-0.0012732802424579859,0.005786837078630924 -1769682148,174371328,0.0,0.0,0.0,1.0,-0.00020743347704410553,0.00019111948495265096,0.00030624924693256617,-0.015359001234173775,-0.15669406950473785,-0.008029035292565823 -1769682148,208262656,0.0,0.0,0.0,1.0,-0.0002829856821335852,0.0002699802571441978,0.0002919352555181831,-0.03753424435853958,-0.005736773833632469,-0.01021826732903719 -1769682148,241501696,0.0,0.0,0.0,1.0,-0.0003471547388471663,0.0003621106152422726,0.00028145441319793463,-0.03768443688750267,-0.005598376039415598,-0.003069060854613781 -1769682148,274273536,0.0,0.0,0.0,1.0,-0.0004125368141103536,0.00042281675268895924,0.0002807992568705231,-0.02983996458351612,0.07259942591190338,-0.006797820795327425 -1769682148,309803264,0.0,0.0,0.0,1.0,-0.0004796026332769543,0.00046806238242425025,0.00028857591678388417,-0.029864316806197166,0.07262273132801056,-0.00560562452301383 -1769682148,343132928,0.0,0.0,0.0,1.0,-0.000534233869984746,0.0004641906707547605,0.0003031526575796306,-0.01889241673052311,-0.0027526903431862593,0.0008477548253722489 -1769682148,375298560,0.0,0.0,0.0,1.0,-0.0005952334031462669,0.0004546742420643568,0.0003240275545977056,0.010819430463016033,-0.07523853331804276,0.013600926846265793 -1769682148,407481600,0.0,0.0,0.0,1.0,-0.000566887145396322,0.00044000823982059956,0.00033697503386065364,0.0003266763233114034,-0.0002977063995786011,-0.015490913763642311 -1769682148,457621760,0.0,0.0,0.0,1.0,-0.0006601673667319119,0.0004917105543427169,0.0003414403763599694,-0.01894286274909973,-0.0027063109446316957,0.003229863476008177 -1769682148,476661504,0.0,0.0,0.0,1.0,-0.000863215303979814,3.296094655524939e-05,0.0003388716431800276,0.018892593681812286,0.002751880558207631,-0.0008464772254228592 -1769682148,507805440,0.0,0.0,0.0,1.0,-0.000988124986179173,-0.000436511094449088,0.00031801903969608247,-0.03753376752138138,-0.0057315281592309475,-0.010222963988780975 -1769682148,544774400,0.0,0.0,0.0,1.0,-0.0010302709415555,-0.0008071899064816535,0.00026637615519575775,0.011367741972208023,-0.07574170082807541,-0.012624561786651611 -1769682148,580535296,0.0,0.0,0.0,1.0,-0.001019350253045559,-0.0009975574212148786,0.00020588250481523573,-0.030033770948648453,0.07278542965650558,0.002750186715275049 -1769682148,609841920,0.0,0.0,0.0,1.0,-0.0008164274040609598,-0.0012368093011900783,0.0001395715371472761,-0.026894863694906235,-0.08081267029047012,0.011707035824656487 -1769682148,645607680,0.0,0.0,0.0,1.0,-0.0007355543784797192,-0.0014059481909498572,4.6655270125484094e-05,-0.019042404368519783,-0.002615391742438078,0.007998637855052948 -1769682148,674145024,0.0,0.0,0.0,1.0,-0.0007014911388978362,-0.001430579344742,-9.601853889762424e-06,-0.00810118205845356,-0.07797132432460785,0.015622178092598915 -1769682148,709278464,0.0,0.0,0.0,1.0,-0.0005664037307724357,-0.001466164831072092,-5.269182656775229e-05,0.007752209901809692,0.07828814536333084,0.001061537186615169 -1769682148,746629888,0.0,0.0,0.0,1.0,-0.0005110337515361607,-0.0014315115986391902,-8.155097020789981e-05,-0.04877643659710884,0.06989827752113342,-0.0035325386561453342 -1769682148,775818496,0.0,0.0,0.0,1.0,-0.00039280345663428307,-0.0013881601626053452,-8.221861207857728e-05,-0.03780952841043472,-0.005480457562953234,0.0028961151838302612 -1769682148,809281792,0.0,0.0,0.0,1.0,-0.00037497826269827783,-0.0013957085320726037,-7.15581263648346e-05,4.940476719639264e-05,-4.510980215854943e-05,-0.002383248647674918 -1769682148,853775616,0.0,0.0,0.0,1.0,-0.0003109944227617234,-0.0013261225540190935,-5.458651503431611e-05,-0.007924082688987255,-0.07813039422035217,0.0072767664678394794 -1769682148,874869504,0.0,0.0,0.0,1.0,-0.00024792036856524646,-0.001303703524172306,-3.693009784910828e-05,-0.007923686876893044,-0.07813046872615814,0.007276349700987339 -1769682148,907476224,0.0,0.0,0.0,1.0,-0.00014851118612568825,-0.001234251307323575,-1.2162445273133926e-05,-0.03771080821752548,-0.0055709113366901875,-0.0018640451598912477 -1769682148,940674304,0.0,0.0,0.0,1.0,-0.00012015571701340377,-0.0011347172548994422,6.761875283700647e-06,0.011140609160065651,-0.07553648203611374,-0.0019211892504245043 -1769682148,978288384,0.0,0.0,0.0,1.0,-6.564403156517074e-05,-0.0010711830109357834,1.8362099581281655e-05,-0.048851437866687775,0.06996559351682663,6.0802733059972525e-05 -1769682149,8993024,0.0,0.0,0.0,1.0,-7.671571074752137e-05,-0.0010256064124405384,3.503628249745816e-05,-0.034493330866098404,-0.15923789143562317,0.00349435000680387 -1769682149,41567488,0.0,0.0,0.0,1.0,-2.6299196633772226e-06,-0.0010352664394304156,5.818105273647234e-05,-0.011140185408294201,0.07553650438785553,0.001922642346471548 -1769682149,74017280,0.0,0.0,0.0,1.0,4.484807141125202e-05,-0.0010497996117919683,9.682938980404288e-05,-0.026595644652843475,-0.08108469843864441,-0.002588558942079544 -1769682149,112650496,0.0,0.0,0.0,1.0,-1.898578557302244e-05,-0.0011006114073097706,0.00011152132356073707,-0.06764572113752365,0.06712446361780167,-0.00383966788649559 -1769682149,144889088,0.0,0.0,0.0,1.0,-0.00011223168985452503,-0.0005859403172507882,0.00012119112943764776,-0.037323351949453354,-0.005930508486926556,-0.020920902490615845 -1769682149,175268352,0.0,0.0,0.0,1.0,-0.00024352410400751978,-0.00017624405154492706,0.00012700956722255796,-0.07800851762294769,0.14194168150424957,-0.04004364833235741 -1769682149,207265024,0.0,0.0,0.0,1.0,-0.0002537918626330793,0.00013703355216421187,0.00013435243454296142,-0.034011274576187134,-0.1596871018409729,-0.020336108282208443 -1769682149,257259008,0.0,0.0,0.0,1.0,-0.00033231565612368286,0.000378943863324821,0.00015059352153912187,-0.026500526815652847,-0.08117396384477615,-0.007355993147939444 -1769682149,275006976,0.0,0.0,0.0,1.0,-0.0003007692866958678,0.00048448334564454854,0.00017456857312936336,0.018989190459251404,0.00266123004257679,-0.005626192316412926 -1769682149,307950848,0.0,0.0,0.0,1.0,-0.00033045344753190875,0.0005000400124117732,0.00020025522098876536,-0.02995665930211544,0.07271844148635864,-0.0007882987847551703 -1769682149,342965504,0.0,0.0,0.0,1.0,-0.0003864294558297843,0.0004700009012594819,0.00022436687140725553,-0.011112615466117859,0.07551441341638565,0.0007363329059444368 -1769682149,376605696,0.0,0.0,0.0,1.0,-0.0004084026732016355,0.0004040827916469425,0.0002627889043651521,-0.011038909666240215,0.07544723898172379,-0.002837540814653039 -1769682149,410151168,0.0,0.0,0.0,1.0,-0.0004527608398348093,0.0003658888745121658,0.0002939074474852532,-0.030052173882722855,0.07280884683132172,0.003979838453233242 -1769682149,442327552,0.0,0.0,0.0,1.0,-0.000450030027423054,6.420507997972891e-05,0.0003318229573778808,0.00031651719473302364,-0.0002910770126618445,-0.015491250902414322 -1769682149,474107648,0.0,0.0,0.0,1.0,-0.00029827741673216224,-0.0007998694782145321,0.00038607639726251364,0.011304001323878765,-0.07569383829832077,-0.010273477993905544 -1769682149,514982144,0.0,0.0,0.0,1.0,-0.0002627905341796577,-0.0012535983696579933,0.00042574977851472795,-0.010841351002454758,0.0752689465880394,-0.01236662920564413 -1769682149,549191680,0.0,0.0,0.0,1.0,-0.0001641248381929472,-0.0016322109149768949,0.00046449160436168313,0.026725975796580315,0.08096959441900253,-0.0033613070845603943 -1769682149,575583488,0.0,0.0,0.0,1.0,-3.435845428612083e-06,-0.0018016749527305365,0.0004908745177090168,0.0,-0.0,0.0 -1769682149,608036352,0.0,0.0,0.0,1.0,0.0001824800274334848,-0.0018672349397093058,0.000515665567945689,-0.011249224655330181,0.07564966380596161,0.007893433794379234 -1769682149,656246272,0.0,0.0,0.0,1.0,0.0001536846102681011,-0.0018386561423540115,0.0005373993190005422,-0.018964266404509544,-0.0026815058663487434,0.004438685718923807 -1769682149,674169856,0.0,0.0,0.0,1.0,0.00018366066797170788,-0.0018038938287645578,0.0005415850318968296,-0.02987445890903473,0.07265575975179672,-0.004349098540842533 -1769682149,707427840,0.0,0.0,0.0,1.0,0.00020750176918227226,-0.0016900161281228065,0.0005528933834284544,-0.01905934512615204,-0.0025913151912391186,0.009207302704453468 -1769682149,740841472,0.0,0.0,0.0,1.0,0.00013093059533275664,-0.0015956228598952293,0.0005474022473208606,0.018939903005957603,0.0027028867043554783,-0.0032500249799340963 -1769682149,777721600,0.0,0.0,0.0,1.0,0.0001950003788806498,-0.0015509296208620071,0.0005357324262149632,-0.04106370359659195,0.14826342463493347,0.001165538327768445 -1769682149,808113664,0.0,0.0,0.0,1.0,0.0002026803995249793,-0.0015102955512702465,0.0005214304546825588,-0.04883359745144844,0.0699780136346817,9.923230390995741e-05 -1769682149,841318656,0.0,0.0,0.0,1.0,0.00022119091590866446,-0.0014522576238960028,0.000510417390614748,0.011095155030488968,-0.07551689445972443,-0.0007446808740496635 -1769682149,875800576,0.0,0.0,0.0,1.0,0.00013115575711708516,-0.0014576137764379382,0.0004860427579842508,0.011164283379912376,-0.07558438926935196,-0.004319754894822836 -1769682149,910823168,0.0,0.0,0.0,1.0,1.980471279239282e-05,-0.0015500738518312573,0.00046413790551014245,0.018751299008727074,0.0028805520851165056,0.006278274580836296 -1769682149,943255040,0.0,0.0,0.0,1.0,-3.469512739684433e-05,-0.0015747155994176865,0.0004519422654993832,0.00011722140334313735,-0.00011212382378289476,-0.005958260968327522 -1769682149,974681856,0.0,0.0,0.0,1.0,-4.639361213776283e-05,-0.0015313742915168405,0.00044547460856847465,0.02979537658393383,-0.0725928321480751,0.00791300367563963 -1769682150,7889920,0.0,0.0,0.0,1.0,-1.894525485113263e-05,-0.001516763586550951,0.00044473851448856294,-0.029771460220217705,0.07257082313299179,-0.009103119373321533 -1769682150,60310272,0.0,0.0,0.0,1.0,-0.00012420566054061055,-0.001475451048463583,0.00044121438986621797,-0.01122710108757019,0.07565245777368546,0.00789818074554205 -1769682150,67710720,0.0,0.0,0.0,1.0,-9.020157449413091e-05,-0.0014522775309160352,0.00043835528776980937,0.007851758971810341,0.07821789383888245,-0.002510796533897519 -1769682150,108037632,0.0,0.0,0.0,1.0,-4.2209056118736044e-05,-0.0009182970388792455,0.0004195565707050264,0.019563622772693634,0.0020945831201970577,-0.035435210913419724 -1769682150,143294976,0.0,0.0,0.0,1.0,8.12112630228512e-05,-0.0002644220367074013,0.0004383897758089006,-0.02147534117102623,0.15036453306674957,-0.034250084310770035 -1769682150,174130944,0.0,0.0,0.0,1.0,0.00017254096746910363,0.00041577662341296673,0.00044774464913643897,0.030484799295663834,-0.07326795160770416,-0.02784307859838009 -1769682150,209195264,0.0,0.0,0.0,1.0,0.00010172814654652029,0.0007276819087564945,0.00044920307118445635,-0.010734847746789455,0.07518243044614792,-0.017126062884926796 -1769682150,243452160,0.0,0.0,0.0,1.0,0.0001611296902410686,0.0008688748348504305,0.0004371821996755898,0.00020874090841971338,-0.00020183849846944213,-0.010724913328886032 -1769682150,274106624,0.0,0.0,0.0,1.0,0.0001782274921424687,0.0009243597160093486,0.00041007279651239514,0.04902784898877144,-0.07019028812646866,-0.010840332135558128 -1769682150,307599616,0.0,0.0,0.0,1.0,0.00014321127673611045,0.0008569101337343454,0.00038361255428753793,0.048771366477012634,-0.06994405388832092,0.0022694533690810204 -1769682150,347506688,0.0,0.0,0.0,1.0,0.00023761429474689066,0.000721271731890738,0.00034865341149270535,0.007837846875190735,0.07823935151100159,-0.0013208076125010848 -1769682150,376085504,0.0,0.0,0.0,1.0,0.00019976505427621305,0.0006386928143911064,0.0003237938799429685,0.0596836656332016,-0.1453074961900711,0.00986951868981123 -1769682150,408304640,0.0,0.0,0.0,1.0,0.0001961278758244589,0.0004848188254982233,0.0003050205414183438,0.08634427934885025,-0.064259372651577,0.011250745505094528 -1769682150,456145664,0.0,0.0,0.0,1.0,0.0002835886843968183,0.00031409371877089143,0.0003047583741135895,0.05670176073908806,0.008203115314245224,-0.003813363378867507 -1769682150,474633984,0.0,0.0,0.0,1.0,0.0005401225644163787,-0.000351002934621647,0.00033075985265895724,0.10544580966234207,-0.06172184273600578,-0.0003458610735833645 -1769682150,510411008,0.0,0.0,0.0,1.0,0.0006719852099195123,-0.0006624439265578985,0.0003466376510914415,0.0755947157740593,0.010943072848021984,-0.004689319059252739 -1769682150,541070848,0.0,0.0,0.0,1.0,0.0005538374534808099,-0.000839939049910754,0.00035929324803873897,0.08655165135860443,-0.0644652396440506,0.0005268475506454706 -1769682150,574303744,0.0,0.0,0.0,1.0,0.0005369357531890273,-0.0009540727478452027,0.00037420607986859977,0.08655072003602982,-0.06446650624275208,0.000525100389495492 -1769682150,608188928,0.0,0.0,0.0,1.0,0.00047391062253154814,-0.0009401725837960839,0.00038324258639477193,0.0534982830286026,0.1619357466697693,-0.005603892263025045 -1769682150,646255872,0.0,0.0,0.0,1.0,0.0005087777972221375,-0.000843112706206739,0.00040025467751547694,0.08657219260931015,-0.06449142843484879,-0.0006698155775666237 -1769682150,676341760,0.0,0.0,0.0,1.0,0.0005155755789019167,-0.000771111052017659,0.0004209328326396644,0.10539481788873672,-0.06168452277779579,0.002026586327701807 -1769682150,710055936,0.0,0.0,0.0,1.0,0.0005290963454172015,-0.0007069445564411581,0.0004410201217979193,0.045564185827970505,0.08378574252128601,0.0004846242954954505 -1769682150,759569408,0.0,0.0,0.0,1.0,0.0005174829275347292,-0.0005413581384345889,0.0004779778828378767,0.04561194032430649,0.08373956382274628,-0.0019014767603948712 -1769682150,773827072,0.0,0.0,0.0,1.0,0.0005478016682900488,-0.00047981349052861333,0.0005008454318158329,0.05663273110985756,0.00826291460543871,-0.00025297171669080853 -1769682150,807789824,0.0,0.0,0.0,1.0,0.00041484879329800606,-0.00048543658340349793,0.0005180697189643979,0.10534504055976868,-0.06164547801017761,0.004405842162668705 -1769682150,850885120,0.0,0.0,0.0,1.0,0.0004559934895951301,-0.00048411087482236326,0.0005297237075865269,0.08337870985269547,0.0892372578382492,-0.002474042121320963 -1769682150,875192832,0.0,0.0,0.0,1.0,0.0003160693740937859,-0.0004977394128218293,0.0005195836420170963,0.0754111111164093,0.011111801490187645,0.004822420421987772 -1769682150,910010112,0.0,0.0,0.0,1.0,6.964860222069547e-05,-0.0006605804082937539,0.0004798712907359004,0.11644872277975082,-0.13721837103366852,0.001288940547965467 -1769682150,941024000,0.0,0.0,0.0,1.0,-7.709004421485588e-06,-0.0007858762401156127,0.0004508362035267055,0.09432771056890488,0.013824543915688992,0.002747048856690526 -1769682150,980920832,0.0,0.0,0.0,1.0,-9.33575356611982e-05,-0.0009407991892658174,0.0004194126813672483,0.16512852907180786,-0.20711062848567963,0.007130267098546028 -1769682151,26363136,0.0,0.0,0.0,1.0,-0.00014327677490655333,-0.0009109099628403783,0.00041951172170229256,0.11335879564285278,0.016422336921095848,-0.005290552973747253 -1769682151,49396736,0.0,0.0,0.0,1.0,-0.00012156589946243912,-0.0008588160271756351,0.0004379234742373228,0.14321660995483398,-0.056274645030498505,-0.0021425094455480576 -1769682151,74232576,0.0,0.0,0.0,1.0,-0.00011542494758032262,-0.0007739586289972067,0.00046963163185864687,0.12432260811328888,-0.059013091027736664,-0.0012632026337087154 -1769682151,111534848,0.0,0.0,0.0,1.0,-0.00015689560677856207,-0.0006598547915928066,0.0005150871584191918,0.08680889755487442,-0.06476011127233505,-0.013799470849335194 -1769682151,144381440,0.0,0.0,0.0,1.0,0.00017669454973656684,-0.00018950623052660376,0.000590217940043658,0.09480787068605423,0.013338337652385235,-0.02229238674044609 -1769682151,174265600,0.0,0.0,0.0,1.0,0.0003265433188062161,0.00024748319992795587,0.0006707163411192596,0.1056993305683136,-0.062028668820858,-0.01468245591968298 -1769682151,208183040,0.0,0.0,0.0,1.0,0.00041688952478580177,0.00043583428487181664,0.000722667493391782,0.151055708527565,0.021970830857753754,-0.0022996291518211365 -1769682151,257125888,0.0,0.0,0.0,1.0,0.0003918106376659125,0.0005668386584147811,0.0007678757538087666,0.12436184287071228,-0.05907224118709564,-0.003643882228061557 -1769682151,274503168,0.0,0.0,0.0,1.0,0.0004184096760582179,0.0006685755797661841,0.000782644550781697,0.15418478846549988,-0.1317516714334488,0.0007067002588883042 -1769682151,307941376,0.0,0.0,0.0,1.0,0.00039419057429768145,0.000668418244458735,0.0007847632514312863,0.12431345880031586,-0.059032537043094635,-0.0012543379561975598 -1769682151,340753152,0.0,0.0,0.0,1.0,0.00033684799564071,0.0006464050966314971,0.0007837998564355075,0.10222925990819931,0.09201440960168839,0.00020096113439649343 -1769682151,378742272,0.0,0.0,0.0,1.0,0.00039359781658276916,0.0005924225552007556,0.0007557586068287492,0.1807863563299179,-0.05064227059483528,0.006833173334598541 -1769682151,408626432,0.0,0.0,0.0,1.0,0.0004024827212560922,0.00046067070798017085,0.0007327017956413329,0.12110507488250732,0.0947638675570488,0.0005127287004143 -1769682151,448925952,0.0,0.0,0.0,1.0,0.0003831909561995417,0.0004460696072783321,0.0006865790928713977,0.16977034509181976,0.024857686832547188,0.006370825227349997 -1769682151,475461120,0.0,0.0,0.0,1.0,0.0003829152847174555,0.0003681713715195656,0.0006353021017275751,0.18873369693756104,0.027516836300492287,0.0019169142469763756 -1769682151,510948608,0.0,0.0,0.0,1.0,0.0005920411203987896,0.00011044315760955215,0.00058988225646317,0.1998126357793808,-0.048058707267045975,-0.0011856579221785069 -1769682151,541876480,0.0,0.0,0.0,1.0,0.0005808405694551766,-0.0001289786450797692,0.0005445132264867425,0.1402827352285385,0.09720905125141144,-0.014669392257928848 -1769682151,576022784,0.0,0.0,0.0,1.0,0.0004373838019091636,-0.00013906903041061014,0.0004933162708766758,0.14016979932785034,0.09732069075107574,-0.008713810704648495 -1769682151,607677696,0.0,0.0,0.0,1.0,0.000366711727110669,-0.00010557024506852031,0.0004649334878195077,0.20760688185691833,0.030256487429142,0.002224904950708151 -1769682151,655801344,0.0,0.0,0.0,1.0,0.0003343008575029671,3.388539334991947e-05,0.0004430926637724042,0.21083654463291168,-0.12359978258609772,-0.00190034881234169 -1769682151,674727424,0.0,0.0,0.0,1.0,0.00028875083080492914,6.871926598250866e-05,0.0004289406933821738,0.22654806077480316,0.03293319046497345,-0.001039855182170868 -1769682151,710182144,0.0,0.0,0.0,1.0,0.00029437115881592035,7.4630523158703e-05,0.00042001958354376256,0.18082185089588165,-0.05071462690830231,0.0044644721783697605 -1769682151,742340864,0.0,0.0,0.0,1.0,0.0002597165002953261,9.568851965013891e-05,0.00040610515861772,0.18866823613643646,0.027562376111745834,0.0054893940687179565 -1769682151,781029632,0.0,0.0,0.0,1.0,0.00029068096773698926,0.00019158168288413435,0.0003899885923601687,0.19962289929389954,-0.047899190336465836,0.008352899923920631 -1769682151,808333568,0.0,0.0,0.0,1.0,0.0002589013602118939,0.0001849670079536736,0.0003687012067530304,0.2075633853673935,0.03028545156121254,0.004610501229763031 -1769682151,844125696,0.0,0.0,0.0,1.0,0.0002853904734365642,0.00017798502813093364,0.00035056271008215845,0.2153906673192978,0.10858523100614548,0.006825213320553303 -1769682151,875481856,0.0,0.0,0.0,1.0,0.00021963901235722005,0.0002602324530016631,0.00033129664370790124,0.19668151438236237,0.105670265853405,-0.001826189924031496 -1769682151,915579136,0.0,0.0,0.0,1.0,0.00023338083701673895,0.0002605935442261398,0.0003222720988560468,0.23757074773311615,-0.04261462390422821,-0.001742529682815075 -1769682151,945168384,0.0,0.0,0.0,1.0,0.0001417066960129887,0.0001276883267564699,0.0002952935465145856,0.25618863105773926,-0.03961341083049774,0.011678784154355526 -1769682151,975056128,0.0,0.0,0.0,1.0,1.695583159744274e-05,1.681202593317721e-05,0.000281159533187747,0.2484038919210434,-0.11796342581510544,0.007083800621330738 -1769682152,11312128,0.0,0.0,0.0,1.0,-1.585304744367022e-05,-5.4322379583027214e-05,0.0002802802191581577,0.23768459260463715,-0.04273698478937149,-0.007698602043092251 -1769682152,56369664,0.0,0.0,0.0,1.0,-5.260953548713587e-05,-3.1991308787837625e-05,0.0002913649077527225,0.28621402382850647,-0.11253814399242401,0.004130241461098194 -1769682152,74968576,0.0,0.0,0.0,1.0,-1.7206908523803577e-05,-4.568125223158859e-05,0.0003081892791669816,0.25634828209877014,-0.039784543216228485,0.0033364000264555216 -1769682152,107636480,0.0,0.0,0.0,1.0,-6.0599886637646705e-05,3.041182026208844e-05,0.000319550366839394,0.2750815451145172,-0.036899127066135406,0.010797644034028053 -1769682152,140692480,0.0,0.0,0.0,1.0,-0.00014137348625808954,4.19333518948406e-05,0.0003284377744421363,0.29399892687797546,-0.03419880568981171,0.008725753054022789 -1769682152,176151552,0.0,0.0,0.0,1.0,-4.100523074157536e-05,0.0001591992622707039,0.00032975818612612784,0.24867293238639832,-0.11825554817914963,-0.007217162288725376 -1769682152,209049344,0.0,0.0,0.0,1.0,6.85940685798414e-05,0.0003914614499080926,0.0003149570256937295,0.26455095410346985,0.03813660517334938,-0.013513640500605106 -1769682152,245012736,0.0,0.0,0.0,1.0,8.796474139671773e-05,0.0005640461458824575,0.00028460679459385574,0.2645514905452728,0.03813423961400986,-0.013509754091501236 -1769682152,275096064,0.0,0.0,0.0,1.0,0.00011029353481717408,0.0008940964471548796,0.00021833977370988578,0.24860072135925293,-0.11819342523813248,-0.0036273386795073748 -1769682152,309621248,0.0,0.0,0.0,1.0,0.00011885992716997862,0.000977058312855661,0.0001492466835770756,0.3617851734161377,-0.10165867954492569,0.00064091756939888 -1769682152,341629696,0.0,0.0,0.0,1.0,0.00012834490917157382,0.0010049904230982065,8.241533214459196e-05,0.37739095091819763,0.05501130595803261,0.00865267775952816 -1769682152,374487552,0.0,0.0,0.0,1.0,0.0001718078419798985,0.0009831361239776015,-2.1464413293870166e-05,0.26427555084228516,0.0384061336517334,0.0008241680916398764 -1769682152,408172288,0.0,0.0,0.0,1.0,0.00019079876074101776,0.0008857361390255392,-8.72225864441134e-05,0.19968296587467194,-0.048000529408454895,0.004824417643249035 -1769682152,445083904,0.0,0.0,0.0,1.0,0.00023049947049003094,0.0007908943807706237,-0.00016531985602341592,0.28604212403297424,-0.11239667236804962,0.012537524104118347 -1769682152,476360448,0.0,0.0,0.0,1.0,0.00025885095237754285,0.0006769630126655102,-0.00020938956004101783,0.35061097145080566,-0.025963932275772095,0.009744878858327866 -1769682152,508602368,0.0,0.0,0.0,1.0,0.00029694868135266006,0.000632047769613564,-0.00023744870850350708,0.3617633879184723,-0.10162961483001709,0.0018983755726367235 -1769682152,555137024,0.0,0.0,0.0,1.0,0.0003425611066631973,0.0006406651227734983,-0.0002655611024238169,0.324020653963089,-0.10712437331676483,0.0012735091149806976 -1769682152,575116032,0.0,0.0,0.0,1.0,0.00017775646119844168,0.0004599006788339466,-0.0003189301351085305,0.3996489644050598,-0.0962633565068245,-0.0046003712341189384 -1769682152,608646400,0.0,0.0,0.0,1.0,0.00012093687109882012,0.00010610777826514095,-0.00036721309879794717,0.302133709192276,0.04380214214324951,-0.004462869837880135 -1769682152,641347072,0.0,0.0,0.0,1.0,3.9346592529909685e-05,-0.0001304458564845845,-0.0004192245251033455,0.39962777495384216,-0.09623118489980698,-0.003406439907848835 -1769682152,674790656,0.0,0.0,0.0,1.0,-0.00024212854623328894,-0.00021263145026750863,-0.0005059099057689309,0.3995594084262848,-0.09615416824817657,0.0001649702899158001 -1769682152,708119552,0.0,0.0,0.0,1.0,-0.00032554648350924253,-0.0003009964420925826,-0.0005810487200506032,0.30189794301986694,0.04404797777533531,0.007448875345289707 -1769682152,745982976,0.0,0.0,0.0,1.0,-0.0004045280220452696,-0.0003309885796625167,-0.0006728253792971373,0.33982664346694946,0.04937175661325455,-0.001454905141144991 -1769682152,775030784,0.0,0.0,0.0,1.0,-0.0004065344110131264,-0.0002861951070372015,-0.0007395403808914125,0.29106083512306213,0.1194051206111908,-0.0013854056596755981 -1769682152,809226496,0.0,0.0,0.0,1.0,-0.0004203127173241228,-0.00020056241191923618,-0.0008023072732612491,0.38840413093566895,-0.020453037694096565,0.008000530302524567 -1769682152,847166464,0.0,0.0,0.0,1.0,-0.0004005185910500586,-0.0001408750977134332,-0.000880843959748745,0.38831159472465515,-0.020347632467746735,0.012764403596520424 -1769682152,874972672,0.0,0.0,0.0,1.0,-0.0004459105839487165,-7.765590999042615e-05,-0.0009440902504138649,0.3993872404098511,-0.09591016918420792,0.00967160239815712 -1769682152,907603968,0.0,0.0,0.0,1.0,-0.0004534746112767607,-8.548299956601113e-05,-0.0010141842067241669,0.38838282227516174,-0.02039477787911892,0.009186792187392712 -1769682152,960875776,0.0,0.0,0.0,1.0,-0.0004236237145960331,-0.00015087828796822578,-0.0011211398523300886,0.4261489808559418,-0.014893263578414917,0.008624733425676823 -1769682152,969246976,0.0,0.0,0.0,1.0,-0.0004408914828673005,-0.00018902831652667373,-0.0011818811763077974,0.3994198739528656,-0.09589509665966034,0.00847175158560276 -1769682153,8823040,0.0,0.0,0.0,1.0,-0.00045929549378342927,-0.0001451906282454729,-0.0013126588892191648,0.44808924198150635,-0.16577482223510742,0.014344785362482071 -1769682153,41551872,0.0,0.0,0.0,1.0,-0.0004191495245322585,-0.0001705390022834763,-0.0014124701265245676,0.4150850176811218,0.06070337072014809,0.010523112490773201 -1769682153,75695872,0.0,0.0,0.0,1.0,-0.0002313688164576888,-4.1644609154900536e-05,-0.0015019202837720513,0.3885970711708069,-0.02051762491464615,-0.0015485193580389023 -1769682153,112130048,0.0,0.0,0.0,1.0,-0.00013181452231947333,-1.7988350009545684e-06,-0.0015675934264436364,0.3507874011993408,-0.025946959853172302,0.001394468592479825 -1769682153,144054272,0.0,0.0,0.0,1.0,-5.627899008686654e-05,3.356861634529196e-05,-0.0016177314100787044,0.42622390389442444,-0.014854157343506813,0.005041459575295448 -1769682153,174650624,0.0,0.0,0.0,1.0,2.9703725886065513e-05,7.772095705149695e-05,-0.0016612838953733444,0.46387094259262085,-0.0092079509049654,0.010440687648952007 -1769682153,208009728,0.0,0.0,0.0,1.0,0.00013167253928259015,-1.7156671674456447e-05,-0.001669536461122334,0.4261082112789154,-0.014684137888252735,0.011000871658325195 -1769682153,259796480,0.0,0.0,0.0,1.0,0.00014168050256557763,-0.0001326517085544765,-0.0016677046660333872,0.43710726499557495,-0.0901079773902893,0.013859553262591362 -1769682153,275483392,0.0,0.0,0.0,1.0,0.00013416618457995355,-8.530638297088444e-05,-0.0016575860790908337,0.49056339263916016,0.07189396768808365,0.010591469705104828 -1769682153,308036352,0.0,0.0,0.0,1.0,0.00017727560771163553,1.2615568266483024e-05,-0.0016509194392710924,0.4639661908149719,-0.009199262596666813,0.005670640151947737 -1769682153,356460800,0.0,0.0,0.0,1.0,6.376155943144113e-05,0.00048694113502278924,-0.0016717045800760388,0.4155673682689667,0.060406528413295746,-0.015691837295889854 -1769682153,375121920,0.0,0.0,0.0,1.0,-2.6601208446663804e-05,0.0007899890770204365,-0.0016886383527889848,0.49099454283714294,0.07153953611850739,-0.012034701183438301 -1769682153,408536320,0.0,0.0,0.0,1.0,-9.246716945199296e-05,0.00096350401872769,-0.00172006047796458,0.4374578297138214,-0.0903121680021286,-0.002798170316964388 -1769682153,442567424,0.0,0.0,0.0,1.0,-0.00012433886877261102,0.0010242591379210353,-0.0017515509389340878,0.4263705015182495,-0.014771690592169762,-0.0020721103064715862 -1769682153,479049216,0.0,0.0,0.0,1.0,-0.00014544464647769928,0.0011087844613939524,-0.0017816786421462893,0.4262542724609375,-0.01462679821997881,0.003904844168573618 -1769682153,510327040,0.0,0.0,0.0,1.0,-0.00015630939742550254,0.0010712658986449242,-0.0017998798284679651,0.41503581404685974,0.061027027666568756,0.010589953511953354 -1769682153,546184704,0.0,0.0,0.0,1.0,-0.0001942886592587456,0.0010341766756027937,-0.001810053363442421,0.5504782795906067,-0.07333730161190033,0.011099749244749546 -1769682153,574972928,0.0,0.0,0.0,1.0,-0.00020816341566387564,0.0009910265216603875,-0.0018136162543669343,0.4749387502670288,-0.08435794711112976,0.012218007817864418 -1769682153,612824576,0.0,0.0,0.0,1.0,-0.00020364735973998904,0.0009019756689667702,-0.001813333947211504,0.42618632316589355,-0.014458036981523037,0.0075358860194683075 -1769682153,644097280,0.0,0.0,0.0,1.0,-0.00015883904416114092,0.0008013842161744833,-0.0018181189661845565,0.4749472737312317,-0.08430641144514084,0.0122421495616436 -1769682153,676097280,0.0,0.0,0.0,1.0,-0.0002127947227563709,0.000819273991510272,-0.0018203133950009942,0.4749056100845337,-0.08422622084617615,0.014640545472502708 -1769682153,707991296,0.0,0.0,0.0,1.0,-0.0001959243672899902,0.0007733852253295481,-0.0018354374915361404,0.42623576521873474,-0.014426428824663162,0.005187088157981634 -1769682153,759490304,0.0,0.0,0.0,1.0,-0.0002503813593648374,0.0006744813872501254,-0.0018638874171301723,0.5127451419830322,-0.07869856059551239,0.010543351992964745 -1769682153,769222912,0.0,0.0,0.0,1.0,-0.0004832327540498227,0.0004536673950497061,-0.0018914614338427782,0.5019432902336121,-0.0034883925691246986,-0.005420058034360409 -1769682153,824697088,0.0,0.0,0.0,1.0,-0.0008944551809690893,-0.00015105791680980474,-0.0019759731367230415,0.5509159564971924,-0.07348796725273132,-0.010255743749439716 -1769682153,843800576,0.0,0.0,0.0,1.0,-0.0011230423115193844,-0.0005257384036667645,-0.00204836786724627,0.5130442380905151,-0.07888225466012955,-0.003761136904358864 -1769682153,875620352,0.0,0.0,0.0,1.0,-0.0011706211371347308,-0.00074677326483652,-0.00213801022619009,0.5019439458847046,-0.003376009874045849,-0.0054382444359362125 -1769682153,907827968,0.0,0.0,0.0,1.0,-0.0012189908884465694,-0.0009175756713375449,-0.002209076890721917,0.463950514793396,-0.008663788437843323,0.007011789362877607 -1769682153,943765248,0.0,0.0,0.0,1.0,-0.0012275507906451821,-0.0010065864771604538,-0.0022713528014719486,0.4793547987937927,0.1479538530111313,0.009100127965211868 -1769682153,974700544,0.0,0.0,0.0,1.0,-0.0012253758031874895,-0.0010679414262995124,-0.002356338081881404,0.5393686890602112,0.00260789692401886,0.010646333917975426 -1769682154,26318336,0.0,0.0,0.0,1.0,-0.0011889147572219372,-0.0010799787705764174,-0.00239686481654644,0.512837827205658,-0.07846040278673172,0.008059061132371426 -1769682154,57502208,0.0,0.0,0.0,1.0,-0.0011399934301152825,-0.0010742483427748084,-0.002423187717795372,0.5503411293029785,-0.07260395586490631,0.020590659230947495 -1769682154,70796032,0.0,0.0,0.0,1.0,-0.0010855747386813164,-0.0011260871542617679,-0.0024221620988100767,0.5727909207344055,-0.22365157306194305,0.015517177060246468 -1769682154,109023232,0.0,0.0,0.0,1.0,-0.0009589087567292154,-0.000891247414983809,-0.0023948836605995893,0.5282447934150696,0.07821007072925568,0.007744367700070143 -1769682154,141266944,0.0,0.0,0.0,1.0,-0.0009343404090031981,-0.0007979048532433808,-0.002358362078666687,0.5017334222793579,-0.002866966649889946,0.005156231112778187 -1769682154,180605440,0.0,0.0,0.0,1.0,-0.0008537682006135583,-0.000643938547000289,-0.002295105252414942,0.6037610173225403,0.08941757678985596,0.0054204994812607765 -1769682154,208217856,0.0,0.0,0.0,1.0,-0.0008476721704937518,-0.0006557086599059403,-0.0022503489162772894,0.5016872882843018,-0.002742122858762741,0.0075161037966609 -1769682154,243528192,0.0,0.0,0.0,1.0,-0.0008512359345331788,-0.0007268001791089773,-0.0022021611221134663,0.5505401492118835,-0.07249371707439423,0.01334407553076744 -1769682154,275793408,0.0,0.0,0.0,1.0,-0.0008645869675092399,-0.0008396573248319328,-0.0021540222223848104,0.4904642105102539,0.0728321522474289,0.008247911930084229 -1769682154,313842944,0.0,0.0,0.0,1.0,-0.0008252689149230719,-0.0008646381902508438,-0.002123679732903838,0.52823406457901,0.078423872590065,0.006487155333161354 -1769682154,343906304,0.0,0.0,0.0,1.0,-0.0008274560677818954,-0.0008727024542167783,-0.0020971433259546757,0.6149174571037292,0.014175286516547203,0.006978148594498634 -1769682154,375622400,0.0,0.0,0.0,1.0,-0.0002472829073667526,-0.0005648898659273982,-0.0019219384994357824,0.6037700772285461,0.0896308422088623,0.0029589608311653137 -1769682154,408099328,0.0,0.0,0.0,1.0,-6.61508966004476e-05,-0.000394173403037712,-0.0018331923056393862,0.599351167678833,-0.14203400909900665,0.02147486060857773 -1769682154,449506560,0.0,0.0,0.0,1.0,5.808345304103568e-05,-0.00023695359413977712,-0.0017614952521398664,0.5882518291473389,-0.06662997603416443,0.015083039179444313 -1769682154,475159296,0.0,0.0,0.0,1.0,5.811516166431829e-05,-0.00021228360128588974,-0.0017602378502488136,0.5015506744384766,-0.0023396145552396774,0.014583287760615349 -1769682154,508271872,0.0,0.0,0.0,1.0,8.32843070384115e-05,-0.00022053760767448694,-0.0017774782609194517,0.6148205995559692,0.014455655589699745,0.011704444885253906 -1769682154,540782336,0.0,0.0,0.0,1.0,0.00013902691716793925,-0.00025931434356607497,-0.001824133563786745,0.5884251594543457,-0.06669052690267563,0.006730060093104839 -1769682154,580736512,0.0,0.0,0.0,1.0,0.00014988075417932123,-0.0002616993442643434,-0.001895342138595879,0.5771635174751282,0.008844735100865364,0.0074888793751597404 -1769682154,610514688,0.0,0.0,0.0,1.0,0.00013963556557428092,-0.00019870130927301943,-0.0019518950721248984,0.5995197296142578,-0.14192602038383484,0.015489799901843071 -1769682154,643019520,0.0,0.0,0.0,1.0,0.00014488381566479802,-0.0001796216965885833,-0.0020057987421751022,0.6148637533187866,0.014563120901584625,0.009302639402449131 -1769682154,675770880,0.0,0.0,0.0,1.0,1.7102371202781796e-05,-1.2264483302715234e-05,-0.002081417478621006,0.6002582907676697,-0.14252716302871704,-0.021457653492689133 -1769682154,710088448,0.0,0.0,0.0,1.0,-0.00021325808484107256,0.0005233513074927032,-0.0021542985923588276,0.5510721206665039,-0.07245716452598572,-0.011784017086029053 -1769682154,741755904,0.0,0.0,0.0,1.0,-0.00037291209446266294,0.0008805944817140698,-0.002196925925090909,0.5774622559547424,0.008747106418013573,-0.007994182407855988 -1769682154,774604288,0.0,0.0,0.0,1.0,-0.0005362334195524454,0.0011963717406615615,-0.0022237382363528013,0.5886204838752747,-0.06655565649271011,-0.0015838779509067535 -1769682154,809218048,0.0,0.0,0.0,1.0,-0.0005569016211666167,0.0013589991722255945,-0.002225446281954646,0.5773450136184692,0.008947428315877914,-0.001987638883292675 -1769682154,857473280,0.0,0.0,0.0,1.0,-0.0007009675027802587,0.0014885426498949528,-0.002239341614767909,0.5395057797431946,0.003463760018348694,0.0033684284426271915 -1769682154,874555136,0.0,0.0,0.0,1.0,-0.0007665797020308673,0.0014972164062783122,-0.0022653306368738413,0.6147368550300598,0.014994235709309578,0.015393219888210297 -1769682154,907934720,0.0,0.0,0.0,1.0,-0.0008112182840704918,0.001431444426998496,-0.002296973718330264,0.550614058971405,-0.07174839824438095,0.013371292501688004 -1769682154,942749440,0.0,0.0,0.0,1.0,-0.0008583316812291741,0.0013455305015668273,-0.002331996103748679,0.6259889602661133,-0.06034122034907341,0.018249783664941788 -1769682157,982834432,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,8748800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,46414080,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,75254016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,7.235601515276358e-05,-4.3057490984210745e-05,-0.0023827017284929752 -1769682158,111570688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,150701312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,176898048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,208294400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,260433152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,270217472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,308558336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,341800960,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,376958464,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,411895040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,445829888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,475502336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,511804160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,546373376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,575665152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,608755712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,661246208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,668736000,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,710725120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,753724416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,7.235661905724555e-05,-4.305758557165973e-05,-0.0023827017284929752 -1769682158,775923200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,802105856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.03771260380744934,0.0056450446136295795,0.001043225871399045 -1769682158,845812480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,875195136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,909945856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,957712384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682158,974922240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682159,9288192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682159,54940928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-3.6178436857881024e-05,2.152878550987225e-05,0.0011913508642464876 -1769682159,75723776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682159,109018624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682159,147242240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682159,175731712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,3.6178498703520745e-05,-2.1528781871893443e-05,-0.0011913508642464876 -1769682159,210075904,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682159,247044608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682159,275342336,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682159,308494080,0.0,0.0,0.0,1.0,-0.005357267335057259,-0.05125614255666733,1.4754361473023891e-05,2.2145848274230957,-0.2665383815765381,0.918380081653595 -1769682159,342375424,0.0,0.0,0.0,1.0,-0.007381204981356859,-0.0982644334435463,-6.770242907805368e-05,0.837634265422821,-0.017085306346416473,0.5644326210021973 -1769682159,376398592,0.0,0.0,0.0,1.0,-0.006765956990420818,-0.1168249249458313,-0.00026779109612107277,-0.4304896295070648,0.016703445464372635,0.18202978372573853 -1769682159,410364928,0.0,0.0,0.0,1.0,-0.00551670603454113,-0.10841453820466995,-0.00046804925659671426,-1.0517606735229492,0.07343439757823944,-0.04881182312965393 -1769682159,456365568,0.0,0.0,0.0,1.0,-0.0039102910086512566,-0.08943179994821548,-0.0006716771167702973,-1.3848280906677246,0.2517596483230591,-0.21878519654273987 -1769682159,475952896,0.0,0.0,0.0,1.0,-0.001875261659733951,-0.05822903662919998,-0.0009486908675171435,-1.3878320455551147,0.017850175499916077,-0.3230014741420746 -1769682159,508740352,0.0,0.0,0.0,1.0,-0.000571624783333391,-0.03585948795080185,-0.0011346471728757024,-1.3991115093231201,0.09266825765371323,-0.3571909964084625 -1769682159,549813248,0.0,0.0,0.0,1.0,0.0007168333977460861,-0.011965662240982056,-0.001338423229753971,-1.124382734298706,0.05721002444624901,-0.3225291967391968 -1769682159,575200512,0.0,0.0,0.0,1.0,0.0013047362444922328,0.0005897427326999605,-0.0014575772220268846,-0.9099204540252686,0.16735699772834778,-0.27181583642959595 -1769682159,609319168,0.0,0.0,0.0,1.0,0.0016293812077492476,0.008710010908544064,-0.0015503631439059973,-0.7635596990585327,-0.04095543175935745,-0.20237189531326294 -1769682159,647936000,0.0,0.0,0.0,1.0,0.001708128023892641,0.013391285203397274,-0.0016381550813093781,-0.6362792253494263,0.13410261273384094,-0.11004053056240082 -1769682159,675405056,0.0,0.0,0.0,1.0,0.001553805428557098,0.013295787386596203,-0.0017021624371409416,-0.5012484192848206,0.0012501385062932968,-0.0431576631963253 -1769682159,709694464,0.0,0.0,0.0,1.0,0.0012858135160058737,0.011202992871403694,-0.0017585981404408813,-0.528377115726471,-0.07888710498809814,0.01493459939956665 -1769682159,744887808,0.0,0.0,0.0,1.0,0.0010001442860811949,0.007702217902988195,-0.0018285540863871574,-0.48731905221939087,0.15933990478515625,0.04697326570749283 -1769682159,776923904,0.0,0.0,0.0,1.0,0.0006357516394928098,0.0029315692372620106,-0.001937613938935101,-0.5403127074241638,-0.002691483125090599,0.060916222631931305 -1769682159,809100544,0.0,0.0,0.0,1.0,0.0004166416765656322,0.00041070423321798444,-0.002002206863835454,-0.5176954865455627,-0.15357361733913422,0.06500591337680817 -1769682159,845369600,0.0,0.0,0.0,1.0,0.00014916289364919066,-0.002882492495700717,-0.0021186417434364557,-0.6761058568954468,0.1310718059539795,0.05563673377037048 -1769682159,875332608,0.0,0.0,0.0,1.0,9.198520274367183e-06,-0.004128474276512861,-0.0022062212228775024,-0.5890588760375977,0.06656692177057266,0.0365012101829052 -1769682159,909184256,0.0,0.0,0.0,1.0,-0.0001125194612541236,-0.005611565429717302,-0.0023210428189486265,-0.7511975169181824,0.11915503442287445,0.027636658400297165 -1769682159,943255552,0.0,0.0,0.0,1.0,-0.00010648708848748356,-0.005868107080459595,-0.0024153694976121187,-0.7660452723503113,-0.03771073743700981,0.014802834019064903 -1769682159,975424256,0.0,0.0,0.0,1.0,-0.00019081651407759637,-0.006302548106759787,-0.0025830273516476154,-0.7771933674812317,0.03737436234951019,-0.0019468367099761963 -1769682160,11292672,0.0,0.0,0.0,1.0,-0.00014948575699236244,-0.005426667630672455,-0.002696768846362829,-0.9015512466430664,0.09546107798814774,-0.017459280788898468 -1769682160,44540416,0.0,0.0,0.0,1.0,-0.00018289951549377292,-0.004771477542817593,-0.0028643307741731405,-0.8902426362037659,0.019993489608168602,-0.012258877046406269 -1769682160,75045888,0.0,0.0,0.0,1.0,-0.00015254550089593977,-0.004023903515189886,-0.002988915191963315,-0.8637552857398987,0.10082870721817017,-0.02515466697514057 -1769682160,108525312,0.0,0.0,0.0,1.0,-0.00015311542665585876,-0.0036106915213167667,-0.0031256454531103373,-0.852449893951416,0.025404758751392365,-0.018850475549697876 -1769682160,143469056,0.0,0.0,0.0,1.0,-0.0001328984508290887,-0.0033162827603518963,-0.003266574814915657,-0.9164736270904541,-0.06154380366206169,-0.020392585545778275 -1769682160,176523776,0.0,0.0,0.0,1.0,-0.00012119370512664318,-0.0030255629681050777,-0.003453589044511318,-0.9278488159179688,0.013736903667449951,-0.02290475368499756 -1769682160,209200384,0.0,0.0,0.0,1.0,-9.35394418775104e-05,-0.002477791626006365,-0.0035880464129149914,-0.9278793931007385,0.013678831979632378,-0.02044752612709999 -1769682160,255484416,0.0,0.0,0.0,1.0,-8.79083017935045e-05,-0.001966133713722229,-0.003722026012837887,-0.9016190767288208,0.09477309882640839,-0.017915748059749603 -1769682160,275956992,0.0,0.0,0.0,1.0,9.741121175466105e-06,-0.001554614631459117,-0.003918513655662537,-0.9507722854614258,0.16433672606945038,-0.019618503749370575 -1769682160,312110592,0.0,0.0,0.0,1.0,-3.624844248406589e-05,-0.0012465736363083124,-0.004078058060258627,-1.0034104585647583,0.0020205602049827576,-0.012600625865161419 -1769682160,342969344,0.0,0.0,0.0,1.0,-2.9654140234924853e-05,-0.0012741833925247192,-0.004231732804328203,-0.9280793070793152,0.013495957478880882,-0.0035666925832629204 -1769682160,375435520,0.0,0.0,0.0,1.0,-3.535619907779619e-05,-0.00015344267012551427,-0.004393334966152906,-1.0029823780059814,0.0010607913136482239,-0.0506625697016716 -1769682160,409400064,0.0,0.0,0.0,1.0,-3.417510015424341e-05,0.0025038314051926136,-0.0044715977273881435,-0.8521209955215454,0.023863421753048897,-0.050595443695783615 -1769682160,445960704,0.0,0.0,0.0,1.0,-7.296803232748061e-06,0.0037596458569169044,-0.0045762332156300545,-0.9017573595046997,0.0940549373626709,-0.013158350251615047 -1769682160,475555328,0.0,0.0,0.0,1.0,-0.00011016292410204187,0.002665627747774124,-0.004681784193962812,-0.8150132894515991,0.03024834394454956,0.0019778963178396225 -1769682160,509000448,0.0,0.0,0.0,1.0,-0.00016073213191702962,0.0012967641232535243,-0.0047861491329967976,-0.8528231382369995,0.02451973222196102,0.009939347393810749 -1769682160,561395456,0.0,0.0,0.0,1.0,-0.00024597340961918235,-0.00028305078740231693,-0.0049091181717813015,-0.8150928616523743,0.030076688155531883,0.007885012775659561 -1769682160,570458880,0.0,0.0,0.0,1.0,-0.0002727308601606637,-0.0009194439626298845,-0.00496825622394681,-0.8788912296295166,-0.05708910524845123,0.0003138883039355278 -1769682160,609808128,0.0,0.0,0.0,1.0,-0.00030935631366446614,-0.0016664261929690838,-0.005082380957901478,-0.852779746055603,0.02401638776063919,0.005223967134952545 -1769682160,658258432,0.0,0.0,0.0,1.0,-0.00031209434382617474,-0.0019334391690790653,-0.005162723828107119,-0.9019538760185242,0.09338024258613586,-0.003645949997007847 -1769682160,675191040,0.0,0.0,0.0,1.0,-0.0003382741706445813,-0.0018290200969204307,-0.005262169986963272,-0.8757854700088501,0.17429670691490173,-0.009442710317671299 -1769682160,709888512,0.0,0.0,0.0,1.0,-0.0002629139053169638,-0.00011806774273281917,-0.005292815156280994,-0.9277747869491577,0.011343782767653465,-0.032253384590148926 -1769682160,741781504,0.0,0.0,0.0,1.0,-0.00022536788310389966,0.0009915694827213883,-0.005316098220646381,-0.8901695609092712,0.017140869051218033,-0.023597709834575653 -1769682160,775559936,0.0,0.0,0.0,1.0,-0.00022823522158432752,0.0006200323114171624,-0.005378296133130789,-0.8642265796661377,0.09837760031223297,-0.011610706336796284 -1769682160,808869376,0.0,0.0,0.0,1.0,-0.000247974821832031,0.0003677505301311612,-0.005414871498942375,-0.9047236442565918,-0.1396680474281311,-0.013960548676550388 -1769682160,842976000,0.0,0.0,0.0,1.0,-0.0002937201934400946,0.0001459850900573656,-0.005453683435916901,-0.8903555870056152,0.016927141696214676,-0.008147946558892727 -1769682160,875260672,0.0,0.0,0.0,1.0,-0.0003301002143416554,-0.00027209168183617294,-0.00549545232206583,-0.9280157089233398,0.010841131210327148,-0.012051643803715706 -1769682160,911083520,0.0,0.0,0.0,1.0,-0.0002904128050431609,-0.0004292679950594902,-0.005520960781723261,-0.9513469338417053,0.16147743165493011,-0.013703093864023685 -1769682160,960300032,0.0,0.0,0.0,1.0,-0.00031451639370061457,-0.0005990051431581378,-0.005546960514038801,-0.9397904872894287,0.08600743114948273,-0.005103202536702156 -1769682160,975266048,0.0,0.0,0.0,1.0,-0.0002999677381012589,-0.0005696850130334496,-0.005564387887716293,-0.9280904531478882,0.01042984426021576,-0.0060444725677371025 -1769682161,9311744,0.0,0.0,0.0,1.0,-0.0003312797052785754,-0.0003541542973835021,-0.005582755897194147,-0.94231778383255,-0.14644044637680054,-0.009474582970142365 -1769682161,55845888,0.0,0.0,0.0,1.0,-0.0003807934990618378,-0.00025754369562491775,-0.005621010437607765,-0.965786337852478,0.00425536185503006,-0.006355732679367065 -1769682161,77206016,0.0,0.0,0.0,1.0,-0.0003059371665585786,0.0018681911751627922,-0.0056495023891329765,-0.9654993414878845,0.00361010804772377,-0.0314294807612896 -1769682161,109273600,0.0,0.0,0.0,1.0,-0.0003604880184866488,0.0026762604247778654,-0.00570963928475976,-0.8030785322189331,-0.04829157516360283,-0.021583804860711098 -1769682161,146438912,0.0,0.0,0.0,1.0,-0.0003324845456518233,0.0032571619376540184,-0.005796147510409355,-0.8148938417434692,0.02699406072497368,-0.017144951969385147 -1769682161,175675648,0.0,0.0,0.0,1.0,-0.0003171993885189295,0.003034199820831418,-0.005857481621205807,-0.8410789966583252,-0.05402256175875664,0.006499013863503933 -1769682161,212539904,0.0,0.0,0.0,1.0,-0.0003937202855013311,0.0018947395728901029,-0.005931990221142769,-0.7161967754364014,-0.11187700182199478,0.006521248258650303 -1769682161,248733440,0.0,0.0,0.0,1.0,-0.0003455672413110733,0.000564818037673831,-0.005997642409056425,-0.8763828873634338,0.1715913712978363,-0.005012867972254753 -1769682161,275248896,0.0,0.0,0.0,1.0,-0.00034998165210708976,9.750631761562545e-06,-0.0060057612136006355,-0.902351438999176,0.09025920182466507,0.0020165052264928818 -1769682161,309103360,0.0,0.0,0.0,1.0,-0.00032779871253296733,-0.00021435762755572796,-0.00599388312548399,-0.8151143789291382,0.026503238826990128,-0.0006271004676818848 -1769682161,346891520,0.0,0.0,0.0,1.0,-0.00028681993717327714,-0.00041577289812266827,-0.005963329691439867,-0.7892314195632935,0.1075139045715332,-0.006454490590840578 -1769682161,377223424,0.0,0.0,0.0,1.0,-0.00026798242470249534,-0.0003836614778265357,-0.005933774635195732,-0.9517917633056641,0.15891218185424805,-0.012829971499741077 -1769682161,408680448,0.0,0.0,0.0,1.0,-0.00030097702983766794,-0.00038020862848497927,-0.005898165516555309,-0.8645290732383728,0.0952019914984703,-0.01547195389866829 -1769682161,456050944,0.0,0.0,0.0,1.0,-0.00031599338399246335,-0.00032255484256893396,-0.0058740428648889065,-0.8645884990692139,0.09511010348796844,-0.011886310763657093 -1769682161,477255424,0.0,0.0,0.0,1.0,-0.00034491639235056937,8.178906864486635e-05,-0.0058460598811507225,-0.8784179091453552,-0.06182508170604706,-0.014162839390337467 -1769682161,510514944,0.0,0.0,0.0,1.0,-0.0003992893034592271,0.0004047140828333795,-0.005836125463247299,-0.8407168388366699,-0.056031860411167145,-0.015015758574008942 -1769682161,543161088,0.0,0.0,0.0,1.0,-0.0005362048977985978,0.0007204705034382641,-0.005828275810927153,-0.9162268042564392,-0.06788437068462372,-0.0014261547476053238 -1769682161,575909888,0.0,0.0,0.0,1.0,-0.0006801960407756269,0.0011622527381405234,-0.005816520657390356,-0.864665150642395,0.09440436214208603,-0.011935198679566383 -1769682161,610450944,0.0,0.0,0.0,1.0,-0.0007092872983776033,0.0013082369696348906,-0.00581495463848114,-0.8646812438964844,0.09425371140241623,-0.01196637749671936 -1769682161,644038400,0.0,0.0,0.0,1.0,-0.0007472365978173912,0.0014062839327380061,-0.005806546658277512,-0.9143307209014893,0.1634226143360138,-0.014955669641494751 -1769682161,675553024,0.0,0.0,0.0,1.0,-0.0007580025121569633,0.001593131455592811,-0.005785898305475712,-0.8783257007598877,-0.06288418918848038,-0.016737796366214752 -1769682161,714278912,0.0,0.0,0.0,1.0,-0.0008157361298799515,0.0015534632839262486,-0.005776061210781336,-0.777389407157898,0.030445082113146782,-0.009965423494577408 -1769682161,747735808,0.0,0.0,0.0,1.0,-0.0014215308474376798,0.0015171511331573129,-0.006100723519921303,-0.8528034687042236,0.01832101121544838,-0.004772055894136429 -1769682161,775954432,0.0,0.0,0.0,1.0,-0.0013527884148061275,0.0014341046335175633,-0.006528783589601517,-0.8151845335960388,0.02424418181180954,-0.0008715726435184479 -1769682161,811521536,0.0,0.0,0.0,1.0,-0.0009951035026460886,0.001255142968147993,-0.006876485422253609,-0.8016039133071899,0.18071888387203217,-0.005724164191633463 -1769682161,856526592,0.0,0.0,0.0,1.0,-0.0007609731983393431,0.0011334255104884505,-0.007232035044580698,-0.8649762868881226,0.09315858781337738,-0.0003214208409190178 -1769682161,878107136,0.0,0.0,0.0,1.0,-0.0005431421450339258,0.0010194422211498022,-0.007426234427839518,-0.9146654009819031,0.16213367879390717,-0.008070550858974457 -1769682161,909550336,0.0,0.0,0.0,1.0,-0.0003477564314380288,0.001052785199135542,-0.007572769653052092,-0.8394253849983215,0.17411039769649506,-0.0037850700318813324 -1769682161,941739776,0.0,0.0,0.0,1.0,-0.00022238900419324636,0.0009456663392484188,-0.007668609265238047,-0.7653223872184753,-0.04608273506164551,-0.007591518573462963 -1769682161,979170304,0.0,0.0,0.0,1.0,-5.9740115830209106e-05,0.0009626414394006133,-0.007713249418884516,-0.8272494673728943,0.09819440543651581,-0.011977721937000751 -1769682162,10360576,0.0,0.0,0.0,1.0,-1.2158314348198473e-05,0.0010632907506078482,-0.007709328085184097,-0.7641273736953735,0.18548962473869324,-0.012655971571803093 -1769682162,53700352,0.0,0.0,0.0,1.0,5.274525028653443e-05,0.001285294070839882,-0.007666194811463356,-0.7896474599838257,0.1038513034582138,-0.011668921448290348 -1769682162,75665152,0.0,0.0,0.0,1.0,1.4435267075896263e-05,0.0014280390460044146,-0.0076310099102556705,-0.8771829009056091,0.1667458415031433,-0.013851266354322433 -1769682162,112307968,0.0,0.0,0.0,1.0,2.4833469069562852e-05,0.0014835592592135072,-0.0075952280312776566,-0.8781828880310059,-0.06547968089580536,-0.01126093603670597 -1769682162,149822464,0.0,0.0,0.0,1.0,-1.45820522448048e-05,0.0015119879972189665,-0.0075546507723629475,-0.9149191379547119,0.16014885902404785,-0.014322157017886639 -1769682162,176649216,0.0,0.0,0.0,1.0,-9.031332592712715e-05,0.0014589494094252586,-0.007545784115791321,-0.8659285306930542,-0.1411740481853485,-0.00637722946703434 -1769682162,209404160,0.0,0.0,0.0,1.0,-0.0001551439636386931,0.0014341569039970636,-0.007557877339422703,-0.8404697179794312,-0.060014642775058746,-0.012200389988720417 -1769682162,258108672,0.0,0.0,0.0,1.0,-0.00029339350294321775,0.0015238530468195677,-0.0076224119402468204,-0.8028526306152344,-0.05405121296644211,-0.008289564400911331 -1769682162,275353600,0.0,0.0,0.0,1.0,-0.00035086809657514095,0.001616929192095995,-0.007705167401582003,-0.8028861284255981,-0.05417707562446594,-0.004752928391098976 -1769682162,309299456,0.0,0.0,0.0,1.0,-0.00039430143078789115,0.0017577775288373232,-0.007792241405695677,-0.80274897813797,-0.05452105402946472,-0.014329960569739342 -1769682162,342826496,0.0,0.0,0.0,1.0,-0.00036362773971632123,0.001724769244901836,-0.007875461131334305,-0.7523083090782166,0.10838595032691956,-0.005664650350809097 -1769682162,377436672,0.0,0.0,0.0,1.0,-0.00031517507159151137,0.0017578614642843604,-0.007937795482575893,-0.7522956132888794,0.10809188336133957,-0.009291717782616615 -1769682162,409417984,0.0,0.0,0.0,1.0,-0.00025477143935859203,0.0016930015990510583,-0.007962573319673538,-0.7523361444473267,0.10792902857065201,-0.00813792273402214 -1769682162,442238208,0.0,0.0,0.0,1.0,2.2480337065644562e-05,0.0016685024602338672,-0.007904610596597195,-0.827726423740387,0.09543579816818237,-0.001818726770579815 -1769682162,476042496,0.0,0.0,0.0,1.0,0.0002709499094635248,0.0019085892708972096,-0.007764854468405247,-0.7148409485816956,0.11384013295173645,-0.001872178167104721 -1769682162,510500608,0.0,0.0,0.0,1.0,0.00035226071486249566,0.0020392832811921835,-0.007655438967049122,-0.7651533484458923,-0.04938994720578194,-0.004680939018726349 -1769682162,546671104,0.0,0.0,0.0,1.0,0.0004134011687710881,0.002235610270872712,-0.00750765623524785,-0.7272517085075378,0.1885554939508438,-0.012919225730001926 -1769682162,576454912,0.0,0.0,0.0,1.0,0.00048166769556701183,0.0023645395413041115,-0.007398384157568216,-0.7274496555328369,-0.043595027178525925,-0.00796589907258749 -1769682162,612176896,0.0,0.0,0.0,1.0,0.0003928050573449582,0.0024480235297232866,-0.007149655371904373,-0.7399678826332092,0.03151603788137436,-0.00823622290045023 -1769682162,655802112,0.0,0.0,0.0,1.0,-0.0004866388626396656,0.0023225615732371807,-0.00647300248965621,-0.7274962663650513,0.1881789267063141,-0.004750002175569534 -1769682162,675998976,0.0,0.0,0.0,1.0,-0.0002787906851153821,0.002238721353933215,-0.006118927616626024,-0.6271088123321533,0.050023287534713745,-0.007104816380888224 -1769682162,710652672,0.0,0.0,0.0,1.0,-4.4826309022028e-05,0.0022230870090425014,-0.005847890395671129,-0.6397000551223755,0.125147745013237,-0.0085563063621521 -1769682162,755264512,0.0,0.0,0.0,1.0,0.0001614447101019323,0.0021198911126703024,-0.005643147975206375,-0.7399905920028687,0.030921142548322678,-0.00845289509743452 -1769682162,776619520,0.0,0.0,0.0,1.0,9.434394451091066e-05,0.0018605772638693452,-0.00551575468853116,-0.6147647500038147,-0.02531563490629196,0.009667462669312954 -1769682162,811321856,0.0,0.0,0.0,1.0,6.975882570259273e-05,0.0016216833610087633,-0.0054674306884408,-0.6145930886268616,-0.025612428784370422,-0.0022816569544374943 -1769682162,844782080,0.0,0.0,0.0,1.0,-1.991372846532613e-05,0.0015228504780679941,-0.005426166113466024,-0.6146717071533203,-0.02564837411046028,0.0036398638039827347 -1769682162,875442176,0.0,0.0,0.0,1.0,-6.298333028098568e-05,0.0014407006092369556,-0.005418868735432625,-0.5771355032920837,-0.019327275454998016,0.010002480819821358 -1769682162,911482112,0.0,0.0,0.0,1.0,-0.00016587512800469995,0.0013589411973953247,-0.005422886461019516,-0.576928973197937,-0.019655855372548103,-0.004323073662817478 -1769682162,946858240,0.0,0.0,0.0,1.0,-0.0002794662432279438,0.0013837686274200678,-0.005450139287859201,-0.5894799828529358,0.055324748158454895,-0.01291903667151928 -1769682162,975545344,0.0,0.0,0.0,1.0,-0.00037178999627940357,0.0014667947543784976,-0.005494044162333012,-0.6271873712539673,0.048981837928295135,-0.007421172223985195 -1769682163,8795136,0.0,0.0,0.0,1.0,-0.0004008224350400269,0.001515862881205976,-0.005562473088502884,-0.6144611239433289,-0.026399999856948853,-0.009610050357878208 -1769682163,43649280,0.0,0.0,0.0,1.0,-0.0005311195272952318,0.0015186475357040763,-0.00564215611666441,-0.5393372178077698,-0.013673773035407066,-0.0016083726659417152 -1769682163,77342208,0.0,0.0,0.0,1.0,-0.00057290616678074,0.0017152511281892657,-0.005761381238698959,-0.6022471189498901,0.13013030588626862,-0.013255033642053604 -1769682163,110965760,0.0,0.0,0.0,1.0,-0.0005599395371973515,0.0016744142631068826,-0.005857476033270359,-0.6398429870605469,0.12361494451761246,-0.016111299395561218 -1769682163,153979136,0.0,0.0,0.0,1.0,-0.0005877145449630916,0.0016832815017551184,-0.005947848781943321,-0.57667475938797,-0.020656203851103783,-0.020023465156555176 -1769682163,176257280,0.0,0.0,0.0,1.0,-0.0005633727414533496,0.0016348038334399462,-0.006054189056158066,-0.5392378568649292,-0.014213517308235168,-0.007695662789046764 -1769682163,209610496,0.0,0.0,0.0,1.0,-0.0002546348259784281,0.0014571479987353086,-0.0060841417871415615,-0.614303469657898,-0.027254652231931686,-0.01815684512257576 -1769682163,243628032,0.0,0.0,0.0,1.0,-0.000410643988288939,0.0008375300676561892,-0.006130750756710768,-0.5390558242797852,-0.014604141935706139,-0.019656043499708176 -1769682163,276455936,0.0,0.0,0.0,1.0,-0.001062421128153801,0.0004695880925282836,-0.006171675864607096,-0.5015558004379272,-0.008210280910134315,-0.012065542861819267 -1769682163,309186560,0.0,0.0,0.0,1.0,-0.0012944991467520595,0.00024128436052706093,-0.006187403108924627,-0.5648760795593262,0.13576962053775787,-0.009374682791531086 -1769682163,342603264,0.0,0.0,0.0,1.0,-0.0014447165885940194,0.0003444249741733074,-0.0061923181638121605,-0.5393111109733582,-0.014646753668785095,-0.0018036412075161934 -1769682163,375701504,0.0,0.0,0.0,1.0,-0.0016138864448294044,0.0005243952036835253,-0.006214323453605175,-0.6143968105316162,-0.027761992067098618,-0.009876308962702751 -1769682163,411350528,0.0,0.0,0.0,1.0,-0.001778070698492229,0.0005738787003792822,-0.006247655022889376,-0.526405930519104,-0.09010837227106094,-0.00281454436480999 -1769682163,447958272,0.0,0.0,0.0,1.0,-0.0015569370007142425,0.00044903988600708544,-0.006317235995084047,-0.46414628624916077,-0.002079365774989128,0.001462956890463829 -1769682163,476761600,0.0,0.0,0.0,1.0,-0.0015040229773148894,0.0002865884162019938,-0.006376965902745724,-0.5275856852531433,0.14179861545562744,0.0018040603026747704 -1769682163,510808320,0.0,0.0,0.0,1.0,-0.0014359810156747699,9.482588211540133e-05,-0.0064263660460710526,-0.5768340826034546,-0.02174408733844757,-0.005879205651581287 -1769682163,555416832,0.0,0.0,0.0,1.0,-0.0014061152469366789,-7.715322863077745e-05,-0.0064777652733027935,-0.5392208695411682,-0.01540299691259861,-0.006612725555896759 -1769682163,577616384,0.0,0.0,0.0,1.0,-0.0013068746775388718,-0.00012892359518446028,-0.0065137348137795925,-0.5781227946281433,0.21005764603614807,-0.005969801917672157 -1769682163,610949632,0.0,0.0,0.0,1.0,-0.0012544175842776895,-3.911772000719793e-05,-0.006533897016197443,-0.5145851373672485,0.06601300835609436,-0.0075238426215946674 -1769682163,643593472,0.0,0.0,0.0,1.0,-0.0012070519151166081,2.8242509870324284e-05,-0.006541495211422443,-0.5391751527786255,-0.01579107530415058,-0.008995387703180313 -1769682163,675608064,0.0,0.0,0.0,1.0,-0.0011706540826708078,0.0001243729202542454,-0.006552832201123238,-0.42655736207962036,0.003733946941792965,0.001916572917252779 -1769682163,712371200,0.0,0.0,0.0,1.0,-0.0011724622454494238,8.118122059386224e-05,-0.006567355245351791,-0.5015836954116821,-0.009524606168270111,-0.008539799600839615 -1769682163,753704192,0.0,0.0,0.0,1.0,-0.0011585257016122341,0.00010276269313180819,-0.006596648134291172,-0.45250949263572693,0.15374861657619476,-0.00795633252710104 -1769682163,775596544,0.0,0.0,0.0,1.0,-0.0011852442985400558,8.485859871143475e-05,-0.006636333651840687,-0.6028107404708862,0.12748195230960846,-0.013372072950005531 -1769682163,809041664,0.0,0.0,0.0,1.0,-0.0011892432812601328,2.4242148356279358e-05,-0.006688780151307583,-0.49018609523773193,0.14706751704216003,-0.006025045644491911 -1769682163,856577024,0.0,0.0,0.0,1.0,-0.0010771648958325386,-4.278882988728583e-05,-0.006731611676514149,-0.47709333896636963,0.07172849029302597,-0.00824166089296341 -1769682163,876927488,0.0,0.0,0.0,1.0,-0.00044805766083300114,0.00024283073435071856,-0.006690955255180597,-0.46413862705230713,-0.0033890996128320694,0.0014500156976282597 -1769682163,911387392,0.0,0.0,0.0,1.0,-0.0002528082113713026,0.0005290094413794577,-0.006671932991594076,-0.53923499584198,-0.0166630856692791,-0.0030565056949853897 -1769682163,942848768,0.0,0.0,0.0,1.0,-8.267927478300408e-05,0.0007808717782609165,-0.006665165536105633,-0.3890250623226166,0.009602900594472885,0.004744383972138166 -1769682163,979561984,0.0,0.0,0.0,1.0,8.298175816889852e-05,0.0008768460829742253,-0.006654265336692333,-0.3889201879501343,0.009389678947627544,-0.002419534604996443 -1769682164,9308928,0.0,0.0,0.0,1.0,0.00024962436873465776,0.000925998785533011,-0.006644933018833399,-0.4773305058479309,0.0713840052485466,0.00243908679112792 -1769682164,43095296,0.0,0.0,0.0,1.0,0.00031285645673051476,0.0009045096230693161,-0.0066205356270074844,-0.47723671793937683,0.07117940485477448,-0.004725465551018715 -1769682164,76694016,0.0,0.0,0.0,1.0,0.0007686585304327309,0.001256820047274232,-0.006532786879688501,-0.4767133891582489,0.07050482928752899,-0.04050110653042793 -1769682164,110758400,0.0,0.0,0.0,1.0,0.0003036504494957626,0.0017704092897474766,-0.006584209389984608,-0.46369823813438416,-0.004536069929599762,-0.027251994237303734 -1769682164,155156736,0.0,0.0,0.0,1.0,-0.00028644141275435686,0.0019730564672499895,-0.006694176234304905,-0.4637860655784607,-0.004567814990878105,-0.02132834494113922 -1769682164,175862528,0.0,0.0,0.0,1.0,-0.0005907425074838102,0.0020025111734867096,-0.00676204776391387,-0.36448338627815247,0.09049998223781586,-0.011753003112971783 -1769682164,212357632,0.0,0.0,0.0,1.0,-0.0008494466310366988,0.0019784746691584587,-0.0068247136659920216,-0.3512977957725525,0.015359691344201565,-0.006842303555458784 -1769682164,262918400,0.0,0.0,0.0,1.0,-0.0011364953825250268,0.0019819794688373804,-0.006879067048430443,-0.375619500875473,-0.06646578758955002,-0.003613571636378765 -1769682164,270338048,0.0,0.0,0.0,1.0,-0.0011924866121262312,0.0019523182418197393,-0.006897089537233114,-0.38888099789619446,0.008579862304031849,-0.006173359230160713 -1769682164,309353472,0.0,0.0,0.0,1.0,-0.0013084992533549666,0.0018643002258613706,-0.006901775952428579,-0.4023975133895874,0.08378387987613678,0.005558814853429794 -1769682164,356066048,0.0,0.0,0.0,1.0,-0.001389218377880752,0.0017273545963689685,-0.006909836083650589,-0.38894030451774597,0.00844663381576538,-0.0026473423931747675 -1769682164,377538816,0.0,0.0,0.0,1.0,-0.001468057045713067,0.001614249194972217,-0.006926367059350014,-0.40232613682746887,0.08348070830106735,-0.0016318331472575665 -1769682164,409995008,0.0,0.0,0.0,1.0,-0.0008569895289838314,0.0013077298644930124,-0.006915834732353687,-0.30267083644866943,0.17821089923381805,-0.025346368551254272 -1769682164,442960640,0.0,0.0,0.0,1.0,-0.0007792902179062366,-0.000654428091365844,-0.006951992865651846,-0.27510592341423035,0.027142208069562912,-0.07629681378602982 -1769682164,476155648,0.0,0.0,0.0,1.0,-0.0013823258923366666,-0.003137111198157072,-0.00716059748083353,-0.2888374924659729,0.10246778279542923,-0.05734481289982796 -1769682164,511838464,0.0,0.0,0.0,1.0,-0.0029238914139568806,-0.003524068044498563,-0.007307406049221754,-0.38874563574790955,0.007787960581481457,-0.015723956748843193 -1769682164,544265472,0.0,0.0,0.0,1.0,-0.003681435016915202,-0.0035554049536585808,-0.007467878982424736,-0.4023658037185669,0.08297013491392136,-0.00508234603330493 -1769682164,575891968,0.0,0.0,0.0,1.0,-0.004358806647360325,-0.003193847369402647,-0.007658978458493948,-0.35146552324295044,0.014567623846232891,0.0015363171696662903 -1769682164,610269440,0.0,0.0,0.0,1.0,-0.0046604895032942295,-0.0029052793979644775,-0.007765389047563076,-0.41311874985694885,-0.07405272126197815,0.004293815698474646 -1769682164,654122240,0.0,0.0,0.0,1.0,-0.004618215840309858,-0.0026362547650933266,-0.007833384908735752,-0.3412863314151764,0.17163236439228058,0.023366328328847885 -1769682164,676713472,0.0,0.0,0.0,1.0,-0.0041054654866456985,-0.0027484025340527296,-0.007814913056790829,-0.38930389285087585,0.007797899655997753,0.020238976925611496 -1769682164,709171968,0.0,0.0,0.0,1.0,-0.003935021813958883,-0.0028243325650691986,-0.007758596912026405,-0.300625205039978,-0.053888797760009766,0.01770024374127388 -1769682164,759457280,0.0,0.0,0.0,1.0,-0.003780794097110629,-0.0029389928095042706,-0.007646163925528526,-0.32748478651046753,0.09594101458787918,-0.0002540759742259979 -1769682164,775676928,0.0,0.0,0.0,1.0,-0.003749309340491891,-0.002993649570271373,-0.0075743068009614944,-0.37873655557632446,0.16425441205501556,0.006431973539292812 -1769682164,809622272,0.0,0.0,0.0,1.0,-0.0037293084897100925,-0.003040374955162406,-0.007560060825198889,-0.2763890326023102,0.0275138970464468,0.0003193402662873268 -1769682164,842489600,0.0,0.0,0.0,1.0,-0.003826239611953497,-0.0030810039024800062,-0.007610963191837072,-0.28998398780822754,0.10249593108892441,-0.0020582969300448895 -1769682164,878385152,0.0,0.0,0.0,1.0,-0.003925622440874577,-0.0030616282019764185,-0.007810284849256277,-0.3376592993736267,-0.06149525195360184,-0.011240663938224316 -1769682164,911522560,0.0,0.0,0.0,1.0,-0.003888135775923729,-0.0030795475468039513,-0.007993103004992008,-0.3649752736091614,0.08856519311666489,-0.01121489517390728 -1769682164,943884800,0.0,0.0,0.0,1.0,-0.0037148213014006615,-0.0030872044153511524,-0.008121584542095661,-0.37522628903388977,-0.06843255460262299,-0.00687397550791502 -1769682164,976642816,0.0,0.0,0.0,1.0,-0.0032626113388687372,-0.0030444436706602573,-0.008059676736593246,-0.3411942720413208,0.17025983333587646,-0.011838099919259548 -1769682165,9591808,0.0,0.0,0.0,1.0,-0.0030958240386098623,-0.0030356207862496376,-0.007902717217803001,-0.3378252685070038,-0.061662521213293076,0.003167350310832262 -1769682165,44208640,0.0,0.0,0.0,1.0,-0.0013792896643280983,-0.0024085708428174257,-0.007469911593943834,-0.2667207419872284,0.1842847764492035,0.023691197857260704 -1769682165,76607488,0.0,0.0,0.0,1.0,-0.0007443787762895226,-0.001531506422907114,-0.007202445063740015,-0.2905104458332062,0.10225902497768402,0.022047685459256172 -1769682165,110890752,0.0,0.0,0.0,1.0,-0.0005486602894961834,-0.0010360132437199354,-0.007268731482326984,-0.3654998540878296,0.0883573591709137,0.01641997881233692 -1769682165,162347264,0.0,0.0,0.0,1.0,-0.0005063547869212925,-0.0004940153448842466,-0.007583539932966232,-0.3040321469306946,0.17684930562973022,-0.0017229632940143347 -1769682165,170248960,0.0,0.0,0.0,1.0,0.0013234992511570454,0.000570921169128269,-0.007777785882353783,-0.27916219830513,0.2576560080051422,-0.08706586807966232 -1769682165,210109696,0.0,0.0,0.0,1.0,0.0005543706938624382,0.003769758390262723,-0.008350932970643044,-0.3635079860687256,0.08620043098926544,-0.13021396100521088 -1769682165,255856128,0.0,0.0,0.0,1.0,-7.254682714119554e-05,0.004924653563648462,-0.008899158798158169,-0.31327831745147705,0.01901843398809433,-0.05000215396285057 -1769682165,276459008,0.0,0.0,0.0,1.0,-0.0010055641178041697,0.005107959732413292,-0.009414002299308777,-0.31351566314697266,0.0191165953874588,-0.03337925300002098 -1769682165,309561600,0.0,0.0,0.0,1.0,-0.001405032817274332,0.004867939744144678,-0.009522601962089539,-0.24854280054569244,-0.12376667559146881,-0.009202747605741024 -1769682165,342290688,0.0,0.0,0.0,1.0,-0.0016991740558296442,0.004426772706210613,-0.009450332261621952,-0.27669745683670044,0.026491854339838028,0.0134792011231184 -1769682165,378989568,0.0,0.0,0.0,1.0,-0.002193617634475231,0.0038745494093745947,-0.00918230414390564,-0.2905600070953369,0.10131402313709259,0.006327054928988218 -1769682165,410054400,0.0,0.0,0.0,1.0,-0.002548744436353445,0.003555646166205406,-0.008926316164433956,-0.23921941220760345,0.0332990437746048,0.013882705941796303 -1769682165,442748928,0.0,0.0,0.0,1.0,-0.002959056757390499,0.003233501221984625,-0.008690424263477325,-0.28630122542381287,-0.130716472864151,0.0175684355199337 -1769682165,475763712,0.0,0.0,0.0,1.0,-0.002227810909971595,0.00238381652161479,-0.008381756953895092,-0.1919722855091095,0.1969148814678192,-0.006531083956360817 -1769682165,509173504,0.0,0.0,0.0,1.0,-0.003078098176047206,0.0007156070787459612,-0.008303440175950527,-0.17273083329200745,-0.11064644902944565,-0.047786083072423935 -1769682165,547447552,0.0,0.0,0.0,1.0,-0.0036819877568632364,-0.001087127486243844,-0.008283407427370548,-0.2150929868221283,0.11444772034883499,-0.03446507453918457 -1769682165,577341184,0.0,0.0,0.0,1.0,-0.0038732204120606184,-0.001954005565494299,-0.00828783493489027,-0.0887901559472084,0.06069795787334442,-0.018765587359666824 -1769682165,611275008,0.0,0.0,0.0,1.0,-0.005307525862008333,-0.0016167826252058148,-0.008208706974983215,-0.187650665640831,-0.0350792296230793,0.011880803853273392 -1769682165,657730816,0.0,0.0,0.0,1.0,-0.006624779663980007,-0.0005154252285137773,-0.00810975395143032,-0.2908990979194641,0.10072866082191467,0.013521015644073486 -1769682165,676894720,0.0,0.0,0.0,1.0,-0.007117425557225943,0.00027130296803079545,-0.007987791672348976,-0.22531120479106903,-0.042113229632377625,0.024496031925082207 -1769682165,712371712,0.0,0.0,0.0,1.0,-0.007464882917702198,0.0008990527130663395,-0.007811825256794691,-0.2717929780483246,-0.20639070868492126,0.013678174465894699 -1769682165,742850560,0.0,0.0,0.0,1.0,-0.007125025615096092,0.0011411166051402688,-0.007613632827997208,-0.17882178723812103,0.12198491394519806,0.0341150127351284 -1769682165,777608192,0.0,0.0,0.0,1.0,-0.005509723909199238,0.0001716955448500812,-0.007273080758750439,-0.2307562530040741,0.18994663655757904,0.048128388822078705 -1769682165,809892352,0.0,0.0,0.0,1.0,-0.00513392174616456,-0.0004177790542598814,-0.006990405265241861,-0.1788662075996399,0.12186800688505173,0.032968536019325256 -1769682165,843491072,0.0,0.0,0.0,1.0,-0.004866827744990587,-0.0009310319437645376,-0.006697865668684244,-0.2769891619682312,0.02545858733355999,0.02534361556172371 -1769682165,876230144,0.0,0.0,0.0,1.0,-0.004605609457939863,-0.0013499900233000517,-0.006360653322190046,-0.173307865858078,-0.11044681072235107,0.010421141982078552 -1769682165,911861248,0.0,0.0,0.0,1.0,-0.004468039143830538,-0.0014903368428349495,-0.006156382616609335,-0.3050479292869568,0.1749197244644165,-0.006347373127937317 -1769682165,951873024,0.0,0.0,0.0,1.0,-0.004340853542089462,-0.001521546975709498,-0.005949776154011488,-0.18711544573307037,-0.03585111349821091,-0.01795838586986065 -1769682165,976180224,0.0,0.0,0.0,1.0,-0.004276338964700699,-0.0014232967514544725,-0.005828479304909706,-0.1640295386314392,0.046273473650217056,-0.011250724084675312 -1769682166,12111104,0.0,0.0,0.0,1.0,-0.004190846346318722,-0.0013185404241085052,-0.005728582385927439,-0.11231253296136856,-0.021515201777219772,-0.00743375439196825 -1769682166,57573376,0.0,0.0,0.0,1.0,-0.004096346907317638,-0.0011362789664417505,-0.005612263455986977,-0.17839539051055908,0.12116783857345581,-0.009755030274391174 -1769682166,76644608,0.0,0.0,0.0,1.0,-0.004088306799530983,-0.0010495830792933702,-0.005535869859158993,-0.20153918862342834,0.03902895748615265,-0.010510105639696121 -1769682166,109432576,0.0,0.0,0.0,1.0,-0.0024330243468284607,-0.00044371423427946866,-0.0052162641659379005,-0.28256380558013916,0.2569516599178314,0.023260965943336487 -1769682166,142842880,0.0,0.0,0.0,1.0,-0.0010167966829612851,0.0005980697460472584,-0.0048118093982338905,-0.2395268827676773,0.032104238867759705,0.023573026061058044 -1769682166,178259968,0.0,0.0,0.0,1.0,0.0013470925623551011,0.002351425588130951,-0.004246612545102835,-0.20111329853534698,0.038660384714603424,-0.040312476456165314 -1769682166,210165504,0.0,0.0,0.0,1.0,0.0010513520101085305,0.004655926022678614,-0.003998953849077225,-0.20046821236610413,0.0382419191300869,-0.08324620127677917 -1769682166,244194560,0.0,0.0,0.0,1.0,0.0011722285998985171,0.006278160959482193,-0.0038159366231411695,-0.14883914589881897,-0.02937990427017212,-0.06756936758756638 -1769682166,275887360,0.0,0.0,0.0,1.0,0.0013528093695640564,0.0075757806189358234,-0.0036128368228673935,-0.09722784161567688,-0.09697066992521286,-0.049495477229356766 -1769682166,315855872,0.0,0.0,0.0,1.0,-0.00038147770101204515,0.006909905467182398,-0.003850232344120741,-0.11291845887899399,-0.02130931243300438,0.03180672600865364 -1769682166,351070976,0.0,0.0,0.0,1.0,-0.0017984252190217376,0.005736333318054676,-0.0040663150139153,-0.14164011180400848,0.12846270203590393,0.02517530880868435 -1769682166,376494080,0.0,0.0,0.0,1.0,-0.0025888823438435793,0.00483636325225234,-0.004168617073446512,-0.029392065480351448,0.15014231204986572,0.03273569419980049 -1769682166,410078464,0.0,0.0,0.0,1.0,-0.0032611428759992123,0.004046821966767311,-0.004231714177876711,-0.03801518306136131,-0.006908045150339603,0.03402135521173477 -1769682166,464984064,0.0,0.0,0.0,1.0,-0.003981377929449081,0.003409869270399213,-0.004288132302463055,-0.08965679258108139,0.060626909136772156,0.017070021480321884 -1769682166,474541312,0.0,0.0,0.0,1.0,-0.004130843561142683,0.0031549890991300344,-0.004301147535443306,-0.023182310163974762,-0.08204344660043716,0.011069314554333687 -1769682166,512136960,0.0,0.0,0.0,1.0,-0.004518859554082155,0.0027528521604835987,-0.004316735081374645,-0.12680983543395996,0.05319993197917938,-0.0025593785103410482 -1769682166,542514688,0.0,0.0,0.0,1.0,-0.0047194622457027435,0.002517831977456808,-0.004300288390368223,-0.11232831329107285,-0.021730640903115273,-0.0028791804797947407 -1769682166,576350464,0.0,0.0,0.0,1.0,-0.004787826910614967,0.00245875446125865,-0.004243103321641684,-0.023046931251883507,-0.08210922032594681,0.0050616804510355 -1769682166,609650176,0.0,0.0,0.0,1.0,-0.004805244039744139,0.0024744272232055664,-0.004171764478087425,-0.13509760797023773,-0.10400162637233734,-0.013352228328585625 -1769682166,656708352,0.0,0.0,0.0,1.0,-0.005526945926249027,0.0030300936195999384,-0.004019086714833975,-0.20223671197891235,0.03884858638048172,0.026074806228280067 -1769682166,676175872,0.0,0.0,0.0,1.0,-0.006664360407739878,0.004076065495610237,-0.00391496904194355,-0.18750937283039093,-0.036178283393383026,0.013774657621979713 -1769682166,709392128,0.0,0.0,0.0,1.0,-0.007220033556222916,0.004855610430240631,-0.003821380203589797,-0.07509297877550125,-0.01444176584482193,0.010740713216364384 -1769682166,758537216,0.0,0.0,0.0,1.0,-0.007726337295025587,0.0055871400982141495,-0.003704652888700366,-0.09790127724409103,-0.09666352719068527,0.004954133648425341 -1769682166,779422976,0.0,0.0,0.0,1.0,-0.007340569980442524,0.0056134182959795,-0.0036234380677342415,-0.052504636347293854,0.06782454252243042,0.028411991894245148 -1769682166,809553920,0.0,0.0,0.0,1.0,-0.0055124182254076,0.004496837500482798,-0.003508550813421607,-0.015666360035538673,0.07531949132680893,0.0624031126499176 -1769682166,854607616,0.0,0.0,0.0,1.0,-0.00486297532916069,0.0034973390866070986,-0.00337401544675231,-0.0008716502343304455,0.0003244361432734877,0.04886699095368385 -1769682166,877079040,0.0,0.0,0.0,1.0,-0.004349110182374716,0.0025321238208562136,-0.0032029615249484777,-0.06708110123872757,0.14267177879810333,0.0264902226626873 -1769682166,911685120,0.0,0.0,0.0,1.0,-0.004067393019795418,0.0020273143891245127,-0.0030853995122015476,-0.0003221451479475945,0.00011315470328554511,0.01787814311683178 -1769682166,943845632,0.0,0.0,0.0,1.0,-0.003793917130678892,0.0017660618759691715,-0.002983746351674199,-0.20181001722812653,0.0384286604821682,-0.001501716673374176 -1769682166,975826688,0.0,0.0,0.0,1.0,-0.00357620557770133,0.001689854427240789,-0.0028851255774497986,-0.07463596761226654,-0.01467641070485115,-0.014380590058863163 -1769682167,11520256,0.0,0.0,0.0,1.0,-0.0034340268466621637,0.0017342400969937444,-0.0028331985231488943,-0.0746990293264389,-0.014659985899925232,-0.010810328647494316 -1769682167,46946816,0.0,0.0,0.0,1.0,-0.0032944672275334597,0.001914431806653738,-0.0027734648901969194,-0.014383482746779919,0.07481108605861664,-0.012621347792446613 -1769682167,77246976,0.0,0.0,0.0,1.0,-0.0032126714941114187,0.0020486919675022364,-0.002722674049437046,-0.0893457755446434,0.060221005231142044,-0.009136153385043144 -1769682167,109429248,0.0,0.0,0.0,1.0,-0.0031827047932893038,0.00217655161395669,-0.0026667332276701927,-0.07464902102947235,-0.014690348878502846,-0.013213624246418476 -1769682167,217231872,0.0,0.0,0.0,1.0,-0.0013654838548973203,0.0028792640659958124,-0.0023633583914488554,-0.19377215206623077,0.19542157649993896,0.00487535772845149 -1769682167,220579840,0.0,0.0,0.0,1.0,-0.00045204622438177466,0.0038915425539016724,-0.002051328308880329,-0.25402525067329407,0.10589753091335297,0.0042307013645768166 -1769682167,226676992,0.0,0.0,0.0,1.0,7.517868652939796e-05,0.004739917349070311,-0.0018191785784438252,0.04556039720773697,0.1644030213356018,0.0023340131156146526 -1769682167,254429184,0.0,0.0,0.0,1.0,0.0005333846202120185,0.005614612251520157,-0.0015773222548887134,-0.014612008817493916,0.07486749440431595,-0.0018819349352270365 -1769682167,273146624,0.0,0.0,0.0,1.0,0.0006889168871566653,0.005839545279741287,-0.0014726393856108189,-0.10415894538164139,0.13510675728321075,-0.0015398970572277904 -1769682167,310509312,0.0,0.0,0.0,1.0,0.0008799507631920278,0.005803621374070644,-0.0014080816181376576,0.014295713976025581,-0.07477343082427979,0.018576467409729958 -1769682167,359696128,0.0,0.0,0.0,1.0,-0.0010711848735809326,0.004473377019166946,-0.0016315956600010395,-0.015458681620657444,0.07510283589363098,0.04101461544632912 -1769682167,377048320,0.0,0.0,0.0,1.0,-0.001855578157119453,0.0036442074924707413,-0.0017549627227708697,0.01390089001506567,-0.07466187328100204,0.03883732482790947 -1769682167,410203648,0.0,0.0,0.0,1.0,-0.0024382115807384253,0.003000362543389201,-0.0018619340844452381,-0.06079280748963356,-0.0893726721405983,0.029094483703374863 -1769682167,467393792,0.0,0.0,0.0,1.0,-0.003583241254091263,0.0027587024960666895,-0.002000966342166066,-0.1354336440563202,-0.10410720854997635,0.016943534836173058 -1769682167,477257472,0.0,0.0,0.0,1.0,-0.0036876623053103685,0.0030664587393403053,-0.0020796076860278845,-0.0605488158762455,-0.08944973349571228,0.017142916098237038 -1769682167,509556480,0.0,0.0,0.0,1.0,-0.0038713624235242605,0.0034191987942904234,-0.0021383774001151323,-0.08961862325668335,0.060213398188352585,0.002670829650014639 -1769682167,547389696,0.0,0.0,0.0,1.0,-0.00404520146548748,0.003884057281538844,-0.0021958330180495977,-0.04543253779411316,-0.1644352525472641,-0.0036866015288978815 -1769682167,576566528,0.0,0.0,0.0,1.0,-0.004064346197992563,0.004097500815987587,-0.00221582711674273,-0.134928897023201,-0.1042674109339714,-0.007007707841694355 -1769682167,610753536,0.0,0.0,0.0,1.0,-0.004068632144480944,0.00423116609454155,-0.002221789676696062,-0.08926805108785629,0.06010933965444565,-0.015217777341604233 -1769682167,648685824,0.0,0.0,0.0,1.0,-0.004053088836371899,0.004375915974378586,-0.0022026814986020327,-0.07465352863073349,-0.014743542298674583,-0.011009180918335915 -1769682167,676137216,0.0,0.0,0.0,1.0,-0.004632193129509687,0.004814072512090206,-0.0021512929815799,0.0746016576886177,0.01475737988948822,0.013405018486082554 -1769682167,710792448,0.0,0.0,0.0,1.0,-0.005033342633396387,0.005329201463609934,-0.0021128992084413767,0.0,-0.0,0.0 -1769682167,768858624,0.0,0.0,0.0,1.0,-0.005315232556313276,0.005723831243813038,-0.002052894327789545,-0.14981751143932343,-0.029407808557152748,0.0029184133745729923 -1769682167,778128128,0.0,0.0,0.0,1.0,-0.005437388084828854,0.005817799363285303,-0.002006582682952285,-0.014837566763162613,0.07488280534744263,0.005358502268791199 -1769682167,811493120,0.0,0.0,0.0,1.0,-0.004189607687294483,0.005275044124573469,-0.0019602584652602673,0.11908143013715744,0.1793694645166397,0.05673987790942192 -1769682167,856103424,0.0,0.0,0.0,1.0,-0.0031401782762259245,0.004315107595175505,-0.00189235620200634,0.08850739896297455,-0.05995434522628784,0.05101286992430687 -1769682167,877506816,0.0,0.0,0.0,1.0,-0.0025349583011120558,0.003303953679278493,-0.001806387910619378,0.0887891948223114,-0.059999044984579086,0.0379093773663044 -1769682167,910877952,0.0,0.0,0.0,1.0,-0.0022124131210148335,0.0027831990737468004,-0.001741168787702918,0.0595916211605072,0.08967553079128265,0.024842126294970512 -1769682167,943047168,0.0,0.0,0.0,1.0,-0.001955921994522214,0.0025089909322559834,-0.001684508053585887,-0.0002609193907119334,3.988791286246851e-05,0.011918014846742153 -1769682167,976777728,0.0,0.0,0.0,1.0,-0.00169181649107486,0.002392765134572983,-0.0016024847282096744,-0.16444014012813568,0.04536650329828262,-0.002572131110355258 -1769682168,11204608,0.0,0.0,0.0,1.0,-0.0015406985767185688,0.0024050301872193813,-0.001543649472296238,0.1497538983821869,0.029487665742635727,-0.00036833365447819233 -1769682168,56020736,0.0,0.0,0.0,1.0,-0.00147635443136096,0.002591513330116868,-0.0014756628079339862,0.07488928735256195,0.014746449887752533,-0.0007716465042904019 -1769682168,77156096,0.0,0.0,0.0,1.0,-0.0014240427408367395,0.0027133666444569826,-0.001437220722436905,0.15001600980758667,0.029465997591614723,-0.012256192043423653 -1769682168,109890048,0.0,0.0,0.0,1.0,-0.0018721269443631172,0.0025696614757180214,-0.0014444445259869099,-0.07496794313192368,-0.0147420484572649,0.004333753604441881 -1769682168,157134592,0.0,0.0,0.0,1.0,-0.0014699354069307446,0.002049172529950738,-0.0013608734589070082,-0.00048076806706376374,6.436922558350489e-05,0.021452205255627632 -1769682168,179077888,0.0,0.0,0.0,1.0,-0.0005064751021564007,0.002198742935433984,-0.001191921648569405,-0.0007232292555272579,9.582030907040462e-05,0.03217826038599014 -1769682168,209529344,0.0,0.0,0.0,1.0,-0.00014849923900328577,0.0023468341678380966,-0.0010620483662933111,-0.0005373714375309646,7.078428461682051e-05,0.023835713043808937 -1769682168,257170944,0.0,0.0,0.0,1.0,8.85290646692738e-05,0.002511049620807171,-0.000970628927461803,-0.08999963849782944,0.06013111025094986,0.01567184366285801 -1769682168,293576704,0.0,0.0,0.0,1.0,0.00030598966986872256,0.0026635651011019945,-0.0008741183555684984,0.014603341929614544,-0.07482810318470001,0.007709109224379063 -1769682168,303684096,0.0,0.0,0.0,1.0,0.0003563108912203461,0.002706172876060009,-0.0008391740266233683,-0.07485821843147278,-0.014772357419133186,-0.00046857341658324003 -1769682168,346374400,0.0,0.0,0.0,1.0,-0.0003694793558679521,0.002260560402646661,-0.0009354682406410575,-0.10486200451850891,0.13498196005821228,0.018658239394426346 -1769682168,376543488,0.0,0.0,0.0,1.0,-0.001314275898039341,0.002026849891990423,-0.001072343555279076,0.08889048546552658,-0.059974901378154755,0.03322191536426544 -1769682168,409907456,0.0,0.0,0.0,1.0,-0.0024143022019416094,0.0029234071262180805,-0.0012309896992519498,0.162840336561203,-0.04508000984787941,0.07304264605045319 -1769682168,443264000,0.0,0.0,0.0,1.0,-0.0019626934081315994,0.004328414332121611,-0.001264229416847229,0.013453022576868534,-0.07468539476394653,0.05775870755314827 -1769682168,477034240,0.0,0.0,0.0,1.0,-0.001946854405105114,0.00563841313123703,-0.0013008293462917209,-0.15040621161460876,-0.029492352157831192,0.028761843219399452 -1769682168,510838016,0.0,0.0,0.0,1.0,-0.0019659865647554398,0.006237643305212259,-0.0013140568044036627,-0.015205411240458488,0.07489383220672607,0.017327124252915382 -1769682168,546617088,0.0,0.0,0.0,1.0,-0.0019395059207454324,0.00667197722941637,-0.0013252191711217165,-0.1497635543346405,-0.029581625014543533,0.0012807666789740324 -1769682168,577454336,0.0,0.0,0.0,1.0,-0.0019413980189710855,0.006777158938348293,-0.0013238932006061077,-0.1643247753381729,0.045232582837343216,-0.008831118233501911 -1769682168,609519104,0.0,0.0,0.0,1.0,-0.0018993673147633672,0.006759797688573599,-0.001311499159783125,-0.10415125638246536,0.13485848903656006,-0.013589870184659958 -1769682168,655577856,0.0,0.0,0.0,1.0,-0.0018571612890809774,0.006660859100520611,-0.0012989984825253487,-0.01450574491173029,0.07481443136930466,-0.01246060710400343 -1769682168,676672000,0.0,0.0,0.0,1.0,-0.0016516975592821836,0.006414311472326517,-0.001267155515961349,-0.059549953788518906,-0.08969689160585403,-0.020337572321295738 -1769682168,710137856,0.0,0.0,0.0,1.0,-0.0012639890192076564,0.006068528164178133,-0.0012456398690119386,0.07529420405626297,0.01476784236729145,-0.017241399735212326 -1769682168,743074816,0.0,0.0,0.0,1.0,-0.0010611185571178794,0.005801459774374962,-0.0012072102399542928,0.015163909643888474,-0.07487424463033676,-0.013759144581854343 -1769682168,777195008,0.0,0.0,0.0,1.0,-0.0008288930403068662,0.005523722618818283,-0.0011479404056444764,-0.014688733965158463,0.07483026385307312,-0.005308912601321936 -1769682168,810241792,0.0,0.0,0.0,1.0,-0.0006244897958822548,0.005399668123573065,-0.001111739780753851,-0.014963138848543167,0.07485369592905045,0.005415656603872776 -1769682168,842937344,0.0,0.0,0.0,1.0,0.00043726543663069606,0.004833881743252277,-0.001066129538230598,-0.07545671612024307,-0.01476732362061739,0.023144833743572235 -1769682168,876920064,0.0,0.0,0.0,1.0,0.0009439803543500602,0.004198871087282896,-0.0010028869146481156,0.07410959154367447,0.014888008125126362,0.029302630573511124 -1769682168,910087680,0.0,0.0,0.0,1.0,0.0011678248411044478,0.003989317920058966,-0.0009615203598514199,0.13440987467765808,0.1045311763882637,0.01874164119362831 -1769682168,959227648,0.0,0.0,0.0,1.0,0.0013579399092122912,0.0038757645525038242,-0.0009307434665970504,0.01451151818037033,-0.0748104602098465,0.012477755546569824 -1769682168,976321024,0.0,0.0,0.0,1.0,0.0013903226936236024,0.003778945654630661,-0.0009295697673223913,0.08954375237226486,-0.05999589338898659,0.00606184359639883 -1769682169,10137088,0.0,0.0,0.0,1.0,0.001416108338162303,0.0038211732171475887,-0.0009403029107488692,-0.04528629779815674,-0.16449902951717377,0.0039787860587239265 -1769682169,44687104,0.0,0.0,0.0,1.0,0.0002631771203596145,0.0035226100590080023,-0.0010764304315671325,-0.061557088047266006,-0.08952893316745758,0.05821993947029114 -1769682169,76969984,0.0,0.0,0.0,1.0,0.00035305414348840714,0.002068607835099101,-0.0011689977254718542,0.05748559534549713,0.08990931510925293,0.09551061689853668 -1769682169,110578432,0.0,0.0,0.0,1.0,0.0006436845869757235,0.0005930803599767387,-0.0012015711981803179,-0.002212779363617301,0.0002066650486085564,0.08341696858406067 -1769682169,155267072,0.0,0.0,0.0,1.0,0.0007571160094812512,-0.0007277927361428738,-0.001242071040906012,-0.016385916620492935,0.07498133927583694,0.0578109510242939 -1769682169,176632832,0.0,0.0,0.0,1.0,0.0003406075411476195,-0.0014829738065600395,-0.0013421953190118074,0.014335733838379383,-0.07478638738393784,0.019648294895887375 -1769682169,210090752,0.0,0.0,0.0,1.0,0.0001874240697361529,-0.0019596978090703487,-0.0014215904520824552,0.01456036139279604,-0.07480670511722565,0.011306343600153923 -1769682169,247745536,0.0,0.0,0.0,1.0,8.667960355523974e-05,-0.0021595871075987816,-0.0014805082464590669,-0.014502931386232376,0.0747997835278511,-0.013688812963664532 -1769682169,276593920,0.0,0.0,0.0,1.0,0.00010987000860041007,-0.0020083808340132236,-0.001483044121414423,0.07524606585502625,0.014819378033280373,-0.01475540455430746 -1769682169,309911040,0.0,0.0,0.0,1.0,8.912704652175307e-05,-0.0017658623401075602,-0.001454278128221631,-0.08925580233335495,0.05992747098207474,-0.017994748428463936 -1769682169,361544960,0.0,0.0,0.0,1.0,-0.0025836401619017124,0.0005310585256665945,-0.0014737441670149565,-0.1500808596611023,-0.02969423681497574,0.014029519632458687 -1769682169,370972928,0.0,0.0,0.0,1.0,-0.0008902574772946537,0.0030279578641057014,-0.0013531575677916408,-0.15105023980140686,-0.02960829809308052,0.05096360296010971 -1769682169,409719296,0.0,0.0,0.0,1.0,0.0002294660807820037,0.006925718393176794,-0.0011067544110119343,0.013792406767606735,-0.07473069429397583,0.04109310358762741 -1769682169,457537536,0.0,0.0,0.0,1.0,0.0007019922486506402,0.009268475696444511,-0.0009209210984408855,-0.1801086813211441,0.11997293680906296,0.023496638983488083 -1769682169,476245248,0.0,0.0,0.0,1.0,0.0009384892764501274,0.009991019032895565,-0.0008349494310095906,-0.17969882488250732,0.11993034183979034,0.007949123159050941 -1769682169,510532864,0.0,0.0,0.0,1.0,0.0010862975614145398,0.010194547474384308,-0.0007898716139607131,0.05983252450823784,0.08971896022558212,0.004991532769054174 -1769682169,543004160,0.0,0.0,0.0,1.0,0.0012453144881874323,0.009980258531868458,-0.0007725837058387697,0.07503165304660797,0.01486215740442276,-0.006306638941168785 -1769682169,578462464,0.0,0.0,0.0,1.0,0.0013249145122244954,0.009332308545708656,-0.0007875835872255266,-0.14929719269275665,-0.029799753800034523,-0.01485040970146656 -1769682169,610601472,0.0,0.0,0.0,1.0,0.0013936248142272234,0.008795837871730328,-0.0008152606314979494,0.0002704001381061971,-2.522240174585022e-05,-0.009532882831990719 -1769682169,658249472,0.0,0.0,0.0,1.0,0.001418262254446745,0.008348100818693638,-0.0008368761627934873,0.08974360674619675,-0.0599432997405529,0.0003443891182541847 -1769682169,671581184,0.0,0.0,0.0,1.0,0.0014282335760071874,0.007918767631053925,-0.0008557515102438629,0.06022634357213974,0.08968871831893921,-0.009239980950951576 -1769682169,712993280,0.0,0.0,0.0,1.0,0.0028100900817662477,0.006729878485202789,-0.000888952927198261,0.06064273416996002,0.0896497443318367,-0.023529356345534325 -1769682169,749838336,0.0,0.0,0.0,1.0,0.003665565513074398,0.0057119145058095455,-0.0008723408100195229,0.0006654997705481946,-6.680264777969569e-05,-0.02263990230858326 -1769682169,779448320,0.0,0.0,0.0,1.0,0.004061036743223667,0.005287343170493841,-0.0008231911342591047,-0.029314979910850525,0.14960165321826935,-0.0168295968323946 -1769682169,810822400,0.0,0.0,0.0,1.0,0.004420613870024681,0.00508617190644145,-0.0007529299473389983,-0.014711042866110802,0.07480510324239731,-0.006639431696385145 -1769682169,862137344,0.0,0.0,0.0,1.0,0.004188194405287504,0.005328403785824776,-0.0006375217344611883,0.1350150853395462,0.10459566116333008,-0.007046586833894253 -1769682169,869885184,0.0,0.0,0.0,1.0,0.00412225816398859,0.005542040802538395,-0.0005869626183994114,-0.014640308916568756,0.07479460537433624,-0.009046332910656929 -1769682169,909811712,0.0,0.0,0.0,1.0,0.004051303490996361,0.005925416015088558,-0.00047661582357250154,0.015000339597463608,-0.0748358964920044,-0.0028534485027194023 -1769682169,943474944,0.0,0.0,0.0,1.0,0.003995171282440424,0.006165366154164076,-0.00041327407234348357,0.045004233717918396,0.164553701877594,0.0007554678013548255 -1769682169,976860672,0.0,0.0,0.0,1.0,0.003850708482787013,0.006353511940687895,-0.0003537751908879727,0.06011498346924782,0.08970431238412857,-0.005659664515405893 -1769682170,10596864,0.0,0.0,0.0,1.0,0.0006774709327146411,0.0050156912766397,-0.0005936870002187788,0.02670089341700077,-0.1492493599653244,0.1015971302986145 -1769682170,47559936,0.0,0.0,0.0,1.0,0.0021531658712774515,0.0008363767410628498,-0.0005552704096771777,0.17420554161071777,-0.11914825439453125,0.17284569144248962 -1769682170,76537344,0.0,0.0,0.0,1.0,0.0023296279832720757,-0.0015898029087111354,-0.0005174407851882279,0.07066000252962112,0.015458771958947182,0.1357021927833557 -1769682170,110156032,0.0,0.0,0.0,1.0,0.002414716174826026,-0.0031990897841751575,-0.00047457884647883475,0.1466720551252365,0.030221790075302124,0.09862076491117477 -1769682170,146303232,0.0,0.0,0.0,1.0,0.0025870443787425756,-0.004321044776588678,-0.0003963633789680898,-0.0014994514640420675,0.0002076981181744486,0.04885239526629448 -1769682170,177305856,0.0,0.0,0.0,1.0,0.001819494180381298,-0.004812199156731367,-0.0004696545365732163,0.1945357769727707,-0.1946614682674408,-0.001563261728733778 -1769682170,210503424,0.0,0.0,0.0,1.0,0.0008895985083654523,-0.0053868661634624004,-0.0005674431449733675,0.10539081692695618,-0.13483531773090363,-0.02244751900434494 -1769682170,257304064,0.0,0.0,0.0,1.0,0.0005210506496950984,-0.005529292393475771,-0.000590756069868803,0.0011887908913195133,-0.00017195948748849332,-0.039320752024650574 -1769682170,276989184,0.0,0.0,0.0,1.0,-0.0011286389781162143,-0.004778048489242792,-0.0006089358357712626,-0.030428055673837662,-0.23932936787605286,0.012059439904987812 -1769682170,312843776,0.0,0.0,0.0,1.0,-0.002646109787747264,-0.0014169934438541532,-0.0006051367381587625,-0.2569633424282074,0.10526540130376816,0.0848822221159935 -1769682170,343513600,0.0,0.0,0.0,1.0,-0.0013119098730385303,0.002829981967806816,-0.00043310673208907247,-0.2713414430618286,0.18000110983848572,0.06623920798301697 -1769682170,376404736,0.0,0.0,0.0,1.0,0.0006607327959500253,0.007754624355584383,8.539114060113207e-05,-0.06009490042924881,-0.08971402794122696,0.005718688480556011 -1769682170,410059520,0.0,0.0,0.0,1.0,0.0015069091459736228,0.01015725452452898,0.00037850067019462585,0.06016999110579491,0.08970313519239426,-0.00808804389089346 -1769682170,445616128,0.0,0.0,0.0,1.0,0.0023701570462435484,0.01172644179314375,0.000655328156426549,-0.07438070327043533,-0.014979934319853783,-0.015357007272541523 -1769682170,477491200,0.0,0.0,0.0,1.0,0.0028180070221424103,0.012049585580825806,0.0007840557373128831,-0.08901827782392502,0.059803422540426254,-0.024520965293049812 -1769682170,511491840,0.0,0.0,0.0,1.0,0.003178634913638234,0.011871098540723324,0.0008631066884845495,-0.0146375996991992,0.07478245347738266,-0.009150521829724312 -1769682170,558972672,0.0,0.0,0.0,1.0,0.003498730482533574,0.011184826493263245,0.0009095020359382033,0.0605754591524601,0.08963818103075027,-0.019939696416258812 -1769682170,579174656,0.0,0.0,0.0,1.0,0.003684437368065119,0.010597091168165207,0.0009328412124887109,0.1498013734817505,0.02979719638824463,-0.002435927512124181 -1769682170,610140672,0.0,0.0,0.0,1.0,0.003853463800624013,0.010017978958785534,0.000950329122133553,0.07505763322114944,0.014873082749545574,-0.005962497554719448 -1769682170,646668544,0.0,0.0,0.0,1.0,0.003951926715672016,0.009329580701887608,0.0010093816090375185,0.059932783246040344,0.08972688019275665,0.0003418907872401178 -1769682170,678131712,0.0,0.0,0.0,1.0,0.004064695909619331,0.008920791558921337,0.0011134558590129018,-0.00011945421283598989,1.844632060965523e-05,0.0035742379259318113 -1769682170,710675456,0.0,0.0,0.0,1.0,0.005144210997968912,0.008149229921400547,0.0012100852327421308,0.09099303185939789,-0.060123953968286514,-0.03597905486822128 -1769682170,745226496,0.0,0.0,0.0,1.0,0.006774422246962786,0.0065933708101511,0.0014140618732199073,0.06067168340086937,0.08960078656673431,-0.021099932491779327 -1769682170,776603904,0.0,0.0,0.0,1.0,0.007387167774140835,0.00582757405936718,0.001587667386047542,0.2098817229270935,0.11945626139640808,-0.005450839176774025 -1769682170,809958400,0.0,0.0,0.0,1.0,0.007792653515934944,0.005365479271858931,0.0017608031630516052,0.00024524779291823506,-4.288608761271462e-05,-0.007148227654397488 -1769682170,850232064,0.0,0.0,0.0,1.0,0.007034172769635916,0.005594139453023672,0.0019546516705304384,0.09100982546806335,-0.060180485248565674,-0.03584178164601326 -1769682170,877055488,0.0,0.0,0.0,1.0,0.006233781110495329,0.00636997539550066,0.0020566913299262524,0.0012404345907270908,-0.00023240801237989217,-0.035740531980991364 -1769682170,910302208,0.0,0.0,0.0,1.0,0.00587294390425086,0.007067777682095766,0.002118473406881094,-0.0736629068851471,-0.015099041163921356,-0.034677665680646896 -1769682170,950524416,0.0,0.0,0.0,1.0,0.003280461532995105,0.00692317821085453,0.001949226832948625,0.13037535548210144,-0.28368431329727173,0.11509448289871216 -1769682170,977113088,0.0,0.0,0.0,1.0,0.002526381751522422,0.003862750018015504,0.001833758084103465,0.2163149118423462,0.04620452970266342,0.23516514897346497 -1769682171,11291392,0.0,0.0,0.0,1.0,0.0032379142940044403,0.00020089070312678814,0.0018652635626494884,0.08246127516031265,-0.05853145569562912,0.2061193436384201 -1769682171,56182784,0.0,0.0,0.0,1.0,0.003323749639093876,-0.0025826366618275642,0.0018773800693452358,0.0989496186375618,-0.13367721438407898,0.16071876883506775 -1769682171,77270016,0.0,0.0,0.0,1.0,0.003375817323103547,-0.004876978695392609,0.0018654639134183526,-0.13793213665485382,-0.10389348119497299,0.08656178414821625 -1769682171,110921984,0.0,0.0,0.0,1.0,0.0035328688099980354,-0.0057256994768977165,0.0018795871874317527,0.027781320735812187,-0.1492663323879242,0.055754415690898895 -1769682171,143167744,0.0,0.0,0.0,1.0,0.0037912495899945498,-0.005975660867989063,0.001982602756470442,-0.07566417008638382,-0.014665487222373486,0.02252398245036602 -1769682171,177149952,0.0,0.0,0.0,1.0,0.004208291415125132,-0.005657627247273922,0.0022674857173115015,-0.13419288396835327,-0.10465537011623383,-0.02054077759385109 -1769682171,210341632,0.0,0.0,0.0,1.0,0.002220640191808343,-0.006004542112350464,0.002184601966291666,-0.028097590431571007,-0.2398526966571808,-0.06471268832683563 -1769682171,244705280,0.0,0.0,0.0,1.0,0.0004172767512500286,-0.005981673952192068,0.002122723264619708,0.06029877811670303,-0.2995811402797699,-0.026613086462020874 -1769682171,276617216,0.0,0.0,0.0,1.0,-6.26456894678995e-05,-0.004227244760841131,0.0022373381070792675,-0.2243971973657608,-0.04449360817670822,-0.007292372174561024 -1769682171,311672320,0.0,0.0,0.0,1.0,-0.00013677416427526623,-0.0027736134361475706,0.0024098888970911503,-0.05992140248417854,-0.0896817147731781,-0.003721023676916957 -1769682171,358126080,0.0,0.0,0.0,1.0,-0.0003883632889483124,-0.0013527319533750415,0.002633803291246295,-0.0894714966416359,0.05999269708991051,-0.007075679022818804 -1769682171,376616448,0.0,0.0,0.0,1.0,0.0007009042310528457,1.0640129403327592e-05,0.002997621428221464,-0.17667442560195923,0.11948106437921524,-0.08086580038070679 -1769682171,410272768,0.0,0.0,0.0,1.0,0.0018799913814291358,0.0013804992195218801,0.0033901433926075697,0.0768633559346199,0.014328519813716412,-0.058341581374406815 -1769682171,459639040,0.0,0.0,0.0,1.0,0.002637461293488741,0.0022725313901901245,0.0036836161743849516,-0.05842006579041481,-0.09001677483320236,-0.04898330941796303 -1769682171,476803072,0.0,0.0,0.0,1.0,0.00339810224249959,0.002825726754963398,0.0039461697451770306,0.16514407098293304,-0.045456018298864365,-0.016675475984811783 -1769682171,511735040,0.0,0.0,0.0,1.0,0.0038691656664013863,0.00288582406938076,0.004084479995071888,0.09008623659610748,-0.06019633263349533,-0.01194083970040083 -1769682171,551371776,0.0,0.0,0.0,1.0,0.00434227054938674,0.002677807817235589,0.004229881800711155,-0.08975113928318024,0.06013397499918938,0.0023899758234620094 -1769682171,576996096,0.0,0.0,0.0,1.0,0.004677336663007736,0.002417071256786585,0.004339242819696665,0.05967940762639046,0.08970703184604645,0.013216414488852024 -1769682171,610731008,0.0,0.0,0.0,1.0,0.004878124687820673,0.002123713493347168,0.004459311254322529,0.07448779046535492,0.014827927574515343,0.011975995264947414 -1769682171,647626752,0.0,0.0,0.0,1.0,0.005085646640509367,0.0017376235919073224,0.004651129245758057,-0.00045154168037697673,0.00011567992623895407,0.01310474332422018 -1769682171,676631808,0.0,0.0,0.0,1.0,0.005226664245128632,0.0015325432177633047,0.00486593134701252,-0.0753132551908493,-0.014593704603612423,0.011846841312944889 -1769682171,710298112,0.0,0.0,0.0,1.0,0.0053535266779363155,0.0013658495154231787,0.005117088556289673,-0.015173347666859627,0.07498981058597565,0.013103749603033066 -1769682171,743765504,0.0,0.0,0.0,1.0,0.006839996203780174,0.00031097125611267984,0.005360893905162811,0.07548321038484573,0.014521684497594833,-0.016612600535154343 -1769682171,776829696,0.0,0.0,0.0,1.0,0.007680139504373074,-0.0007589053129777312,0.005688011646270752,0.0004938514903187752,-0.00013803178444504738,-0.014295930974185467 -1769682171,810947584,0.0,0.0,0.0,1.0,0.007998309098184109,-0.0012559817405417562,0.0058948504738509655,-0.05969908833503723,-0.08967921137809753,-0.015486860647797585 -1769682171,857324800,0.0,0.0,0.0,1.0,0.008192609995603561,-0.0015359995886683464,0.00605238601565361,0.07516156882047653,0.014561863616108894,-0.0071003008633852005 -1769682171,876931840,0.0,0.0,0.0,1.0,0.005826897453516722,-0.00026651512598618865,0.006187923718243837,-0.057933930307626724,-0.0902082696557045,-0.06785430759191513 -1769682171,910135296,0.0,0.0,0.0,1.0,0.003897795919328928,0.00029740747413598,0.006114359945058823,-0.12049447745084763,-0.17900331318378448,-0.002255825325846672 -1769682171,947141888,0.0,0.0,0.0,1.0,0.003719017142429948,-0.0007364056073129177,0.00607491098344326,0.17698904871940613,-0.11996126174926758,0.06105790659785271 -1769682171,977600256,0.0,0.0,0.0,1.0,0.0035067296121269464,-0.0015213247388601303,0.006042173132300377,0.08768616616725922,-0.05974151939153671,0.053762760013341904 -1769682172,2202880,0.0,0.0,0.0,1.0,0.003372387494891882,-0.0019515070598572493,0.006022575777024031,-0.07632041722536087,-0.014119112864136696,0.04047650471329689 -1769682172,43498240,0.0,0.0,0.0,1.0,0.0032583221327513456,-0.002570702228695154,0.0060310885310173035,-0.000979056116193533,0.00031608797144144773,0.028591744601726532 -1769682172,77263104,0.0,0.0,0.0,1.0,0.0032353189308196306,-0.0028806908521801233,0.006096202414482832,0.14914117753505707,0.029290050268173218,0.021462222561240196 -1769682172,110396928,0.0,0.0,0.0,1.0,0.0032620287965983152,-0.002952752634882927,0.00620763935148716,-0.08964378386735916,0.060447219759225845,0.004615907557308674 -1769682172,154693376,0.0,0.0,0.0,1.0,0.0033526024781167507,-0.0029076016508042812,0.006437384523451328,-0.22454579174518585,-0.043571799993515015,-0.008310586214065552 -1769682172,177227008,0.0,0.0,0.0,1.0,0.0034737265668809414,-0.0028215248603373766,0.006672307383269072,0.1352217048406601,0.10392075031995773,0.004567387048155069 -1769682172,210182912,0.0,0.0,0.0,1.0,0.0037391288205981255,-0.004150658845901489,0.0068221441470086575,0.0629461482167244,0.08851370960474014,-0.07406045496463776 -1769682172,244799232,0.0,0.0,0.0,1.0,0.0012879673158749938,-0.007454401347786188,0.006802957039326429,-0.011921296827495098,0.07402119040489197,-0.0764186903834343 -1769682172,276602624,0.0,0.0,0.0,1.0,0.0005201075691729784,-0.009189378470182419,0.006834214087575674,0.16634662449359894,-0.04677082970738411,-0.05953110754489899 -1769682172,313088768,0.0,0.0,0.0,1.0,-2.7762311219703406e-05,-0.010296273976564407,0.006873649079352617,-0.05910511314868927,-0.08984093368053436,-0.04263373464345932 -1769682172,348312320,0.0,0.0,0.0,1.0,-0.0005968931363895535,-0.010924625210464,0.006916997022926807,-0.045345522463321686,-0.16452693939208984,-0.023387543857097626 -1769682172,376895232,0.0,0.0,0.0,1.0,-0.0006734253838658333,-0.010780120268464088,0.007029132451862097,0.09025208652019501,-0.06087924540042877,-0.027394916862249374 -1769682172,410200576,0.0,0.0,0.0,1.0,0.0006559414323419333,-0.009702106937766075,0.007284428458660841,-0.012986650690436363,0.07441401481628418,-0.04423128440976143 -1769682172,446122752,0.0,0.0,0.0,1.0,0.001562945544719696,-0.008366623893380165,0.007527884561568499,0.000600005907472223,-0.00022597756469622254,-0.019062718376517296 -1769682172,477812224,0.0,0.0,0.0,1.0,0.001758837141096592,-0.0074843307957053185,0.007356575224548578,-0.04601322486996651,-0.16430148482322693,-0.007830030284821987 -1769682172,510468608,0.0,0.0,0.0,1.0,0.0023887446150183678,-0.006881603971123695,0.007257403340190649,0.06075509637594223,0.08920461684465408,-0.003954804502427578 -1769682172,546476800,0.0,0.0,0.0,1.0,0.0031572163570672274,-0.006448692176491022,0.0072548165917396545,-0.028845885768532753,0.1499839425086975,0.006839153356850147 -1769682172,579821824,0.0,0.0,0.0,1.0,0.0036581112071871758,-0.006357870530337095,0.007355428300797939,-0.08953754603862762,0.060789112001657486,0.008448072709143162 -1769682172,611317760,0.0,0.0,0.0,1.0,0.004044102970510721,-0.006410779897123575,0.00751373590901494,-0.06107116490602493,-0.08905578404664993,0.012364464811980724 -1769682172,646398720,0.0,0.0,0.0,1.0,0.004372835159301758,-0.00660440931096673,0.007794039789587259,0.0280833188444376,-0.14973969757556915,0.01464768499135971 -1769682172,677383680,0.0,0.0,0.0,1.0,0.0045098308473825455,-0.006790971849113703,0.008036904968321323,0.08891520649194717,-0.06062016636133194,0.010582503862679005 -1769682172,711909632,0.0,0.0,0.0,1.0,0.004511883482336998,-0.006988425273448229,0.008289700374007225,0.014079108834266663,-0.07490517944097519,0.00495539978146553 -1769682172,745733632,0.0,0.0,0.0,1.0,0.00484868697822094,-0.007406722754240036,0.008594506420195103,0.08937527239322662,-0.060885701328516006,-0.0061227018013596535 -1769682172,777087488,0.0,0.0,0.0,1.0,0.0049094646237790585,-0.007689653430134058,0.008798668161034584,-0.046553052961826324,-0.1641394942998886,-0.002775734756141901 -1769682172,810515968,0.0,0.0,0.0,1.0,0.004846529103815556,-0.007867014035582542,0.008964741602540016,0.23902007937431335,-0.032530274242162704,0.004961272235959768 -1769682172,847384320,0.0,0.0,0.0,1.0,0.0049309819005429745,-0.007884575985372066,0.009164524264633656,-0.1496255248785019,-0.02838451974093914,-0.01343756914138794 -1769682172,880148224,0.0,0.0,0.0,1.0,0.004024236463010311,-0.005534481257200241,0.00931078102439642,0.04699322581291199,-0.22720980644226074,-0.1637282818555832 -1769682172,911634944,0.0,0.0,0.0,1.0,0.0026879096403717995,-0.002783197211101651,0.00932567659765482,-0.19275544583797455,-0.1941613256931305,-0.14470933377742767 -1769682172,955712256,0.0,0.0,0.0,1.0,0.0019661616533994675,-0.00015318088117055595,0.009335190057754517,-0.13297298550605774,-0.10453466325998306,-0.1060696542263031 -1769682172,977419776,0.0,0.0,0.0,1.0,0.001690705306828022,0.0010346926283091307,0.009417307563126087,0.016024213284254074,-0.0759795531630516,-0.07005012035369873 -1769682173,10523136,0.0,0.0,0.0,1.0,0.0014488472370430827,0.001667300472036004,0.009566779248416424,-0.13481250405311584,-0.10358688235282898,-0.04291844367980957 -1769682173,56152832,0.0,0.0,0.0,1.0,0.001298608724027872,0.001847992418333888,0.00978076085448265,0.014399662613868713,-0.07520919293165207,-0.014041529968380928 -1769682173,77882880,0.0,0.0,0.0,1.0,0.001241441466845572,0.001633751904591918,0.010195421054959297,0.1636197865009308,-0.04693390429019928,0.014852331951260567 -1769682173,111926016,0.0,0.0,0.0,1.0,0.001193534699268639,0.0012632169527933002,0.010563439689576626,-0.061925213783979416,-0.08852177858352661,0.029306842014193535 -1769682173,147741696,0.0,0.0,0.0,1.0,0.0023446236737072468,0.0010816326830536127,0.011363902129232883,-0.10392588376998901,0.1366998255252838,0.036841195076704025 -1769682173,177225472,0.0,0.0,0.0,1.0,0.0015923883765935898,5.107234028400853e-05,0.011797046288847923,-0.1500585824251175,-0.027730172500014305,-0.0014954560901969671 -1769682173,210246912,0.0,0.0,0.0,1.0,0.0010854231659322977,-0.00131698208861053,0.012143809348344803,0.10274282097816467,-0.13623099029064178,0.001299083000048995 -1769682173,245047552,0.0,0.0,0.0,1.0,0.0009826498571783304,-0.0024064304307103157,0.012448750436306,-0.027720626443624496,0.15011349320411682,0.0018264846876263618 -1769682173,276867072,0.0,0.0,0.0,1.0,0.0009152116253972054,-0.003352697938680649,0.012849261052906513,0.08856546133756638,-0.06113702058792114,0.010541802272200584 -1769682173,310064896,0.0,0.0,0.0,1.0,0.0008749976404942572,-0.0036953932140022516,0.01311939675360918,-0.07498493045568466,-0.013777299784123898,-0.0031050792895257473 -1769682173,344660224,0.0,0.0,0.0,1.0,0.0007507550762966275,-0.0038064438849687576,0.01335025206208229,0.00013364199548959732,-6.906825001351535e-05,-0.004766001831740141 -1769682173,376781568,0.0,0.0,0.0,1.0,0.0006413217633962631,-0.0037160792853683233,0.013577303849160671,-0.04765436053276062,-0.1638195514678955,-0.0013331035152077675 -1769682173,411399936,0.0,0.0,0.0,1.0,0.0008750458946451545,-0.003385017393156886,0.013762195594608784,-0.06104886904358864,-0.08890305459499359,-0.013519645668566227 -1769682173,457789440,0.0,0.0,0.0,1.0,0.0009971336694434285,-0.003024097066372633,0.013923460617661476,-0.07464790344238281,-0.013836700469255447,-0.01617550477385521 -1769682173,479351296,0.0,0.0,0.0,1.0,0.0011794435558840632,-0.0026256106793880463,0.014120065607130527,-0.12260536104440689,-0.17751385271549225,-0.015085927210748196 -1769682173,511676672,0.0,0.0,0.0,1.0,0.0013079707277938724,-0.0024304301477968693,0.014272447675466537,0.040690429508686066,-0.22528621554374695,-0.0003369490150362253 -1769682173,543621888,0.0,0.0,0.0,1.0,0.0014191356021910906,-0.002297820057719946,0.014450062066316605,-9.79202231974341e-05,5.2803472499363124e-05,0.003574550151824951 -1769682173,577765376,0.0,0.0,0.0,1.0,0.0014925135765224695,-0.0022116375621408224,0.014707439579069614,-0.048313867300748825,-0.1635780930519104,0.005880555137991905 -1769682173,610213376,0.0,0.0,0.0,1.0,0.0015425572637468576,-0.0021854829974472523,0.014897504821419716,-0.08848791569471359,0.06164708733558655,-0.0033277247566729784 -1769682173,646571520,0.0,0.0,0.0,1.0,0.001471738563850522,-0.00222206418402493,0.015120538882911205,0.11518192291259766,-0.2118990123271942,0.006298772059381008 -1769682173,677068544,0.0,0.0,0.0,1.0,0.0014666272327303886,-0.002262794179841876,0.015284075401723385,-0.07518862187862396,-0.013311349786818027,0.001744224689900875 -1769682173,711431424,0.0,0.0,0.0,1.0,0.0014210360823199153,-0.0023093633353710175,0.015418026596307755,0.0750017911195755,0.01338448841124773,0.00539919501170516 -1769682173,757745408,0.0,0.0,0.0,1.0,0.001415651640854776,-0.0024535127449780703,0.015558150596916676,0.00016008253442123532,-9.03477193787694e-05,-0.0059576332569122314 -1769682173,777156608,0.0,0.0,0.0,1.0,0.0013417123118415475,-0.0025161339435726404,0.015623992308974266,-0.062025513499975204,-0.08830227702856064,0.004452880937606096 -1769682173,809988352,0.0,0.0,0.0,1.0,0.0022664740681648254,-0.0031354122329503298,0.01586035266518593,0.14874373376369476,0.027283042669296265,0.0596088245511055 -1769682173,853947392,0.0,0.0,0.0,1.0,0.0018791698385030031,-0.002448965096846223,0.01603495143353939,-0.14876826107501984,-0.027193771675229073,-0.059588439762592316 -1769682173,877635072,0.0,0.0,0.0,1.0,0.0013408917002379894,-0.0014543727738782763,0.016038989648222923,0.089619942009449,-0.06282733380794525,-0.04913008585572243 -1769682173,910694912,0.0,0.0,0.0,1.0,0.0011872545583173633,-0.000649216934107244,0.01603369228541851,0.08943067491054535,-0.06277987360954285,-0.04317248985171318 -1769682173,943449856,0.0,0.0,0.0,1.0,0.0010954496683552861,-9.59962053457275e-05,0.016035504639148712,-0.07420139014720917,-0.013613423332571983,-0.03753107413649559 -1769682173,980856576,0.0,0.0,0.0,1.0,0.0009843670995905995,0.000312342366669327,0.01607494242489338,0.1637590378522873,-0.049427833408117294,-0.012785965576767921 -1769682174,11594240,0.0,0.0,0.0,1.0,0.0009597702301107347,0.00044441784848459065,0.01613047532737255,0.13763681054115295,0.10097016394138336,-0.00748000293970108 -1769682174,44588288,0.0,0.0,0.0,1.0,0.0012079470325261354,0.0005986327887512743,0.01618647389113903,-0.02624628134071827,0.150621235370636,0.013638267293572426 -1769682174,77313280,0.0,0.0,0.0,1.0,0.003215103643015027,0.001785457250662148,0.01629030331969261,0.07448133081197739,0.013302548788487911,0.028003111481666565 -1769682175,12707840,0.0,0.0,0.0,1.0,0.004811104387044907,0.004609519150108099,0.013687617145478725,0.03519948571920395,-0.22599567472934723,0.00983106717467308 -1769682175,82028288,0.0,0.0,0.0,1.0,0.0030421442352235317,0.008799281902611256,0.013342550955712795,0.024446113035082817,-0.15133532881736755,-0.02995387092232704 -1769682175,84824832,0.0,0.0,0.0,1.0,0.002445749007165432,0.01082986406981945,0.013153179548680782,0.174829363822937,-0.12767285108566284,-0.016400078311562538 -1769682175,127728640,0.0,0.0,0.0,1.0,0.0019447660306468606,0.012395569123327732,0.013014043681323528,0.32607385516166687,-0.10464697331190109,-0.03133785352110863 -1769682175,158953472,0.0,0.0,0.0,1.0,0.0013506913091987371,0.013576088473200798,0.01288351509720087,0.31403833627700806,-0.02921813726425171,-0.020977240055799484 -1769682175,168944384,0.0,0.0,0.0,1.0,0.0011277158046141267,0.01363843772560358,0.012839442119002342,0.337053507566452,-0.17993679642677307,-0.010268916375935078 -1769682175,211115008,0.0,0.0,0.0,1.0,0.000731694046407938,0.014221007004380226,0.012787895277142525,0.2499418407678604,-0.1163005381822586,-0.011565079912543297 -1769682175,243354624,0.0,0.0,0.0,1.0,0.0004896500613540411,0.013715742155909538,0.012756314128637314,0.5625820159912109,-0.14518821239471436,0.01084837131202221 -1769682175,278623232,0.0,0.0,0.0,1.0,0.00029081915272399783,0.013159438036382198,0.012734843418002129,0.4234008491039276,-0.24407799541950226,0.0037449400406330824 -1769682175,311846912,0.0,0.0,0.0,1.0,0.000174427725141868,0.012271372601389885,0.012716218829154968,0.5849382281303406,-0.29623496532440186,0.029189717024564743 -1769682175,347150336,0.0,0.0,0.0,1.0,0.0008228321094065905,0.012220349162817001,0.012840807437896729,0.6157327890396118,0.015849951654672623,-0.015847962349653244 -1769682175,377105920,0.0,0.0,0.0,1.0,0.001365568838082254,0.012728861533105373,0.012945203110575676,0.6912965774536133,0.02698354423046112,-0.018089650198817253 -1769682175,410735872,0.0,0.0,0.0,1.0,0.0016915348824113607,0.012702392414212227,0.013010927475988865,0.8637873530387878,-0.10066324472427368,0.022551434114575386 -1769682175,453473536,0.0,0.0,0.0,1.0,0.0020670671947300434,0.01290967594832182,0.01306141261011362,0.7887682914733887,-0.11274988204240799,0.007540734484791756 -1769682175,478650624,0.0,0.0,0.0,1.0,0.0022203640546649694,0.013105185702443123,0.01306874305009842,0.8641262650489807,-0.10169532895088196,0.010241576470434666 -1769682175,511781632,0.0,0.0,0.0,1.0,0.0024058492854237556,0.013493295758962631,0.01306801289319992,0.9395740032196045,-0.09074448049068451,0.010628682561218739 -1769682175,548351488,0.0,0.0,0.0,1.0,0.002547206822782755,0.013337933458387852,0.013036293908953667,1.0145964622497559,-0.07975807785987854,0.02312704548239708 -1769682175,578380544,0.0,0.0,0.0,1.0,0.0029116610530763865,0.012972062453627586,0.012985331006348133,1.0040721893310547,-0.005094666033983231,0.0014426149427890778 -1769682175,610217984,0.0,0.0,0.0,1.0,0.004185427445918322,0.012027253396809101,0.01293336134403944,1.0265134572982788,-0.1564258337020874,0.003137631341814995 -1769682175,655438848,0.0,0.0,0.0,1.0,0.006730027962476015,0.009535083547234535,0.013247506693005562,1.0540227890014648,0.15791787207126617,0.08786863088607788 -1769682175,678093312,0.0,0.0,0.0,1.0,0.008647286333143711,0.0077784801833331585,0.013544336892664433,1.077212929725647,0.005970768630504608,0.06695666164159775 -1769682175,712687872,0.0,0.0,0.0,1.0,0.00722965644672513,0.006574214436113834,0.013502741232514381,1.1099454164505005,-0.22057269513607025,0.0860380083322525 -1769682175,750454784,0.0,0.0,0.0,1.0,0.005760854575783014,0.005138504784554243,0.01326600182801485,1.2501368522644043,-0.12374761700630188,0.07646338641643524 -1769682175,778627840,0.0,0.0,0.0,1.0,0.0052919466979801655,0.00473939860239625,0.013104984536767006,1.2731108665466309,-0.2757302522659302,0.05317552387714386 -1769682175,804359936,0.0,0.0,0.0,1.0,0.004999938886612654,0.004727077670395374,0.013008983805775642,1.3044471740722656,0.036934904754161835,0.050452448427677155 -1769682175,849614592,0.0,0.0,0.0,1.0,0.004587073810398579,0.00505072483792901,0.01276277843862772,1.3157541751861572,-0.039571020752191544,0.04320792853832245 -1769682175,878240000,0.0,0.0,0.0,1.0,0.006438060197979212,0.006645675748586655,0.012617647647857666,1.3906457424163818,-0.02878987230360508,0.060369834303855896 -1769682175,910589440,0.0,0.0,0.0,1.0,0.007239062339067459,0.008063488639891148,0.012507411651313305,1.391164779663086,-0.02960383892059326,0.046399857848882675 -1769682175,946522624,0.0,0.0,0.0,1.0,0.006530736107379198,0.009275882504880428,0.012242562137544155,1.348649263381958,-0.2679215669631958,0.038454242050647736 -1769682175,978408704,0.0,0.0,0.0,1.0,0.0037366333417594433,0.010203784331679344,0.01177509967237711,1.4245147705078125,-0.257801353931427,0.028469786047935486 -1769682176,11283456,0.0,0.0,0.0,1.0,0.0024717217311263084,0.010585635900497437,0.01137456577271223,1.4996073246002197,-0.24727892875671387,0.03879468888044357 -1769682176,61358848,0.0,0.0,0.0,1.0,0.0013395852874964476,0.011002044193446636,0.010948389768600464,1.705286979675293,-0.06496110558509827,0.020901799201965332 -1769682176,71933440,0.0,0.0,0.0,1.0,0.0009384100558236241,0.01088720839470625,0.010772242210805416,1.8016465902328491,-0.20522275567054749,0.0424804612994194 -1769682176,110642688,0.0,0.0,0.0,1.0,0.00016654074715916067,0.010577697306871414,0.010460606776177883,1.7259684801101685,-0.2167123705148697,0.04286311939358711 -1769682176,144887808,0.0,0.0,0.0,1.0,-0.00020145719463471323,0.010050778277218342,0.010263392701745033,1.866169810295105,-0.1202251985669136,0.0469193235039711 -1769682176,177707008,0.0,0.0,0.0,1.0,-0.0009476428385823965,0.004237186163663864,0.009863615967333317,1.9383032321929932,-0.10847850143909454,0.13123677670955658 -1769682176,210710784,0.0,0.0,0.0,1.0,-0.0015191129641607404,-0.0038902645464986563,0.009411598555743694,1.7105578184127808,-0.14045841991901398,0.15365003049373627 -1769682176,245229056,0.0,0.0,0.0,1.0,-0.0019396755378693342,-0.012041286565363407,0.008939438499510288,1.5594362020492554,-0.16221173107624054,0.1511249542236328 -1769682176,278544640,0.0,0.0,0.0,1.0,-0.0021132617257535458,-0.020780153572559357,0.008370605297386646,1.150780439376831,0.010280657559633255,0.11692625284194946 -1769682176,311672320,0.0,0.0,0.0,1.0,-0.0021387808956205845,-0.024852395057678223,0.008005058392882347,1.0968624353408813,-0.15191030502319336,0.10799380391836166 -1769682176,348464128,0.0,0.0,0.0,1.0,-0.002055578865110874,-0.02945072390139103,0.00757897412404418,0.7732787132263184,-0.04331904649734497,0.10651174187660217 -1769682176,377780480,0.0,0.0,0.0,1.0,-0.001977090025320649,-0.031390633434057236,0.007286889012902975,0.6885561347007751,0.020723536610603333,0.06787201017141342 -1769682176,409986048,0.0,0.0,0.0,1.0,-0.0017647178610786796,-0.0300393495708704,0.007051997818052769,0.4645109474658966,-0.012619024142622948,-0.008104080334305763 -1769682176,446029568,0.0,0.0,0.0,1.0,-0.0004767138743773103,-0.02839936874806881,0.006998601369559765,0.1522444784641266,0.020366698503494263,-0.02974974550306797 -1769682176,477354496,0.0,0.0,0.0,1.0,0.0001753883552737534,-0.027104880660772324,0.00689811771735549,0.06553028523921967,0.08577630668878555,-0.013942423276603222 -1769682176,512697344,0.0,0.0,0.0,1.0,0.0006883692112751305,-0.02622847817838192,0.006747488863766193,-0.09599106013774872,0.1402609944343567,-0.020520299673080444 -1769682176,554151424,0.0,0.0,0.0,1.0,0.0010983155807480216,-0.024235662072896957,0.0065710050985217094,-0.22490665316581726,-0.032660044729709625,-0.05906359851360321 -1769682176,579113216,0.0,0.0,0.0,1.0,0.0013939245836809278,-0.025048067793250084,0.006249959114938974,-0.3665872812271118,-0.12846660614013672,-0.030177239328622818 -1769682176,611174144,0.0,0.0,0.0,1.0,0.0016858996823430061,-0.02411426417529583,0.006026852875947952,-0.614508867263794,-0.00843936949968338,-0.026973549276590347 -1769682176,643749120,0.0,0.0,0.0,1.0,0.0018988624215126038,-0.02376832254230976,0.005804114509373903,-0.8517923951148987,0.035988397896289825,-0.02743520773947239 -1769682176,677217536,0.0,0.0,0.0,1.0,0.0020278883166611195,-0.02423437498509884,0.005525280721485615,-0.8621044754981995,0.11165662109851837,-0.03212222456932068 -1769682176,712551168,0.0,0.0,0.0,1.0,0.0021634213626384735,-0.02253546752035618,0.005372379906475544,-1.1540021896362305,-0.005448352545499802,-0.034810781478881836 -1769682176,744382976,0.0,0.0,0.0,1.0,0.002530446043238044,-0.019114339724183083,0.00523989787325263,-1.2492787837982178,0.1345915049314499,-0.07797983288764954 -1769682176,777055744,0.0,0.0,0.0,1.0,0.00564887560904026,-0.014421399682760239,0.005440751556307077,-1.1096010208129883,0.2320891171693802,-0.03623037412762642 -1769682176,810198784,0.0,0.0,0.0,1.0,0.007591647561639547,-0.011012433096766472,0.005740716587752104,-1.1091949939727783,0.23194953799247742,-0.05017075315117836 -1769682176,843740160,0.0,0.0,0.0,1.0,0.009026614017784595,-0.007728228345513344,0.005906100384891033,-1.1640602350234985,0.07062088698148727,-0.047722600400447845 -1769682176,878867712,0.0,0.0,0.0,1.0,0.00989948958158493,-0.004072662442922592,0.005837657488882542,-1.2291784286499023,-0.015162520110607147,-0.05198615416884422 -1769682176,911025920,0.0,0.0,0.0,1.0,0.007295397110283375,-0.002291633514687419,0.005449275020509958,-1.0682686567306519,-0.0693608969449997,-0.026150759309530258 -1769682176,959403776,0.0,0.0,0.0,1.0,0.006167261395603418,-0.0010288241319358349,0.005024902988225222,-1.0136642456054688,0.09266537427902222,-0.014154010452330112 -1769682176,977113344,0.0,0.0,0.0,1.0,0.00560845248401165,-0.0006803490687161684,0.0047801039181649685,-0.992969274520874,-0.058443110436201096,-0.0147919412702322 -1769682177,11261184,0.0,0.0,0.0,1.0,0.005183124449104071,-0.0006994091672822833,0.004594781436026096,-1.0791903734207153,0.0072904229164123535,-0.004247636534273624 -1769682177,44366336,0.0,0.0,0.0,1.0,0.004715846385806799,-0.0009352811612188816,0.004441382363438606,-1.0687154531478882,-0.0683378279209137,-0.010478019714355469 -1769682177,78913792,0.0,0.0,0.0,1.0,0.006915355566889048,0.00016253595822490752,0.0042213560082018375,-0.9189270734786987,-0.046296365559101105,0.04537617415189743 -1769682177,111414272,0.0,0.0,0.0,1.0,0.00782365445047617,0.0008414709009230137,0.004086409229785204,-1.0801727771759033,0.008687583729624748,0.03389093279838562 -1769682177,163009024,0.0,0.0,0.0,1.0,0.008580450899899006,0.0012929632794111967,0.00388599606230855,-1.0040993690490723,0.018669109791517258,0.01647847145795822 -1769682177,169649408,0.0,0.0,0.0,1.0,0.005413845181465149,0.001063937321305275,0.0035259800497442484,-1.1137683391571045,-0.30469053983688354,-0.0021620718762278557 -1769682177,211987456,0.0,0.0,0.0,1.0,0.0026771274860948324,0.0007407134398818016,0.0028886785730719566,-1.1646040678024292,0.07309269905090332,-0.022510668262839317 -1769682177,247353600,0.0,0.0,0.0,1.0,0.0013239601394161582,0.00033020612318068743,0.0024003353901207447,-1.0684870481491089,-0.06781397759914398,-0.021259348839521408 -1769682177,277944064,0.0,0.0,0.0,1.0,0.0005800612270832062,0.00010242091957479715,0.002099012490361929,-1.0990183353424072,0.1589309275150299,-0.030160803347826004 -1769682177,310702336,0.0,0.0,0.0,1.0,-1.0361956810811535e-05,-2.5091561838053167e-05,0.0018647611141204834,-0.9827501177787781,-0.1329895555973053,-0.016195880249142647 -1769682177,347891200,0.0,0.0,0.0,1.0,-0.00044438333134166896,-0.00011248777445871383,0.0016496507450938225,-1.078995943069458,0.008272020146250725,-0.011519024148583412 -1769682177,378763008,0.0,0.0,0.0,1.0,-0.0006953692063689232,-0.00015156084555201232,0.0015637276228517294,-1.0789337158203125,0.008263498544692993,-0.013897099532186985 -1769682177,410801920,0.0,0.0,0.0,1.0,-0.0007784661720506847,-0.0001382755726808682,0.0015216454630717635,-0.9931678771972656,-0.05703829228878021,-0.010020589455962181 -1769682177,456728832,0.0,0.0,0.0,1.0,-0.0008097804966382682,1.7955728253582492e-05,0.0015259092906489968,-1.2401574850082397,0.0633917897939682,-0.024227028712630272 -1769682177,478070272,0.0,0.0,0.0,1.0,-0.0007448082324117422,0.0004971256712451577,0.001560078701004386,-1.0032216310501099,0.01853080838918686,-0.01695805788040161 -1769682177,513233664,0.0,0.0,0.0,1.0,-0.000687257619574666,0.0015055951662361622,0.0016090160934254527,-1.0031583309173584,0.018519235774874687,-0.019374314695596695 -1769682177,544104448,0.0,0.0,0.0,1.0,-0.0005465279682539403,0.002612255048006773,0.001651286380365491,-0.9273200035095215,0.028543224558234215,-0.02725827880203724 -1769682177,579446784,0.0,0.0,0.0,1.0,0.0007695131353102624,0.004861122462898493,0.001930823316797614,-0.9358488321304321,0.10263793915510178,-0.09151359647512436 -1769682177,610501888,0.0,0.0,0.0,1.0,0.0022403430193662643,0.0064989677630364895,0.00222983886487782,-1.0772271156311035,0.007061373442411423,-0.07869909703731537 -1769682177,644050688,0.0,0.0,0.0,1.0,0.0031948480755090714,0.007633813191205263,0.0024466640315949917,-0.8511394262313843,0.03838770464062691,-0.04746843874454498 -1769682177,677493248,0.0,0.0,0.0,1.0,0.00419535581022501,0.008630335330963135,0.0026422312948852777,-0.7756264805793762,0.04874959588050842,-0.04240652173757553 -1769682177,712551680,0.0,0.0,0.0,1.0,0.004677869379520416,0.00891448650509119,0.0027403023559600115,-0.7004101872444153,0.05935674160718918,-0.026527658104896545 -1769682177,748028928,0.0,0.0,0.0,1.0,0.005210425704717636,0.008706732653081417,0.002815661486238241,-0.8723450899124146,0.1907401978969574,-0.015815554186701775 -1769682177,777541376,0.0,0.0,0.0,1.0,0.005477245897054672,0.008626934140920639,0.0028344481252133846,-0.7666850686073303,-0.025501718744635582,0.0032049668952822685 -1769682177,811856384,0.0,0.0,0.0,1.0,0.007355919573456049,0.0074302745051681995,0.002994533395394683,-0.5614013075828552,0.15741506218910217,0.04934083670377731 -1769682177,855596032,0.0,0.0,0.0,1.0,0.012098661623895168,0.003375878557562828,0.0036200217436999083,-0.7129769921302795,0.13758185505867004,0.059732839465141296 -1769682177,878224640,0.0,0.0,0.0,1.0,0.013981635682284832,0.0011735993903130293,0.003920612391084433,-0.6274169087409973,0.07237473130226135,0.06858878582715988 -1769682177,911161856,0.0,0.0,0.0,1.0,0.011730162426829338,0.0002385156403761357,0.00381236569955945,-0.746504008769989,-0.17635871469974518,0.006369061768054962 -1769682177,943769344,0.0,0.0,0.0,1.0,0.00934296753257513,-0.0003635278553701937,0.00348201347514987,-0.6052693128585815,-0.08055652678012848,0.0030025355517864227 -1769682177,981044224,0.0,0.0,0.0,1.0,0.00794870126992464,-0.00047955330228433013,0.0031084921211004257,-0.6805735230445862,-0.0908990129828453,-0.009532899595797062 -1769682178,11592960,0.0,0.0,0.0,1.0,0.007110929582268,-0.0003339307149872184,0.002878190716728568,-0.700289249420166,0.05993572250008583,-0.0286293663084507 -1769682178,47387648,0.0,0.0,0.0,1.0,0.00826476514339447,0.0012112893164157867,0.0025652600452303886,-0.7018644213676453,0.061597589403390884,0.0273258239030838 -1769682178,77965568,0.0,0.0,0.0,1.0,0.009343741461634636,0.002926544053480029,0.00238628382794559,-0.615916907787323,-0.0041390471160411835,0.02084960788488388 -1769682178,113029120,0.0,0.0,0.0,1.0,0.009932443499565125,0.004244738724082708,0.002226807177066803,-0.6258212327957153,0.0713668018579483,0.013533261604607105 -1769682178,144526592,0.0,0.0,0.0,1.0,0.00588035024702549,0.004155006259679794,0.0017622375162318349,-0.4426170885562897,-0.13713501393795013,-0.04203406348824501 -1769682178,177300480,0.0,0.0,0.0,1.0,0.002948691602796316,0.003684902796521783,0.0011800214415416121,-0.5184923410415649,-0.1469270884990692,-0.03442757576704025 -1769682178,210264064,0.0,0.0,0.0,1.0,0.0017103246646001935,0.0029566625598818064,0.0008517231908626854,-0.5185274481773376,-0.14687927067279816,-0.03327827900648117 -1769682178,261403648,0.0,0.0,0.0,1.0,0.0005023950943723321,0.002184792421758175,0.0005609440268017352,-0.443512886762619,-0.13618172705173492,-0.011186777614057064 -1769682178,278037248,0.0,0.0,0.0,1.0,-0.00016138955834321678,0.0017360191559419036,0.0004204532306175679,-0.32223841547966003,0.11062760651111603,-0.01976328156888485 -1769682178,313156608,0.0,0.0,0.0,1.0,-0.0005948844482190907,0.0014041526010259986,0.00033579254522919655,-0.2924518287181854,-0.1158602386713028,-0.002677137963473797 -1769682178,344268032,0.0,0.0,0.0,1.0,-0.0009584834333509207,0.0010584724368527532,0.0002880291431210935,-0.3027145564556122,-0.04002032056450844,0.0031250184401869774 -1769682178,379144704,0.0,0.0,0.0,1.0,-0.0011085050646215677,0.0011042465921491385,0.0002792263694573194,-0.3025765120983124,-0.04015747085213661,-0.0016542801167815924 -1769682178,410813440,0.0,0.0,0.0,1.0,-0.001152513548731804,0.0010278363479301333,0.00029309658566489816,-0.3682638704776764,-0.1257237046957016,0.00251973420381546 -1769682178,445065984,0.0,0.0,0.0,1.0,-0.0011524069122970104,0.0009919449221342802,0.00031077308813109994,-0.3127686679363251,0.03562072664499283,0.001765361987054348 -1769682178,480842752,0.0,0.0,0.0,1.0,0.00025636295322328806,0.0017420158255845308,0.0005530095659196377,-0.32083505392074585,0.10925265401601791,-0.06746330857276917 -1769682178,512627712,0.0,0.0,0.0,1.0,0.0018177087185904384,0.002694658702239394,0.0008338931947946548,-0.311232328414917,0.03408543020486832,-0.050680872052907944 -1769682178,545368320,0.0,0.0,0.0,1.0,0.0031172772869467735,0.0036351487506181,0.0010955912293866277,-0.31104907393455505,0.033916719257831573,-0.05668120086193085 -1769682178,577430272,0.0,0.0,0.0,1.0,0.003893554210662842,0.003989464603364468,0.0012199687771499157,-0.150358647108078,-0.02099420502781868,-0.032452456653118134 -1769682178,612472064,0.0,0.0,0.0,1.0,0.004480467643588781,0.003998494241386652,0.001302082440815866,-0.1709996610879898,0.13083018362522125,-0.016122249886393547 -1769682178,646024192,0.0,0.0,0.0,1.0,0.005083792842924595,0.004219502676278353,0.001380615751259029,-0.3023357689380646,-0.040340110659599304,-0.010190043598413467 -1769682178,678875904,0.0,0.0,0.0,1.0,0.005900311283767223,0.0036613272968679667,0.001567060244269669,-0.1930776685476303,0.2841429114341736,0.04889926686882973 -1769682178,710417408,0.0,0.0,0.0,1.0,0.009776018559932709,0.0008796800393611193,0.00200466625392437,-0.03236791118979454,0.229201540350914,0.07200828194618225 -1769682178,745614592,0.0,0.0,0.0,1.0,0.012490748427808285,-0.0022002358455210924,0.002426957478746772,-0.09756982326507568,0.14318712055683136,0.059480905532836914 -1769682178,770136320,0.0,0.0,0.0,1.0,0.011187806725502014,-0.0026682971511036158,0.002426762832328677,-0.12996402382850647,-0.17261935770511627,-0.04147079586982727 -1769682178,812277504,0.0,0.0,0.0,1.0,0.00763186439871788,-0.0022864043712615967,0.002042909385636449,-0.16036953032016754,0.05463999882340431,-0.0339367650449276 -1769682178,846485760,0.0,0.0,0.0,1.0,0.006274218671023846,-0.0017322328640148044,0.0017061291728168726,-0.1404286026954651,-0.09654106199741364,-0.02855265513062477 -1769682178,878590464,0.0,0.0,0.0,1.0,0.005471454467624426,-0.0013007137458771467,0.001487214583903551,-0.1503654420375824,-0.02098555862903595,-0.032426632940769196 -1769682178,910144768,0.0,0.0,0.0,1.0,0.0052704219706356525,-0.0007584769045934081,0.001282937591895461,-0.24695922434329987,0.12130960822105408,-0.0040422724559903145 -1769682178,946124032,0.0,0.0,0.0,1.0,0.006323520094156265,0.001075545558705926,0.001055461005307734,-0.15174411237239838,-0.019485970959067345,0.014030723832547665 -1769682178,977535488,0.0,0.0,0.0,1.0,0.00656279269605875,0.0019662517588585615,0.0008958057733252645,-0.2374519407749176,0.04623761773109436,0.014121013693511486 -1769682179,10652160,0.0,0.0,0.0,1.0,0.0034825927577912807,0.00016737982514314353,0.0004950167494826019,0.154188334941864,0.016793575137853622,-0.09619887918233871 -1769682179,45197056,0.0,0.0,0.0,1.0,0.0014527239836752415,-0.003309652442112565,6.457161362050101e-05,0.08753997832536697,-0.06774421781301498,-0.06201252341270447 -1769682179,78119680,0.0,0.0,0.0,1.0,0.0005463161505758762,-0.005326861049979925,-0.0001679055130807683,0.07701314240694046,0.008469044230878353,-0.045735809952020645 -1769682179,112744192,0.0,0.0,0.0,1.0,-0.00012814003275707364,-0.006680251099169254,-0.00033337707282043993,-0.00880575180053711,0.07430442422628403,-0.04206719994544983 -1769682179,155695872,0.0,0.0,0.0,1.0,-0.0006223865202628076,-0.00748121552169323,-0.00043896451825276017,0.020264388993382454,-0.1515711098909378,-0.0063839745707809925 -1769682179,177418240,0.0,0.0,0.0,1.0,-0.0010683384025469422,-0.00787278264760971,-0.000521527137607336,-0.07595181465148926,-0.009641975164413452,0.01006167009472847 -1769682179,212012032,0.0,0.0,0.0,1.0,-0.0012434703530743718,-0.0078001925721764565,-0.000557239050976932,-0.00013597047654911876,0.00015550745592918247,0.004763898439705372 -1769682179,247679744,0.0,0.0,0.0,1.0,-0.0013418091693893075,-0.007507083937525749,-0.0005708531243726611,-0.15172383189201355,-0.01948571763932705,0.014248869381844997 -1769682179,279182336,0.0,0.0,0.0,1.0,-0.0013004245702177286,-0.0072691296227276325,-0.0005696844309568405,-0.010101144202053547,0.07574549317359924,0.002024367218837142 -1769682179,311966976,0.0,0.0,0.0,1.0,-0.0012597094755619764,-0.007088740821927786,-0.0005661810282617807,-0.0660710483789444,-0.08512341976165771,0.016441751271486282 -1769682179,347335680,0.0,0.0,0.0,1.0,0.0003582608769647777,-0.0060461778193712234,-0.0002945964806713164,-0.019188430160284042,0.15029041469097137,-0.03285494074225426 -1769682179,378141952,0.0,0.0,0.0,1.0,0.0011844115797430277,-0.005337085109204054,-0.0001505016116425395,-0.009124631062150002,0.07458304613828659,-0.033697761595249176 -1769682179,410171648,0.0,0.0,0.0,1.0,0.0018228834960609674,-0.004866356961429119,-5.5036216508597136e-05,0.0006485152989625931,-0.000775836524553597,-0.0238204225897789 -1769682179,458592000,0.0,0.0,0.0,1.0,0.002401274163275957,-0.004480957053601742,9.70444489212241e-06,0.05608295276761055,0.16071227192878723,-0.01924324966967106 -1769682179,479586816,0.0,0.0,0.0,1.0,0.002791578182950616,-0.004397863056510687,2.0267592844902538e-05,0.08580958843231201,-0.06582386046648026,-0.0038880775682628155 -1769682179,511378944,0.0,0.0,0.0,1.0,0.003028683830052614,-0.004436098039150238,7.718954293522984e-06,0.009974123910069466,-0.07558926194906235,0.0027485063765197992 -1769682179,557864448,0.0,0.0,0.0,1.0,0.0041709220968186855,-0.005144957918673754,0.0001811425609048456,0.2907288074493408,0.11790115386247635,0.06948406994342804 -1769682179,577918720,0.0,0.0,0.0,1.0,0.006422866135835648,-0.007099725306034088,0.0004581421671900898,0.05447081848978996,0.16271580755710602,0.04138132184743881 -1769682179,612946432,0.0,0.0,0.0,1.0,0.007400590926408768,-0.008283962495625019,0.0005940645933151245,0.06464345753192902,0.08689714223146439,0.03697098046541214 -1769682179,646919680,0.0,0.0,0.0,1.0,0.004830846097320318,-0.006046747788786888,0.00037890911335125566,-0.21288368105888367,-0.11084991693496704,-0.15572090446949005 -1769682179,677808896,0.0,0.0,0.0,1.0,0.0036543291062116623,-0.0027531322557479143,0.0001483889645896852,-0.14766691625118256,-0.024727797135710716,-0.14137986302375793 -1769682179,711164928,0.0,0.0,0.0,1.0,0.0030548020731657743,-0.0009300763485953212,2.5085902962018736e-05,-0.04284627363085747,-0.24054107069969177,-0.10393743962049484 -1769682179,744339200,0.0,0.0,0.0,1.0,0.002409700071439147,0.0006291713798418641,-8.628839714219794e-05,0.0020535015501081944,-0.002705558203160763,-0.07979802042245865 -1769682179,777596928,0.0,0.0,0.0,1.0,0.002476135501638055,0.0014210343360900879,-0.00014566679601557553,-0.0850650817155838,0.06486211717128754,-0.024679535999894142 -1769682179,846876928,0.0,0.0,0.0,1.0,0.0028961743228137493,0.0021794787608087063,-0.00019627201254479587,-0.07579827308654785,-0.00979376770555973,0.005535043776035309 -1769682179,864898560,0.0,0.0,0.0,1.0,0.0031137990299612284,0.0025297733955085278,-0.0002404476108495146,-0.08608107268810272,0.06619919836521149,0.014596652239561081 -1769682179,889543424,0.0,0.0,0.0,1.0,0.0008421821985393763,-0.0016938888002187014,-0.0004911435535177588,0.31607210636138916,-0.040237970650196075,-0.13122384250164032 -1769682179,903178752,0.0,0.0,0.0,1.0,0.0003880323492921889,-0.005204866174608469,-0.000601902196649462,0.23980140686035156,-0.049419667571783066,-0.10785050690174103 -1769682179,944479232,0.0,0.0,0.0,1.0,-0.000400530087063089,-0.010664120316505432,-0.0008092127391137183,0.2487114667892456,-0.12361160665750504,-0.06459983438253403 -1769682179,977839616,0.0,0.0,0.0,1.0,-0.0009883928578346968,-0.013965184800326824,-0.0010017654858529568,0.24761174619197845,-0.12213443219661713,-0.021855076774954796 -1769682180,13137152,0.0,0.0,0.0,1.0,-0.0011916172225028276,-0.01520752813667059,-0.001116137020289898,0.21703167259693146,0.10548266023397446,-0.0054368432611227036 -1769682180,48877312,0.0,0.0,0.0,1.0,-0.0013720059068873525,-0.01565086469054222,-0.0012328044977039099,0.08503750711679459,-0.06472128629684448,0.028102677315473557 -1769682180,78032128,0.0,0.0,0.0,1.0,-0.0014014557236805558,-0.015375963412225246,-0.0012876157416030765,-0.07620164006948471,-0.009201932698488235,0.02358195185661316 -1769682180,110929152,0.0,0.0,0.0,1.0,-0.0013137011555954814,-0.014858536422252655,-0.001314813387580216,-0.0006026285700500011,0.0008912477642297745,0.026203982532024384 -1769682180,154291200,0.0,0.0,0.0,1.0,-0.0011552302166819572,-0.014077828265726566,-0.001308515900745988,0.08500757068395615,-0.06459256261587143,0.031540725380182266 -1769682180,179201536,0.0,0.0,0.0,1.0,-0.0010486620012670755,-0.0135834701359272,-0.0012740767560899258,-0.01045606192201376,0.07627014815807343,0.01746436022222042 -1769682180,213317376,0.0,0.0,0.0,1.0,-0.0004097677010577172,-0.012907223775982857,-0.00114103511441499,0.07561597228050232,0.010066060349345207,0.0012935253325849771 -1769682180,245264896,0.0,0.0,0.0,1.0,0.00012122298358008265,-0.012233695015311241,-0.0009824695298448205,0.08573547005653381,-0.06567476689815521,-0.0007346040802076459 -1769682180,278142208,0.0,0.0,0.0,1.0,0.00034030259121209383,-0.011949067004024982,-0.0008846513228490949,0.06571830809116364,0.08545146882534027,-0.007498369552195072 -1769682180,310755584,0.0,0.0,0.0,1.0,0.0005411037127487361,-0.011780548840761185,-0.0008102878928184509,0.17147673666477203,-0.13134056329727173,-0.0015889580827206373 -1769682180,347814912,0.0,0.0,0.0,1.0,0.0006636325852014124,-0.01172435563057661,-0.0007728206692263484,4.750467269332148e-05,-8.087703463388607e-05,-0.0023823417723178864 -1769682180,377898496,0.0,0.0,0.0,1.0,0.000718095398042351,-0.011784958653151989,-0.0007728249183855951,0.07582695037126541,0.00971319992095232,-0.009581727907061577 -1769682180,413083904,0.0,0.0,0.0,1.0,0.0012658146442845464,-0.012175658717751503,-0.0006901998422108591,0.15047834813594818,0.0214945487678051,0.0415319949388504 -1769682180,448822528,0.0,0.0,0.0,1.0,0.0018121183384209871,-0.012938796542584896,-0.0005768054979853332,0.05480775237083435,0.16258104145526886,0.03485612943768501 -1769682180,477817600,0.0,0.0,0.0,1.0,0.0020012652967125177,-0.013236966915428638,-0.000566903327126056,0.15066777169704437,0.021221593022346497,0.033054810017347336 -1769682180,511630080,0.0,0.0,0.0,1.0,0.00015509975492022932,-0.009243365377187729,-0.0008327045943588018,-0.06049531698226929,-0.09530238807201385,-0.28057152032852173 -1769682180,562055936,0.0,0.0,0.0,1.0,-0.00010722107253968716,-0.0028974786400794983,-0.0010195407085120678,-0.15699924528598785,0.04719046503305435,-0.2453860193490982 -1769682180,568776960,0.0,0.0,0.0,1.0,-0.00026290485402569175,-0.0004790444509126246,-0.001091843587346375,0.0793011412024498,0.0030133428517729044,-0.20627152919769287 -1769682180,610711808,0.0,0.0,0.0,1.0,-0.0005391773884184659,0.0027750071603804827,-0.001184194115921855,0.07793355733156204,0.005662316456437111,-0.1288372427225113 -1769682180,644104704,0.0,0.0,0.0,1.0,-0.0007720674620941281,0.003951811231672764,-0.0012167462846264243,0.31405818462371826,-0.03812345489859581,-0.07895658165216446 -1769682180,679825664,0.0,0.0,0.0,1.0,-0.0003862146404571831,0.00646199518814683,-0.001207819557748735,0.15188080072402954,0.018979497253894806,-0.033676113933324814 -1769682180,712359424,0.0,0.0,0.0,1.0,-9.366836457047611e-05,0.007919189520180225,-0.0011630412191152573,0.0,-0.0,0.0 -1769682180,745765632,0.0,0.0,0.0,1.0,-0.0007131251040846109,0.007756324019283056,-0.001137814950197935,0.31160175800323486,-0.03349611163139343,0.05589614063501358 -1769682180,777909248,0.0,0.0,0.0,1.0,-0.0005047241575084627,0.0017776534659788013,-0.0012264649849385023,0.3978350758552551,-0.0999692752957344,0.029994502663612366 -1769682180,811394816,0.0,0.0,0.0,1.0,-0.0006206444813869894,-0.0027916976250708103,-0.001308166771195829,0.23648013174533844,-0.044476468116045,0.028631065040826797 -1769682180,844426752,0.0,0.0,0.0,1.0,-0.0007347814389504492,-0.00669656228274107,-0.0014197365380823612,0.16067616641521454,-0.05421408638358116,0.03823617845773697 -1769682180,877831680,0.0,0.0,0.0,1.0,-0.000799360394012183,-0.008157799020409584,-0.001499520381912589,0.009680486284196377,-0.07484755665063858,0.02419375069439411 -1769682180,911016960,0.0,0.0,0.0,1.0,-0.0007733625825494528,-0.00863452535122633,-0.0015790247125551105,0.07531051337718964,0.01068706251680851,0.01770368218421936 -1769682180,959517184,0.0,0.0,0.0,1.0,-0.0007285423926077783,-0.008296934887766838,-0.0016846751095727086,-0.00021184644720051438,0.0004039415216539055,0.011912301182746887 -1769682180,977607168,0.0,0.0,0.0,1.0,-0.0006254788604564965,-0.007645928766578436,-0.0017543755238875747,0.07546577602624893,0.010412461124360561,0.009322221390902996 -1769682181,11758848,0.0,0.0,0.0,1.0,-0.0005697101005353034,-0.006858225911855698,-0.0018192770658060908,0.08551976084709167,-0.0650768131017685,0.014423404820263386 -1769682181,47821056,0.0,0.0,0.0,1.0,-0.00042658508755266666,-0.005889450665563345,-0.0018710207659751177,0.15148720145225525,0.019754862412810326,-0.013588111847639084 -1769682181,80742400,0.0,0.0,0.0,1.0,-0.0004340485611464828,-0.005286562722176313,-0.0018938713474199176,-0.15130235254764557,-0.02012632042169571,0.0028915421571582556 -1769682181,113374720,0.0,0.0,0.0,1.0,-0.0007351434323936701,-0.005029705353081226,-0.0019446766236796975,0.1612505167722702,-0.05511471629142761,0.009340684860944748 -1769682181,152300288,0.0,0.0,0.0,1.0,-0.000947769614867866,-0.004874572157859802,-0.0019638463854789734,0.0755307674407959,0.010314974933862686,0.005675872787833214 -1769682181,177933568,0.0,0.0,0.0,1.0,-0.001074329949915409,-0.004803260322660208,-0.0019409173401072621,0.09590991586446762,-0.14110398292541504,0.002759433351457119 -1769682181,215306752,0.0,0.0,0.0,1.0,-0.0011792462319135666,-0.004803566727787256,-0.0019067743560299277,0.0,-0.0,0.0 -1769682181,248352768,0.0,0.0,0.0,1.0,-0.0013184298295527697,-0.004865662194788456,-0.0018734491895884275,0.07564664632081985,0.010088209062814713,-0.0015069725923240185 -1769682181,278119424,0.0,0.0,0.0,1.0,-0.0014086241135373712,-0.004906503949314356,-0.0018852788489311934,0.07566487789154053,0.01005249097943306,-0.0027089270297437906 -1769682181,311062272,0.0,0.0,0.0,1.0,-0.0012938036816194654,-0.005158115644007921,-0.0018764834385365248,0.15095102787017822,0.02091364748775959,0.018385693430900574 -1769682181,358104576,0.0,0.0,0.0,1.0,-0.001851107575930655,-0.00511948810890317,-0.0018902972806245089,0.0851966068148613,-0.06418796628713608,0.03926793485879898 -1769682181,378497536,0.0,0.0,0.0,1.0,-0.0023268545046448708,-0.0047066956758499146,-0.001971596386283636,0.009728646837174892,-0.07465136796236038,0.0300841573625803 -1769682181,413217024,0.0,0.0,0.0,1.0,-0.003085133619606495,-0.00277676316909492,-0.002147969091311097,0.06707625836133957,0.08222203701734543,-0.10788092017173767 -1769682181,445828864,0.0,0.0,0.0,1.0,-0.003089037723839283,0.0002735104935709387,-0.0022949757985770702,-0.063907191157341,-0.0890909731388092,-0.09822123497724533 -1769682181,480269824,0.0,0.0,0.0,1.0,-0.0030941301956772804,0.0018733597826212645,-0.0023662897292524576,0.06671633571386337,0.08300609141588211,-0.08522791415452957 -1769682181,510652416,0.0,0.0,0.0,1.0,-0.003112438600510359,0.0029023224487900734,-0.002381866332143545,0.0764867290854454,0.008319022133946419,-0.0563519187271595 -1769682181,545316864,0.0,0.0,0.0,1.0,-0.0029515817295759916,0.003529055044054985,-0.0022957928013056517,-0.01987984962761402,0.15011069178581238,-0.036267492920160294 -1769682181,578261760,0.0,0.0,0.0,1.0,-0.0029986975714564323,0.003523988416418433,-0.0021533267572522163,0.010391691699624062,-0.07599513232707977,-0.010463236831128597 -1769682181,613222912,0.0,0.0,0.0,1.0,-0.0031814021058380604,0.003212588606402278,-0.001990435877814889,0.07556314766407013,0.010303279384970665,0.003242078935727477 -1769682181,645344000,0.0,0.0,0.0,1.0,-0.0034420646261423826,0.002683475846424699,-0.0018216596217826009,-0.0655747801065445,-0.08544525504112244,0.012478500604629517 -1769682181,678342400,0.0,0.0,0.0,1.0,-0.0020246380008757114,0.003099327441304922,-0.0016424694331362844,-0.0007435396546497941,0.0015115472488105297,0.04646117612719536 -1769682181,711657216,0.0,0.0,0.0,1.0,-0.001410913304425776,0.0035864384844899178,-0.001563797239214182,0.08512980490922928,-0.06397069245576859,0.04520008713006973 -1769682181,763956992,0.0,0.0,0.0,1.0,-0.0009990022517740726,0.004008132498711348,-0.0016246199375018477,-0.06589468568563461,-0.08480100333690643,0.03269390016794205 -1769682181,773145344,0.0,0.0,0.0,1.0,-0.0008593577076680958,0.004113790579140186,-0.0017256269929930568,0.06492066383361816,0.08673494309186935,0.026878487318754196 -1769682181,810800384,0.0,0.0,0.0,1.0,-0.0005904138670302927,0.004192742519080639,-0.0020118062384426594,-0.010490251705050468,0.07610205560922623,0.014061965979635715 -1769682181,846095616,0.0,0.0,0.0,1.0,-0.00036884372821077704,0.004116255324333906,-0.0023843736853450537,0.055053938180208206,0.1615726798772812,0.001652450766414404 -1769682181,880597504,0.0,0.0,0.0,1.0,-0.00017945138097275048,0.004052004311233759,-0.002664396073669195,-0.09600778669118881,0.14077943563461304,-0.008556166663765907 -1769682181,912683520,0.0,0.0,0.0,1.0,1.997037179535255e-05,0.003960067871958017,-0.002900068648159504,0.0,-0.0,0.0 -1769682181,951052544,0.0,0.0,0.0,1.0,0.0002993257367052138,0.0038610256742686033,-0.003098325105383992,0.17172855138778687,-0.13067297637462616,0.0035866000689566135 -1769682181,978164992,0.0,0.0,0.0,1.0,0.0005188895156607032,0.003819667734205723,-0.0031344385351985693,0.0757347047328949,0.010016469284892082,-0.007371059153228998 -1769682182,15655680,0.0,0.0,0.0,1.0,-0.0005503940628841519,0.0031609132420271635,-0.003303193487226963,0.020118772983551025,-0.15037931501865387,0.027881978079676628 -1769682182,49987328,0.0,0.0,0.0,1.0,-0.0013464903458952904,0.002358220284804702,-0.0033579599112272263,0.06478359550237656,0.08686015754938126,0.02933601848781109 -1769682182,77963008,0.0,0.0,0.0,1.0,-0.0017797263571992517,0.0019574447069317102,-0.003315796609967947,0.08544335514307022,-0.06447330862283707,0.02743380516767502 -1769682182,110877440,0.0,0.0,0.0,1.0,-0.0022470266558229923,0.001700322492979467,-0.003264378057792783,0.1407465934753418,0.09645938873291016,0.007712622173130512 -1769682182,163701248,0.0,0.0,0.0,1.0,-0.0027577949222177267,0.0016188420122489333,-0.0032386225648224354,-0.08583257347345352,0.06514692306518555,-0.005989940371364355 -1769682182,170761472,0.0,0.0,0.0,1.0,-0.0029966826550662518,0.001639399561099708,-0.0032625538296997547,-0.08581558614969254,0.06510350853204727,-0.0071802097372710705 -1769682182,212899072,0.0,0.0,0.0,1.0,-0.0034002189058810472,0.001757744001224637,-0.003389133373275399,0.0859927088022232,-0.06539719551801682,-0.0023527792654931545 -1769682182,244773632,0.0,0.0,0.0,1.0,-0.004432597663253546,0.0023793107829988003,-0.003625419456511736,0.010187418200075626,-0.07532232254743576,0.009731253609061241 -1769682182,283875584,0.0,0.0,0.0,1.0,-0.0063511403277516365,0.0038580968976020813,-0.0038435827009379864,0.16131235659122467,-0.054523125290870667,0.014155345968902111 -1769682182,311256576,0.0,0.0,0.0,1.0,-0.006950422190129757,0.00481422059237957,-0.004015012644231319,-0.06578479707241058,-0.08498448133468628,0.03130057081580162 -1769682182,346972160,0.0,0.0,0.0,1.0,-0.00604492099955678,0.004348698537796736,-0.0041014645248651505,-0.0012822819408029318,0.002187692327424884,0.0702878013253212 -1769682182,378061568,0.0,0.0,0.0,1.0,-0.00585634121671319,0.00393233448266983,-0.004171410575509071,0.08518391102552414,-0.06390030682086945,0.04409964010119438 -1769682182,412907008,0.0,0.0,0.0,1.0,-0.005631681997328997,0.003507888177409768,-0.004219294060021639,0.07495740056037903,0.011428145691752434,0.03443387150764465 -1769682182,447930112,0.0,0.0,0.0,1.0,-0.005229269154369831,0.003088385798037052,-0.004235217347741127,0.07552767544984818,0.010487010702490807,0.003471449948847294 -1769682182,477929728,0.0,0.0,0.0,1.0,-0.005063674878329039,0.002842099405825138,-0.004197207745164633,0.010294487699866295,-0.07539819180965424,0.007255807053297758 -1769682182,511987456,0.0,0.0,0.0,1.0,-0.005956469569355249,0.0021287668496370316,-0.0041016219183802605,0.08638735115528107,-0.06579360365867615,-0.01905245892703533 -1769682182,562764288,0.0,0.0,0.0,1.0,-0.00702047860249877,0.0010372839169576764,-0.003915797919034958,0.021438274532556534,-0.1520816534757614,-0.028439387679100037 -1769682182,570880256,0.0,0.0,0.0,1.0,-0.007305367849767208,0.0006308761658146977,-0.0037941255141049623,0.06571804732084274,0.08510301262140274,-0.031118223443627357 -1769682182,611119104,0.0,0.0,0.0,1.0,-0.0031310953199863434,0.0026426345575600863,-0.0031470591202378273,-0.07644522190093994,-0.009083401411771774,0.045341674238443375 -1769682182,648583680,0.0,0.0,0.0,1.0,-0.0014410328585654497,0.004614310804754496,-0.0026561529375612736,-0.01104310154914856,0.07648930698633194,0.02973521314561367 -1769682182,680379904,0.0,0.0,0.0,1.0,-0.000813163467682898,0.0056550148874521255,-0.0024446379393339157,-0.096775121986866,0.141129270195961,0.01186250988394022 -1769682182,711170304,0.0,0.0,0.0,1.0,-0.0003399732813704759,0.006306705065071583,-0.00238225981593132,-0.09671790897846222,0.14101672172546387,0.008272719569504261 -1769682182,745210624,0.0,0.0,0.0,1.0,0.0001298926945310086,0.006752265617251396,-0.0024683258961886168,-0.17210642993450165,0.13023914396762848,-0.0024639989715069532 -1769682182,778194944,0.0,0.0,0.0,1.0,0.00041381572373211384,0.006796426139771938,-0.002639457816258073,-0.07555953413248062,-0.0104928994551301,-0.001195696066133678 -1769682182,813406976,0.0,0.0,0.0,1.0,0.0005685166106559336,0.006658308207988739,-0.002864172914996743,-0.09628024697303772,0.1402886062860489,-0.015621902421116829 -1769682182,849250304,0.0,0.0,0.0,1.0,0.0007206090958788991,0.00647440692409873,-0.003179736901074648,0.021100925281643867,-0.15131284296512604,-0.0034495654981583357 -1769682182,877591808,0.0,0.0,0.0,1.0,0.000911205483134836,0.006265922915190458,-0.0033547680359333754,0.07575172185897827,0.01023426279425621,-0.00828621257096529 -1769682182,910779136,0.0,0.0,0.0,1.0,0.0002234536368632689,0.0057220603339374065,-0.0035663016606122255,-0.14193987846374512,-0.09471090883016586,0.06307628750801086 -1769682182,958366720,0.0,0.0,0.0,1.0,-0.0016132195014506578,0.004126626532524824,-0.00391934160143137,0.009342290461063385,-0.0739106759428978,0.05725144222378731 -1769682182,978040320,0.0,0.0,0.0,1.0,-0.0023058983497321606,0.0032307414803653955,-0.003959484398365021,0.13979917764663696,0.09774068742990494,0.038236260414123535 -1769682183,11014912,0.0,0.0,0.0,1.0,-0.002940207486972213,0.0026799142360687256,-0.0039052043575793505,-0.12015403807163239,-0.2468828409910202,0.032150812447071075 -1769682183,44585472,0.0,0.0,0.0,1.0,-0.0037241133395582438,0.0023267243523150682,-0.0037883948534727097,-0.1513490378856659,-0.020780423656105995,0.009319236502051353 -1769682183,81070592,0.0,0.0,0.0,1.0,-0.004235519096255302,0.002290459116920829,-0.003750848351046443,0.1406160593032837,0.0966014564037323,-0.002200519433245063 -1769682183,111453440,0.0,0.0,0.0,1.0,-0.004790384788066149,0.00233808858320117,-0.0037909988313913345,0.16165253520011902,-0.054396502673625946,0.003843824379146099 -1769682183,146172928,0.0,0.0,0.0,1.0,-0.005887514445930719,0.003046529134735465,-0.004163210745900869,0.0122139323502779,-0.07775150239467621,-0.0750359445810318 -1769682183,178017280,0.0,0.0,0.0,1.0,-0.008364285342395306,0.004720669239759445,-0.004657129291445017,-0.4208557605743408,-0.2911358177661896,-0.0341951809823513 -1769682183,211712000,0.0,0.0,0.0,1.0,-0.009968558326363564,0.006391693372279406,-0.005117727909237146,-0.29088976979255676,-0.11888506263494492,-0.035193976014852524 -1769682183,252104448,0.0,0.0,0.0,1.0,-0.007767495233565569,0.0059040687046945095,-0.0053301015868783,-0.34667056798934937,0.26232102513313293,0.08403456956148148 -1769682183,278980608,0.0,0.0,0.0,1.0,-0.006340550258755684,0.004547544755041599,-0.005369139369577169,0.12786564230918884,0.1748262345790863,0.08865980058908463 -1769682183,311116544,0.0,0.0,0.0,1.0,-0.0054018497467041016,0.0033340686932206154,-0.0053880177438259125,0.13878165185451508,0.09888819605112076,0.07553107291460037 -1769682183,357858304,0.0,0.0,0.0,1.0,-0.00431695906445384,0.002157385228201747,-0.005330835003405809,-0.01174788549542427,0.07688244432210922,0.047735199332237244 -1769682183,377856000,0.0,0.0,0.0,1.0,-0.003593222238123417,0.0015664725797250867,-0.005201473366469145,-0.0005902435514144599,0.0007128643919713795,0.02621009759604931 -1769682183,411567872,0.0,0.0,0.0,1.0,-0.002944892505183816,0.0012105499627068639,-0.004987332504242659,-0.01094274315983057,0.07586796581745148,0.010818205773830414 -1769682183,446922752,0.0,0.0,0.0,1.0,-0.005185260437428951,-0.0006598361069336534,-0.00458071893081069,-0.13920728862285614,-0.09833411127328873,-0.052979495376348495 -1769682183,479557888,0.0,0.0,0.0,1.0,-0.005886925850063562,-0.0016303674783557653,-0.0042237224988639355,0.15206894278526306,0.02022077888250351,-0.04244174063205719 -1769682183,512032256,0.0,0.0,0.0,1.0,-0.0033972603268921375,-0.0002621131425257772,-0.003667488694190979,-0.4762422740459442,0.08873254805803299,0.06445827335119247 -1769682183,547097600,0.0,0.0,0.0,1.0,-0.0012046616757288575,0.0038520253729075193,-0.002928379690274596,-0.012412508949637413,0.07753011584281921,0.07400377839803696 -1769682183,578233600,0.0,0.0,0.0,1.0,-0.00047543770051561296,0.006217905320227146,-0.0025798147544264793,-0.011780058965086937,0.07676992565393448,0.04541059583425522 -1769682183,615292416,0.0,0.0,0.0,1.0,-2.414062328170985e-05,0.007822168990969658,-0.002401995239779353,-0.44337546825408936,-0.13887423276901245,0.03523634746670723 -1769682183,649936128,0.0,0.0,0.0,1.0,0.0003618259506765753,0.009022951126098633,-0.0023734949063509703,0.15036888420581818,0.022262675687670708,0.03154740482568741 -1769682183,677749504,0.0,0.0,0.0,1.0,0.0006612243596464396,0.009242872707545757,-0.002466561971232295,0.15075236558914185,0.021831979975104332,0.014909337274730206 -1769682183,712308480,0.0,0.0,0.0,1.0,0.0007364003686234355,0.009191918186843395,-0.002625751309096813,-0.1618049293756485,0.054039161652326584,-0.0029139439575374126 -1769682183,756403456,0.0,0.0,0.0,1.0,0.000915625540073961,0.008818906731903553,-0.0029102296102792025,-0.31243306398391724,0.0320330485701561,-0.022743243724107742 -1769682183,778220032,0.0,0.0,0.0,1.0,0.0009692883468233049,0.008502264507114887,-0.0031151901930570602,0.12997229397296906,0.17211812734603882,-0.0180908665060997 -1769682183,811082752,0.0,0.0,0.0,1.0,0.0010780716547742486,0.008175971917808056,-0.0032895973417907953,0.010885036550462246,-0.0756589025259018,-0.003680700436234474 -1769682183,844367872,0.0,0.0,0.0,1.0,-0.00015239507774822414,0.007069895509630442,-0.003685643896460533,-0.13020989298820496,-0.17186273634433746,0.028749510645866394 -1769682183,882293504,0.0,0.0,0.0,1.0,-0.0007208219612948596,0.006275065243244171,-0.0038200586568564177,-0.31344786286354065,0.03297097980976105,0.017445065081119537 -1769682183,911704320,0.0,0.0,0.0,1.0,-0.0010550286388024688,0.005708483513444662,-0.0038227008190006018,0.17202436923980713,-0.12882506847381592,0.028082264587283134 -1769682183,945933312,0.0,0.0,0.0,1.0,-0.0014065623981878161,0.005332753993570805,-0.0036675857845693827,-0.15131375193595886,-0.02133570797741413,0.008610520511865616 -1769682183,978624000,0.0,0.0,0.0,1.0,-0.0016924516530707479,0.005225545261055231,-0.0034576859325170517,0.15069738030433655,0.02198299765586853,0.015239899046719074 -1769682184,14724608,0.0,0.0,0.0,1.0,-0.001943667302839458,0.005267034284770489,-0.0032272383105009794,0.17255046963691711,-0.12927207350730896,0.009092938154935837 -1769682184,50726912,0.0,0.0,0.0,1.0,-0.0022325932513922453,0.005395027343183756,-0.0029508720617741346,0.010860658250749111,-0.07555456459522247,-0.00011197877756785601 -1769682184,78807040,0.0,0.0,0.0,1.0,-0.004459402058273554,0.006813358515501022,-0.0031977647449821234,0.17490176856517792,-0.131548210978508,-0.07901650667190552 -1769682184,111357696,0.0,0.0,0.0,1.0,-0.005192469339817762,0.007810321170836687,-0.003423101268708706,0.0022204318083822727,-0.0021737865172326565,-0.08338868618011475 -1769682184,159827200,0.0,0.0,0.0,1.0,-0.004776004236191511,0.008035171777009964,-0.0035110902972519398,-0.022414498031139374,0.15171757340431213,0.024104153737425804 -1769682184,167794688,0.0,0.0,0.0,1.0,-0.002594619058072567,0.005554221570491791,-0.003390805795788765,-0.17693211138248444,0.13330329954624176,0.15042957663536072 -1769682184,212857600,0.0,0.0,0.0,1.0,-0.0008187074563466012,0.001464197994209826,-0.003223160747438669,0.006979743950068951,-0.07184035331010818,0.14399665594100952 -1769682184,244878336,0.0,0.0,0.0,1.0,0.00032862284570001066,-0.0013606990687549114,-0.0031425629276782274,0.13705790042877197,0.10019487142562866,0.11447838693857193 -1769682184,286494464,0.0,0.0,0.0,1.0,0.0010510432766750455,-0.0026641455478966236,-0.003083288436755538,-0.013179858215153217,0.0776926800608635,0.0835334062576294 -1769682184,327664896,0.0,0.0,0.0,1.0,0.001784670283086598,-0.003382953582331538,-0.002970445901155472,-0.18471784889698029,0.20573106408119202,0.03264705091714859 -1769682184,349917952,0.0,0.0,0.0,1.0,0.00030193623388186097,-0.004791888874024153,-0.0026923236437141895,0.16290141642093658,-0.0546545535326004,-0.03357737138867378 -1769682184,378195456,0.0,0.0,0.0,1.0,-0.0006101603503338993,-0.0057999733835458755,-0.0024279814679175615,0.012020496651530266,-0.07658886164426804,-0.040646735578775406 -1769682184,413976320,0.0,0.0,0.0,1.0,-0.001277644420042634,-0.006309026386588812,-0.0021310653537511826,-0.28980377316474915,-0.12043912708759308,-0.05229801684617996 -1769682184,454022144,0.0,0.0,0.0,1.0,0.00027709297137334943,-0.0031416907440871,-0.0015634767478331923,-0.4648730754852295,0.010898318141698837,0.028029225766658783 -1769682184,478759936,0.0,0.0,0.0,1.0,0.0004150093882344663,-0.0007891713757999241,-0.001240528654307127,-0.16255129873752594,0.054274290800094604,0.02056843973696232 -1769682184,512066048,0.0,0.0,0.0,1.0,0.00039832768379710615,0.0010416670702397823,-0.0010333112441003323,-0.29130232334136963,-0.11900661885738373,0.004947696812450886 -1769682184,555194880,0.0,0.0,0.0,1.0,0.00043054501293227077,0.002556165447458625,-0.000888905837200582,-0.46405795216560364,0.010048472322523594,-0.002967705950140953 -1769682184,578429184,0.0,0.0,0.0,1.0,0.000350409623933956,0.003105703042820096,-0.0008779558120295405,-0.312583327293396,0.031440142542123795,-0.01863584853708744 -1769682184,610994688,0.0,0.0,0.0,1.0,0.00025262130657210946,0.0033391104079782963,-0.0009357804083265364,-0.17263838648796082,0.12893331050872803,-0.012693247757852077 -1769682184,647163392,0.0,0.0,0.0,1.0,0.00018620197079144418,0.0032406512182205915,-0.0010861626360565424,0.14025750756263733,0.09719978272914886,-0.005921425297856331 -1769682184,680471296,0.0,0.0,0.0,1.0,0.000266209157416597,0.0030162641778588295,-0.0012138637248426676,0.12922348082065582,0.17280538380146027,-0.0033874623477458954 -1769682184,711142400,0.0,0.0,0.0,1.0,0.0002709034306462854,0.0027613453567028046,-0.0013228515163064003,0.00012819832772947848,-0.00012320790847297758,-0.0047650584019720554 -1769682184,750648320,0.0,0.0,0.0,1.0,0.0008083308930508792,0.002639816841110587,-0.0013051169225946069,-0.02104763686656952,0.15021318197250366,-0.03308536484837532 -1769682184,778555392,0.0,0.0,0.0,1.0,0.0016952925361692905,0.0029178906697779894,-0.0011465915013104677,-0.13921086490154266,-0.09821023792028427,-0.03224301338195801 -1769682184,810897920,0.0,0.0,0.0,1.0,0.0022549391724169254,0.003114636056125164,-0.0009551113471388817,0.30263569951057434,0.04319196194410324,-0.01913844794034958 -1769682184,845110784,0.0,0.0,0.0,1.0,0.0027204633224755526,0.0033629536628723145,-0.0006642460357397795,0.011242074891924858,-0.07578559964895248,-0.009645743295550346 -1769682184,878930688,0.0,0.0,0.0,1.0,0.00297286594286561,0.003447770606726408,-0.0004446402017492801,-0.15069837868213654,-0.02219347096979618,-0.013095758855342865 -1769682184,911782144,0.0,0.0,0.0,1.0,0.003103413386270404,0.0034701682161539793,-0.0002498906687833369,-0.12905751168727875,-0.1729568988084793,-0.0013973963214084506 -1769682184,950171904,0.0,0.0,0.0,1.0,0.003093710634857416,0.003500770078971982,-3.825207386398688e-05,0.13984274864196777,0.09760942310094833,0.00845219288021326 -1769682184,980032512,0.0,0.0,0.0,1.0,0.0019378387369215488,0.004070088267326355,-8.581690781284124e-05,0.035136111080646515,-0.22869080305099487,-0.07886603474617004 -1769682185,10799872,0.0,0.0,0.0,1.0,0.0001293806853936985,0.005473950412124395,-0.0004544564289972186,-0.13804273307323456,-0.09931507706642151,-0.07280456274747849 -1769682185,64437504,0.0,0.0,0.0,1.0,0.00045073829824104905,0.0056985062547028065,-0.0008114277152344584,0.013133598491549492,-0.0775565430521965,-0.07631200551986694 -1769682185,71960064,0.0,0.0,0.0,1.0,0.0013319369172677398,0.0049737985245883465,-0.0008930564508773386,0.2897099554538727,0.12058493494987488,0.05032525211572647 -1769682185,115186688,0.0,0.0,0.0,1.0,0.0022236460354179144,0.0013499140040948987,-0.0008873086771927774,0.2987985610961914,0.046837396919727325,0.11698785424232483 -1769682185,144814848,0.0,0.0,0.0,1.0,0.0028074716683477163,-0.0013918253825977445,-0.0008410544833168387,0.008561499416828156,-0.07324588298797607,0.08570826798677444 -1769682185,178042880,0.0,0.0,0.0,1.0,0.003079516813158989,-0.0027246475219726562,-0.000766515382565558,0.2887542247772217,0.12151901423931122,0.08365140110254288 -1769682185,212009728,0.0,0.0,0.0,1.0,0.003372559556737542,-0.003580052638426423,-0.0006659523351117969,-0.023269742727279663,0.1522865742444992,0.04535653814673424 -1769682185,249141504,0.0,0.0,0.0,1.0,0.0023390850983560085,-0.004645941779017448,-0.00046855639084242284,-0.1286221146583557,-0.17336934804916382,-0.015625223517417908 -1769682185,279004416,0.0,0.0,0.0,1.0,0.001199680264107883,-0.005632334854453802,-0.0003150894190184772,-0.1395556926727295,-0.09790132939815521,-0.01794276013970375 -1769682185,310983936,0.0,0.0,0.0,1.0,0.0004320814332459122,-0.00623695645481348,-0.00017144459707196802,0.1627451628446579,-0.05432701110839844,-0.025042090564966202 -1769682185,350478336,0.0,0.0,0.0,1.0,0.00029727720539085567,-0.006108992733061314,0.0001046504476107657,-0.139693483710289,-0.09777381271123886,-0.013114603236317635 -1769682185,379672064,0.0,0.0,0.0,1.0,0.00034285092260688543,-0.00551921222358942,0.0003984282957389951,0.17308388650417328,-0.1292182207107544,-0.0013258091639727354 -1769682185,411182336,0.0,0.0,0.0,1.0,0.00028032163390889764,-0.004968433640897274,0.0007269311463460326,-0.14002330601215363,-0.09744749963283539,-0.0011549661867320538 -1769682185,455595776,0.0,0.0,0.0,1.0,0.00017413095338270068,-0.00432054977864027,0.0011934987269341946,0.15127874910831451,0.021648269146680832,-0.008443884551525116 -1769682185,478672640,0.0,0.0,0.0,1.0,0.00014668551739305258,-0.0039448244497179985,0.001511473092250526,-0.14003172516822815,-0.09743588417768478,-0.0011110615450888872 -1769682185,511415808,0.0,0.0,0.0,1.0,-3.6654055293183774e-05,-0.003718241583555937,0.0017603758024051785,0.16188505291938782,-0.05351453274488449,0.005770289339125156 -1769682185,546429440,0.0,0.0,0.0,1.0,-0.0002668657689355314,-0.0035736465360969305,0.001905490760691464,-0.3020525276660919,-0.04376253858208656,-0.0020570112392306328 -1769682185,582432256,0.0,0.0,0.0,1.0,-0.0004779541050083935,-0.003520710626617074,0.0018879681592807174,0.17279422283172607,-0.12900911271572113,0.008061856031417847 -1769682185,612080896,0.0,0.0,0.0,1.0,-0.0005199588485993445,-0.0035498610232025385,0.0018066754564642906,-0.011036291718482971,0.07560282200574875,0.002434143330901861 -1769682185,646096896,0.0,0.0,0.0,1.0,-0.0004968306748196483,-0.0036526808980852365,0.0016888167010620236,0.010843628086149693,-0.0754101425409317,0.0047101653181016445 -1769682185,678163456,0.0,0.0,0.0,1.0,0.0007845675572752953,-0.00319404574111104,0.0018171812407672405,-0.16062982380390167,0.0522751621901989,-0.053319547325372696 -1769682185,711651072,0.0,0.0,0.0,1.0,0.0019258095417171717,-0.0024666949175298214,0.002031161682680249,0.4540901482105255,0.06447778642177582,-0.03527986630797386 -1769682185,750999040,0.0,0.0,0.0,1.0,0.0029396137688308954,-0.0017652472015470266,0.0023199869319796562,0.0008023168775252998,-0.0008430004818364978,-0.03097257763147354 -1769682185,779922944,0.0,0.0,0.0,1.0,0.0035337810404598713,-0.0014717660378664732,0.0025407124776393175,0.0007391974795609713,-0.0007810805691406131,-0.02859002910554409 -1769682185,811439616,0.0,0.0,0.0,1.0,0.0039311358705163,-0.0013128208229318261,0.0027615635190159082,0.15116164088249207,0.021669942885637283,-0.0038503119722008705 -1769682185,855815424,0.0,0.0,0.0,1.0,0.004230204503983259,-0.001296886010095477,0.003027057508006692,-0.010871347971260548,0.07547847926616669,-0.0023636738769710064 -1769682185,878994944,0.0,0.0,0.0,1.0,0.00448996014893055,-0.0013745370088145137,0.003198821796104312,-0.1510433405637741,-0.021768998354673386,-0.0008943468565121293 -1769682185,912609792,0.0,0.0,0.0,1.0,0.0025002218317240477,-0.0001598841045051813,0.0029830974526703358,0.023367850109934807,-0.15275053679943085,-0.05956679582595825 -1769682185,945880064,0.0,0.0,0.0,1.0,0.0016640729736536741,0.0007797982543706894,0.002774721011519432,0.17415449023246765,-0.13075345754623413,-0.049133703112602234 -1769682185,982674176,0.0,0.0,0.0,1.0,0.0013677319511771202,0.0009740724926814437,0.0026940875686705112,-0.009922710247337818,0.07448261231184006,-0.03812653198838234 -1769682186,11603200,0.0,0.0,0.0,1.0,0.0014641163870692253,0.0005137366824783385,0.002653977135196328,-0.12931691110134125,-0.17274565994739532,0.0015067453496158123 -1769682186,51321088,0.0,0.0,0.0,1.0,0.0012563776690512896,-4.6807064791209996e-05,0.0026160439010709524,0.010521660558879375,-0.0751492902636528,0.014309505000710487 -1769682186,77724160,0.0,0.0,0.0,1.0,0.0012018663110211492,-0.0004711732908617705,0.0025798871647566557,0.15056446194648743,0.022221848368644714,0.019953977316617966 -1769682186,114795776,0.0,0.0,0.0,1.0,0.0010482108918949962,-0.0007914404268376529,0.002540785353630781,0.010387917049229145,-0.07501585781574249,0.019079282879829407 -1769682186,148741888,0.0,0.0,0.0,1.0,0.000667074229568243,-0.0012188294203951955,0.00252342876046896,0.02149650827050209,-0.15083789825439453,0.009574074298143387 -1769682186,178274816,0.0,0.0,0.0,1.0,-2.5434288545511663e-05,-0.0019461213378235698,0.00254729762673378,-0.1399516761302948,-0.09747063368558884,-0.010383588261902332 -1769682186,211140352,0.0,0.0,0.0,1.0,-0.0004984595580026507,-0.0024358376394957304,0.00257872068323195,0.010919974185526371,-0.07562199980020523,-0.0023621038999408484 -1769682186,263136000,0.0,0.0,0.0,1.0,-0.0005034119822084904,-0.002741999924182892,0.002713786670938134,0.15082243084907532,0.021888643503189087,0.010379675775766373 -1769682186,273630720,0.0,0.0,0.0,1.0,-0.000332717812852934,-0.0025211870670318604,0.002828374970704317,-0.00018151174299418926,0.0002011886826949194,0.007147427648305893 -1769682186,312374272,0.0,0.0,0.0,1.0,-0.00024461813154630363,-0.0019356890115886927,0.003079719375818968,-0.1513100117444992,-0.021325647830963135,0.008700558915734291 -1769682186,346065664,0.0,0.0,0.0,1.0,-0.00022009357053320855,-0.0014791953144595027,0.0033152890391647816,-0.3130315840244293,0.0324777327477932,0.0007298020645976067 -1769682186,379869440,0.0,0.0,0.0,1.0,-0.0001404077047482133,-0.001244989107362926,0.003473760327324271,0.010820308700203896,-0.07556043565273285,1.2385964510031044e-05 -1769682186,411340032,0.0,0.0,0.0,1.0,-0.0002484980795998126,-0.001097654108889401,0.0035922310780733824,0.30209261178970337,0.04315239563584328,0.004000292159616947 -1769682186,447377152,0.0,0.0,0.0,1.0,-0.00020267553918529302,-0.0010099249193444848,0.0037211121525615454,0.021542461588978767,-0.1510593444108963,0.0024032900109887123 -1769682186,478476288,0.0,0.0,0.0,1.0,-0.00017206513439305127,-0.001020770170725882,0.0037934514693915844,0.02158518135547638,-0.15112878382205963,1.937340130098164e-05 -1769682186,512043520,0.0,0.0,0.0,1.0,-0.0001716319820843637,-0.001051929546520114,0.0038580200634896755,0.010783891193568707,-0.0755656436085701,8.992195944301784e-06 -1769682186,550672640,0.0,0.0,0.0,1.0,-9.629621490603313e-05,-0.0011051557958126068,0.003908125218003988,-0.010653025470674038,0.07543334364891052,-0.004773076623678207 -1769682186,595102464,0.0,0.0,0.0,1.0,-6.337212107609957e-05,-0.0011852554744109511,0.003927500452846289,0.3235882520675659,-0.1081138402223587,0.006344199180603027 -1769682186,600774400,0.0,0.0,0.0,1.0,0.0001813458657125011,-0.0011031932663172483,0.003967210650444031,-0.010163242928683758,0.07489953190088272,-0.02383221872150898 -1769682186,649190400,0.0,0.0,0.0,1.0,0.0009140431648120284,-0.0005830927984789014,0.004107284359633923,-0.16130468249320984,0.053565770387649536,-0.02222413383424282 -1769682186,680381184,0.0,0.0,0.0,1.0,0.001177242142148316,-0.0003802192222792655,0.004154627211391926,0.17274199426174164,-0.12996402382850647,-0.0063547613099217415 -1769682186,710953216,0.0,0.0,0.0,1.0,0.0014104304136708379,-0.0002650090027600527,0.004198825918138027,-0.15080565214157104,-0.021700773388147354,-0.012679838575422764 -1769682186,746274560,0.0,0.0,0.0,1.0,0.0016524423845112324,-0.0002087415923597291,0.004282156005501747,0.15110543370246887,0.021338798105716705,0.0007646456360816956 -1769682186,778422272,0.0,0.0,0.0,1.0,0.0018107837531715631,-0.00020143685105722398,0.004375359043478966,0.30186137557029724,0.043043673038482666,0.015820102766156197 -1769682186,814015744,0.0,0.0,0.0,1.0,0.0014335684245452285,0.0001087150230887346,0.004345462191849947,0.022090818732976913,-0.15197010338306427,-0.028536096215248108 -1769682186,846355712,0.0,0.0,0.0,1.0,0.000460596609627828,0.0008461877005174756,0.004241136834025383,-0.1397266834974289,-0.09766754508018494,-0.02932444028556347 -1769682186,878167296,0.0,0.0,0.0,1.0,0.00030595928546972573,0.0010821610921993852,0.0041577173396945,-0.16107407212257385,0.05351388454437256,-0.029389282688498497 -1769682186,911330560,0.0,0.0,0.0,1.0,0.00024354123161174357,0.0010648096213117242,0.004099028185009956,0.14046119153499603,0.09681927412748337,0.0007423481438308954 -1769682186,949843456,0.0,0.0,0.0,1.0,0.00025049224495887756,0.0003242763632442802,0.00404608016833663,0.31223973631858826,-0.03241601213812828,0.02779393643140793 -1769682186,978990848,0.0,0.0,0.0,1.0,0.00021099133300594985,-7.982878014445305e-05,0.004012509249150753,0.1291981041431427,0.1731126308441162,0.026918426156044006 -1769682187,11431936,0.0,0.0,0.0,1.0,0.000236133360886015,-0.00041585470899008214,0.003983588423579931,-0.3028503358364105,-0.04167090356349945,0.022274039685726166 -1769682187,45978368,0.0,0.0,0.0,1.0,0.00030159071320667863,-0.0007843670318834484,0.003937614616006613,-0.00011855229968205094,0.0001358778972644359,0.004764963872730732 -1769682187,78776832,0.0,0.0,0.0,1.0,-0.0004400131874717772,-0.001224498264491558,0.003913856577128172,0.010844138450920582,-0.07586236298084259,-0.009496788494288921 -1769682187,111397888,0.0,0.0,0.0,1.0,-0.0010264203883707523,-0.001728940405882895,0.003867845982313156,-0.010421332903206348,0.07538820058107376,-0.007178178057074547 -1769682187,145334784,0.0,0.0,0.0,1.0,-0.0012733644107356668,-0.0021444791927933693,0.0038282466121017933,0.3023390769958496,0.042117003351449966,-0.0008848896250128746 -1769682187,179147520,0.0,0.0,0.0,1.0,-0.00034806234179995954,-0.0017716471338644624,0.00388111243955791,-0.16224929690361023,0.05512934923171997,0.020678460597991943 -1769682187,211876608,0.0,0.0,0.0,1.0,-0.0004873014986515045,-0.0005086290766485035,0.003932655788958073,-0.010921233333647251,0.07600213587284088,0.014272653497755527 -1769682187,247332864,0.0,0.0,0.0,1.0,-0.00027062027947977185,0.000820061017293483,0.004033912904560566,-0.15150047838687897,-0.020626945421099663,0.013556075282394886 -1769682187,278175744,0.0,0.0,0.0,1.0,-0.00018309359438717365,0.001456083613447845,0.0041353232227265835,0.15056341886520386,0.021691076457500458,0.024569910019636154 -1769682187,311123200,0.0,0.0,0.0,1.0,-2.5859691959340125e-05,0.0018821504199877381,0.004234627354890108,-0.17217159271240234,0.13013750314712524,-0.003179040504619479 -1769682187,348065792,0.0,0.0,0.0,1.0,1.0861956980079412e-05,0.002093595452606678,0.004339130595326424,-0.00011811262083938345,0.0001353569678030908,0.004764989484101534 -1769682187,378236416,0.0,0.0,0.0,1.0,-2.691574627533555e-05,0.002109964145347476,0.004361398052424192,-0.14070351421833038,-0.09648531675338745,0.0016308326739817858 -1769682187,412659712,0.0,0.0,0.0,1.0,-0.00010133533214684576,0.0020466367714107037,0.004344196990132332,-0.14053738117218018,-0.09667591005563736,-0.005525355227291584 -1769682187,457763072,0.0,0.0,0.0,1.0,-0.00015800399705767632,0.0018551863031461835,0.004281759262084961,0.14097099006175995,0.09617196023464203,-0.011140618473291397 -1769682187,478818560,0.0,0.0,0.0,1.0,-8.515903755323961e-05,0.0017272176919505,0.0042122965678572655,0.333667129278183,-0.18491940200328827,0.006446538958698511 -1769682187,511754240,0.0,0.0,0.0,1.0,-0.00014608771016355604,0.0016062805661931634,0.004141063429415226,5.973563384031877e-05,-6.768169987481087e-05,-0.002382477978244424 -1769682187,545292544,0.0,0.0,0.0,1.0,8.688194793649018e-05,0.0016728887567296624,0.004078955389559269,0.010580937378108501,-0.07574637234210968,-0.004739671479910612 -1769682187,579043072,0.0,0.0,0.0,1.0,0.0003561774792615324,0.001809396781027317,0.004047691822052002,-0.010211983695626259,0.07534139603376389,-0.009556307457387447 -1769682187,612193792,0.0,0.0,0.0,1.0,0.0003944534691981971,0.0019229432800784707,0.004031546879559755,0.16162239015102386,-0.05480930209159851,0.0008655756246298552 -1769682187,649303552,0.0,0.0,0.0,1.0,0.0006851960206404328,0.0020363954827189445,0.004101330880075693,-0.2918749451637268,-0.11724232137203217,-0.004050170071423054 -1769682187,678301952,0.0,0.0,0.0,1.0,0.0008931756019592285,0.002101543825119734,0.004223336465656757,-0.14082485437393188,-0.0963093489408493,0.0015573492273688316 -1769682187,711814144,0.0,0.0,0.0,1.0,0.000914997945073992,0.002197733148932457,0.004360667429864407,-6.058796134311706e-05,6.795654917368665e-05,0.00238244840875268 -1769682187,748490240,0.0,0.0,0.0,1.0,0.0001137163199018687,0.0028218745719641447,0.00434616394340992,0.13106442987918854,0.17120611667633057,-0.025400983169674873 -1769682187,778409984,0.0,0.0,0.0,1.0,-0.00048474103095941246,0.0032768698874861,0.0043267542496323586,0.2924273908138275,0.11653543263673782,-0.014922097325325012 -1769682187,811956224,0.0,0.0,0.0,1.0,-0.00047310261288657784,0.0033900532871484756,0.004297169391065836,-0.14014437794685364,-0.09704580157995224,-0.02708069235086441 -1769682187,848953600,0.0,0.0,0.0,1.0,0.0002453564666211605,0.002394620329141617,0.004338324535638094,0.019069315865635872,-0.149412602186203,0.06440537422895432 -1769682187,878656512,0.0,0.0,0.0,1.0,0.00011796712351497263,0.001100094523280859,0.004308372735977173,0.2802770137786865,0.1940750777721405,0.05658778175711632 -1769682187,911353856,0.0,0.0,0.0,1.0,7.632288179593161e-05,0.00011132210784126073,0.004240420181304216,0.18076352775096893,-0.20463736355304718,0.05824003741145134 -1769682187,946092800,0.0,0.0,0.0,1.0,0.0001863854704424739,-0.0007799710729159415,0.0041249413043260574,0.16049513220787048,-0.05388636887073517,0.04147794097661972 -1769682187,969774848,0.0,0.0,0.0,1.0,0.00021190552797634155,-0.0010189207969233394,0.0040625762194395065,-0.0005538943223655224,0.0006125649670138955,0.021441787481307983 -1769682188,12771840,0.0,0.0,0.0,1.0,-0.0010541274677962065,-0.0019398482982069254,0.00397489033639431,0.031313374638557434,-0.22730140388011932,-0.014175409451127052 -1769682188,45420288,0.0,0.0,0.0,1.0,-0.0019937604665756226,-0.0027630103286355734,0.003880060277879238,0.0006114179850555956,-0.0006788612809032202,-0.02382473647594452 -1769682188,78422016,0.0,0.0,0.0,1.0,-0.0024691526778042316,-0.0030472837388515472,0.0038074448239058256,0.1621234267950058,-0.05580354109406471,-0.02289925515651703 -1769682188,112635904,0.0,0.0,0.0,1.0,-0.0012478240532800555,-0.002314138924703002,0.003871307009831071,0.16114357113838196,-0.05473925173282623,0.015204830095171928 -1769682188,145570816,0.0,0.0,0.0,1.0,-0.0008480299147777259,-0.0011740241898223758,0.00399703299626708,0.010031553916633129,-0.07536652684211731,0.009549194946885109 -1769682188,178821376,0.0,0.0,0.0,1.0,-0.0005155939725227654,-0.0004362268664408475,0.004155060276389122,-0.15128852427005768,-0.020380083471536636,0.0015069656074047089 -1769682188,213282816,0.0,0.0,0.0,1.0,-0.0001732774544507265,3.7640165828634053e-05,0.004344519227743149,-0.1614854335784912,0.055211104452610016,-0.0008923497516661882 -1769682188,261636352,0.0,0.0,0.0,1.0,-5.200679152039811e-05,0.0004271690850146115,0.0046000853180885315,-0.010301666334271431,0.07570859044790268,0.0023655034601688385 -1769682188,270596864,0.0,0.0,0.0,1.0,2.146129554603249e-05,0.0005638924776576459,0.004706148989498615,0.010294604115188122,-0.07570955902338028,-0.0023654336109757423 -1769682188,311745280,0.0,0.0,0.0,1.0,8.993774827104062e-06,0.0005779579514637589,0.004857469350099564,0.15117953717708588,0.020425140857696533,0.0032647131010890007 -1769682188,352008704,0.0,0.0,0.0,1.0,1.3183504051994532e-05,0.0005529058980755508,0.004938286729156971,6.060964005882852e-05,-6.751748151145875e-05,-0.00238246051594615 -1769682188,373915648,0.0,0.0,0.0,1.0,-4.1288854845333844e-05,0.0005018365918658674,0.004940494894981384,0.1409882754087448,0.09602753818035126,0.003252242226153612 -1769682188,412870144,0.0,0.0,0.0,1.0,-0.00011287709639873356,0.00038465778925456107,0.0049159643240273,-0.01000030618160963,0.0754464864730835,-0.007164696231484413 -1769682188,447109120,0.0,0.0,0.0,1.0,-0.0001804815256036818,0.0003427108458708972,0.0048502665013074875,0.00012135178985772654,-0.00013503505033440888,-0.004764917306602001 -1769682188,478397952,0.0,0.0,0.0,1.0,0.00013948645209893584,0.00044945665285922587,0.004826754331588745,-0.1507713496685028,-0.020771969109773636,-0.019953716546297073 -1769682188,511364352,0.0,0.0,0.0,1.0,0.000357979501131922,0.0005927394959144294,0.004797069821506739,-0.02023056522011757,0.15124037861824036,-0.0024185744114220142 -1769682188,551355904,0.0,0.0,0.0,1.0,0.0004968398716300726,0.0007603769772686064,0.0047480822540819645,-6.0778125771321356e-05,6.761577969882637e-05,0.00238245353102684 -1769682188,579677952,0.0,0.0,0.0,1.0,0.0005923358839936554,0.0008425572887063026,0.004713045433163643,-0.2821703553199768,-0.19176937639713287,-0.006529383827000856 -1769682188,615031552,0.0,0.0,0.0,1.0,0.0007059078197926283,0.000844764756038785,0.004692947492003441,-0.1412203460931778,-0.09572941064834595,0.0014986651949584484 -1769682188,650803456,0.0,0.0,0.0,1.0,0.00040418520802631974,0.00112243986222893,0.004615945275872946,-0.16027167439460754,0.054330144077539444,-0.043821174651384354 -1769682188,678814464,0.0,0.0,0.0,1.0,-0.000701473152730614,0.0021385818254202604,0.004440908320248127,0.04131907597184181,-0.30373260378837585,-0.03801799193024635 -1769682188,712560128,0.0,0.0,0.0,1.0,-0.0012172608403488994,0.0028823153115808964,0.004353038035333157,0.16227255761623383,-0.056609272956848145,-0.03478005900979042 -1769682188,758314496,0.0,0.0,0.0,1.0,-0.001305907964706421,0.0032376088201999664,0.004330418072640896,-0.17103727161884308,0.13088102638721466,-0.015289082191884518 -1769682188,778153984,0.0,0.0,0.0,1.0,-0.0006846472970210016,0.0024900324642658234,0.004378082230687141,0.15054340660572052,0.020834237337112427,0.02955540083348751 -1769682188,811433472,0.0,0.0,0.0,1.0,-0.0006021794979460537,0.0018013641238212585,0.004347349517047405,0.17025841772556305,-0.13011644780635834,0.04389701038599014 -1769682188,846280448,0.0,0.0,0.0,1.0,-0.0006618669722229242,0.0010614660568535328,0.004187512211501598,0.16045212745666504,-0.05474699288606644,0.034355420619249344 -1769682188,882013184,0.0,0.0,0.0,1.0,-0.0005841453676111996,0.0006841428694315255,0.004017591010779142,0.15054816007614136,0.020768597722053528,0.029577404260635376 -1769682188,911660032,0.0,0.0,0.0,1.0,-0.0004919945495203137,0.0003443141176830977,0.003836133750155568,0.01934073492884636,-0.15060241520404816,0.02623693272471428 -1769682188,946583552,0.0,0.0,0.0,1.0,-0.0023183126468211412,-0.0010611191391944885,0.0036850625183433294,0.31315386295318604,-0.03644014522433281,-0.019454043358564377 -1769682188,979260928,0.0,0.0,0.0,1.0,-0.003106995252892375,-0.0019146361155435443,0.0035857846960425377,0.16197268664836884,-0.05650917813181877,-0.02522071823477745 -1769682189,15362304,0.0,0.0,0.0,1.0,-0.0031589181162416935,-0.0023337900638580322,0.003547870321199298,0.29268208146095276,0.1153816357254982,-0.00042788591235876083 -1769682189,47866368,0.0,0.0,0.0,1.0,-0.0018214249284937978,-0.0020769317634403706,0.003684221999719739,0.2926987409591675,0.11533928662538528,-0.0004421505145728588 -1769682189,78713088,0.0,0.0,0.0,1.0,-0.0012103035114705563,-0.0019013907294720411,0.003840565448626876,-0.15100079774856567,-0.020179780200123787,-0.012867806479334831 -1769682189,128368384,0.0,0.0,0.0,1.0,-0.0007470683776773512,-0.0017748859245330095,0.0040262662805616856,0.31263649463653564,-0.03608723729848862,-0.0005062571726739407 -1769682189,164241664,0.0,0.0,0.0,1.0,-0.00033095802064053714,-0.001532157650217414,0.0043108584359288216,0.17077161371707916,-0.1310930848121643,0.01757275126874447 -1769682189,172947712,0.0,0.0,0.0,1.0,-9.071662498172373e-05,-0.0013533525634557009,0.004469086416065693,0.4735125005245209,-0.09166030585765839,0.01467068213969469 -1769682189,211900160,0.0,0.0,0.0,1.0,0.00017108296742662787,-0.0011695546563714743,0.004796348977833986,0.1511971354484558,0.019894953817129135,0.0056915306486189365 -1769682189,249548288,0.0,0.0,0.0,1.0,0.00018374498176854104,-0.0010224509751424193,0.005032418295741081,0.15132276713848114,0.01973210833966732,0.0009198387851938605 -1769682189,278759168,0.0,0.0,0.0,1.0,0.00011446404096204787,-0.0009589367546141148,0.00508419144898653,-0.009895389899611473,0.07568711042404175,2.1887230104766786e-05 -1769682189,314056704,0.0,0.0,0.0,1.0,-2.125085302395746e-05,-0.0010063465451821685,0.0050608194433152676,0.00012110588431823999,-0.00013299980491865426,-0.004764981102198362 -1769682189,351264256,0.0,0.0,0.0,1.0,-0.00025775551330298185,-0.0010676352540031075,0.00487794354557991,0.29279667139053345,0.1150025874376297,0.0018322481773793697 -1769682189,378772736,0.0,0.0,0.0,1.0,-0.0002497760870028287,-0.0010426973458379507,0.004662760067731142,0.16137473285198212,-0.05625695735216141,-0.006271445658057928 -1769682189,414870528,0.0,0.0,0.0,1.0,-0.0002675468858797103,-0.0009981421753764153,0.004417282063513994,0.14173150062561035,0.0950414389371872,-0.008609794080257416 -1769682189,450635520,0.0,0.0,0.0,1.0,-0.0001896619505714625,-0.0009085565689019859,0.004062993917614222,0.17119240760803223,-0.13200068473815918,-0.006309111602604389 -1769682189,479181056,0.0,0.0,0.0,1.0,-5.437678919406608e-05,-0.0008753169095143676,0.0038276626728475094,0.3128145933151245,-0.036886632442474365,-0.010166849941015244 -1769682189,512443904,0.0,0.0,0.0,1.0,0.0001401766639901325,-0.0008737770840525627,0.0036382321268320084,0.1513460874557495,0.0195541400462389,0.000881821964867413 -1769682189,558027008,0.0,0.0,0.0,1.0,0.00036662674392573535,-0.0008523893775418401,0.0035202677827328444,0.17102311551570892,-0.13193105161190033,-0.0015573063865303993 -1769682189,578625792,0.0,0.0,0.0,1.0,0.0006983387283980846,-0.000882812135387212,0.0035776831209659576,0.1512911468744278,0.01958310976624489,0.003254591953009367 -1769682189,611581952,0.0,0.0,0.0,1.0,-0.000672589463647455,-5.308130494086072e-05,0.0033837887458503246,0.33321666717529297,-0.18936504423618317,-0.04360111430287361 -1769682189,646156544,0.0,0.0,0.0,1.0,-0.002133101923391223,0.0013507070252671838,0.003263290273025632,0.3039092421531677,0.03763318061828613,-0.04589694365859032 -1769682189,685717760,0.0,0.0,0.0,1.0,-0.002988931955769658,0.0021273810416460037,0.0032431993167847395,0.4549126923084259,0.05747097730636597,-0.030694629997015 -1769682189,712314624,0.0,0.0,0.0,1.0,-0.002512563019990921,0.0019772248342633247,0.003284007078036666,0.4730692207813263,-0.09245961904525757,0.024054918438196182 -1769682189,745963264,0.0,0.0,0.0,1.0,-0.0018958128057420254,0.0019166967831552029,0.003271052148193121,0.161118283867836,-0.0562739335000515,0.0008652908727526665 -1769682189,780475648,0.0,0.0,0.0,1.0,-0.0018372408812865615,0.0019559680949896574,0.0031634375918656588,0.31211352348327637,-0.036478400230407715,0.016087330877780914 -1769682189,812425728,0.0,0.0,0.0,1.0,-0.001744579174555838,0.001895525841973722,0.0029749993700534105,0.3026093542575836,0.03893670439720154,0.006626085378229618 -1769682189,851633408,0.0,0.0,0.0,1.0,-0.0015619004843756557,0.0016989109572023153,0.0026617376133799553,0.4634106159210205,-0.01709221489727497,0.019448168575763702 -1769682189,879987968,0.0,0.0,0.0,1.0,-0.0016752011142671108,0.001434995443560183,0.002465334953740239,0.17094703018665314,-0.13217388093471527,-0.003934761509299278 -1769682189,911592448,0.0,0.0,0.0,1.0,-0.003319271607324481,0.000170413579326123,0.0023181429132819176,0.4646861255168915,-0.01853114925324917,-0.03055701032280922 -1769682189,964670720,0.0,0.0,0.0,1.0,-0.004149359650909901,-0.0010641328990459442,0.0021927959751337767,0.47354790568351746,-0.09337081015110016,0.002705057617276907 -1769682189,972282368,0.0,0.0,0.0,1.0,-0.003610385349020362,-0.0010788504732772708,0.002213261555880308,0.4539358913898468,0.058223433792591095,0.010004397481679916 -1769682190,11847424,0.0,0.0,0.0,1.0,-0.0019382762257009745,-0.0014643990434706211,0.002444279845803976,0.31263700127601624,-0.03724675625562668,-0.005346739664673805 -1769682190,48937984,0.0,0.0,0.0,1.0,-0.0006657687481492758,-0.0020224922336637974,0.002865877700969577,0.010060486383736134,-0.07609827816486359,-0.014392559416592121 -1769682190,81521920,0.0,0.0,0.0,1.0,-0.00013079015479888767,-0.0022223598789423704,0.0032405152451246977,0.3221381902694702,-0.112830251455307,0.0016564344987273216 -1769682190,112289536,0.0,0.0,0.0,1.0,0.00012397860700730234,-0.0022853605914860964,0.0035941440146416426,0.31226348876953125,-0.0369565449655056,0.008881294168531895 -1769682190,154836992,0.0,0.0,0.0,1.0,0.0003754090575966984,-0.0022108247503638268,0.003964446950703859,0.009551056660711765,-0.07558745890855789,0.0046659731306135654 -1769682190,178361344,0.0,0.0,0.0,1.0,0.0002861497341655195,-0.0021818852983415127,0.004092338494956493,0.3216773569583893,-0.11250225454568863,0.018264273181557655 -1769682190,215500032,0.0,0.0,0.0,1.0,0.00019490608246997,-0.0021628979593515396,0.004099864512681961,0.7664164900779724,0.020586170256137848,0.01145988516509533 -1769682190,249787648,0.0,0.0,0.0,1.0,-2.833864709828049e-05,-0.002090835478156805,0.003920593298971653,0.30266469717025757,0.03852487727999687,0.00650374498218298 -1769682190,279828480,0.0,0.0,0.0,1.0,-0.00020198131096549332,-0.0019419826567173004,0.003673977917060256,0.17059804499149323,-0.13219678401947021,0.0030419628601521254 -1769682190,311578880,0.0,0.0,0.0,1.0,-0.00022110791178420186,-0.001910931197926402,0.00335500156506896,0.3028511106967926,0.038266152143478394,-0.0006790691986680031 -1769682190,362312448,0.0,0.0,0.0,1.0,-0.0003614319139160216,-0.0019260091939941049,0.0028953319415450096,0.33122795820236206,-0.18842600286006927,0.018049828708171844 -1769682190,369936384,0.0,0.0,0.0,1.0,-0.00047661270946264267,-0.002006281167268753,0.0026711297687143087,0.31217411160469055,-0.037189677357673645,0.01109546609222889 -1769682190,412788224,0.0,0.0,0.0,1.0,-0.00039561637095175683,-0.0019998482894152403,0.002294224686920643,0.5956509709358215,0.15260519087314606,0.01769310235977173 -1769682190,446608384,0.0,0.0,0.0,1.0,-0.00040092525887303054,-0.0020298033487051725,0.0020178919658064842,0.1609412580728531,-0.056550368666648865,0.00308520020917058 -1769682190,479571968,0.0,0.0,0.0,1.0,-0.00031677939114160836,-0.0020773583091795444,0.0018953593680635095,0.5958499908447266,0.15232715010643005,0.010464025661349297 -1769682190,511858176,0.0,0.0,0.0,1.0,-0.00018469130736775696,-0.0021498925052583218,0.0018518317956477404,0.3123405873775482,-0.037475116550922394,0.003856282914057374 -1769682190,547803904,0.0,0.0,0.0,1.0,-5.4667390941176564e-05,-0.0022539666388183832,0.001900196890346706,0.3122459948062897,-0.037367083132267,0.008594051003456116 -1769682190,580916992,0.0,0.0,0.0,1.0,-3.0275321478256956e-05,-0.0022260372061282396,0.002005724934861064,0.4543973207473755,0.05702734738588333,-0.004842262249439955 -1769682190,612194816,0.0,0.0,0.0,1.0,-0.0017354983137920499,-0.0009888468775898218,0.0017691184766590595,0.3231177031993866,-0.11461030691862106,-0.04635847359895706 -1769682190,648814080,0.0,0.0,0.0,1.0,-0.003748547751456499,0.0008316035964526236,0.0015284355031326413,0.313426673412323,-0.03876863047480583,-0.041480910032987595 -1769682190,679000320,0.0,0.0,0.0,1.0,-0.004298394080251455,0.0015197244938462973,0.0014285384677350521,0.31238773465156555,-0.03763262927532196,0.0014148098416626453 -1769682190,712092160,0.0,0.0,0.0,1.0,-0.004343403968960047,0.0014843330718576908,0.0013585538836196065,0.1512962430715561,0.019168537110090256,0.005548945628106594 -1769682190,759838464,0.0,0.0,0.0,1.0,-0.003264801809564233,0.0019455334404483438,0.0013179327361285686,0.6061734557151794,0.07556861639022827,-0.018256526440382004 -1769682190,780916736,0.0,0.0,0.0,1.0,-0.0029592099599540234,0.0021497556008398533,0.001205169945023954,0.15182052552700043,0.018589023500680923,-0.015870563685894012 -1769682190,812938496,0.0,0.0,0.0,1.0,-0.002725583966821432,0.0021945154294371605,0.0010467888787388802,0.15153071284294128,0.018897902220487595,-0.003945796750485897 -1769682190,846929152,0.0,0.0,0.0,1.0,-0.002306598937138915,0.002171624219045043,0.0008082757703959942,0.3028879463672638,0.03797253966331482,-0.000713348388671875 -1769682190,880115456,0.0,0.0,0.0,1.0,-0.001990671269595623,0.0020811003632843494,0.0006385599845089018,0.6244056224822998,-0.07503324747085571,0.017326386645436287 -1769682190,912455936,0.0,0.0,0.0,1.0,-0.0017127281753346324,0.00201333686709404,0.00048668222734704614,0.4824179410934448,-0.16966350376605988,0.021090570837259293 -1769682190,948278784,0.0,0.0,0.0,1.0,-0.0035355999134480953,0.0005468783201649785,0.0004177898808848113,0.4738101661205292,-0.0949305072426796,-0.01684391498565674 -1769682190,984675840,0.0,0.0,0.0,1.0,-0.0036541391164064407,-0.00014571619976777583,0.00040074135176837444,0.1610199213027954,-0.056786272674798965,-0.001712349010631442 -1769682191,12779776,0.0,0.0,0.0,1.0,-0.0036427383311092854,-0.00044490923755802214,0.00041143051930703223,0.46367478370666504,-0.01859430968761444,0.007161719258874655 -1769682191,46962432,0.0,0.0,0.0,1.0,-0.001539295306429267,-0.0018269428983330727,0.0006492176908068359,0.757317841053009,0.09476397931575775,-0.005224777385592461 -1769682191,79062784,0.0,0.0,0.0,1.0,-0.0009327696170657873,-0.002672410337254405,0.0007716190884821117,0.46408483386039734,-0.0190422423183918,-0.009576240554451942 -1769682191,115261952,0.0,0.0,0.0,1.0,-0.0004611989133991301,-0.0032109469175338745,0.0008608903735876083,0.46385008096694946,-0.018810251727700233,-8.802395313978195e-05 -1769682191,148716544,0.0,0.0,0.0,1.0,-1.3306108485267032e-05,-0.0034746932797133923,0.0009470792720094323,0.32185104489326477,-0.1134272962808609,0.0035781185142695904 -1769682191,179350528,0.0,0.0,0.0,1.0,0.0002799405774567276,-0.0034189128782600164,0.001014637527987361,0.6339888572692871,-0.15095791220664978,0.014458946883678436 -1769682191,211706368,0.0,0.0,0.0,1.0,0.0005224536871537566,-0.003351967316120863,0.0010665480513125658,0.30278196930885315,0.038020018488168716,0.003953711595386267 -1769682191,259422464,0.0,0.0,0.0,1.0,0.0006337331142276525,-0.0031190933659672737,0.0010968941496685147,0.6241093277931213,-0.07490531355142593,0.028834976255893707 -1769682191,278562304,0.0,0.0,0.0,1.0,0.0006806491874158382,-0.0029522825498133898,0.0010722674196586013,0.30284273624420166,0.03793613612651825,0.0015033334493637085 -1769682191,311617792,0.0,0.0,0.0,1.0,0.0005546837928704917,-0.0027379312086850405,0.0010010841069743037,0.3122536540031433,-0.037685576826334,0.006025024689733982 -1769682191,362011904,0.0,0.0,0.0,1.0,0.0004652848874684423,-0.002631671493873,0.0008238848531618714,0.4730265438556671,-0.09429018944501877,0.013645772822201252 -1769682191,387758592,0.0,0.0,0.0,1.0,0.00024222000502049923,-0.002666712272912264,0.0006231189472600818,0.6242234110832214,-0.07510055601596832,0.023850426077842712 -1769682191,403127296,0.0,0.0,0.0,1.0,-0.0001393557759001851,-0.002791577484458685,0.0004417201562318951,0.9078658819198608,0.11445379257202148,0.03280233219265938 -1769682191,446471168,0.0,0.0,0.0,1.0,-0.000622440769802779,-0.0031747817993164062,7.355141133302823e-05,0.4726913273334503,-0.09394331276416779,0.027805859223008156 -1769682191,479953152,0.0,0.0,0.0,1.0,-0.0007313871756196022,-0.0033458976540714502,-9.584064537193626e-05,0.6242848634719849,-0.07517452538013458,0.021272923797369003 -1769682191,514359040,0.0,0.0,0.0,1.0,-0.0009375240188091993,-0.003461203072220087,-0.0002358443452976644,0.766248881816864,0.019455445930361748,0.019699405878782272 -1769682191,551419136,0.0,0.0,0.0,1.0,-0.001050469116307795,-0.003456978825852275,-0.00038966815918684006,0.6149929165840149,0.0003274492919445038,0.01181676797568798 -1769682191,579179264,0.0,0.0,0.0,1.0,-0.0011279338505119085,-0.0034709349274635315,-0.0005123508744873106,0.7663078308105469,0.019414246082305908,0.017132224515080452 -1769682191,611521792,0.0,0.0,0.0,1.0,-0.0011950187617912889,-0.0034517114982008934,-0.0006308716256171465,0.4637358784675598,-0.01879543997347355,0.0039416151121258736 -1769682191,659773184,0.0,0.0,0.0,1.0,-0.001252377638593316,-0.0033836711663752794,-0.0007759295403957367,0.44463613629341125,0.13274729251861572,0.006744483485817909 -1769682191,669243392,0.0,0.0,0.0,1.0,-0.0012129262322559953,-0.003352049272507429,-0.0008472804329358041,0.9178965091705322,0.03824561834335327,0.010318216867744923 -1769682191,712596224,0.0,0.0,0.0,1.0,-0.0022414838895201683,-0.002488338388502598,-0.000976241601165384,0.46325430274009705,-0.018214445561170578,0.025237619876861572 -1769682191,745391872,0.0,0.0,0.0,1.0,-0.004033022094517946,-0.0007591426838189363,-0.0014652637764811516,0.4741833806037903,-0.0954895168542862,-0.03700864687561989 -1769682191,783191808,0.0,0.0,0.0,1.0,-0.005109442863613367,0.00046484963968396187,-0.0018185232765972614,0.5026320815086365,-0.32247939705848694,-0.03069162555038929 -1769682191,812822016,0.0,0.0,0.0,1.0,-0.005324019584804773,0.0008300026529468596,-0.0020173864904791117,0.454363614320755,0.056868962943553925,-0.003095912281423807 -1769682191,848068096,0.0,0.0,0.0,1.0,-0.00518486462533474,0.0011000511003658175,-0.002166410442441702,0.47377362847328186,-0.0949072614312172,-0.017966018989682198 -1769682191,878652672,0.0,0.0,0.0,1.0,-0.0039187646470963955,0.0018099856097251177,-0.0021422547288239002,0.6065804958343506,0.07507887482643127,-0.0382051020860672 -1769682191,912241408,0.0,0.0,0.0,1.0,-0.003267846303060651,0.002369451569393277,-0.0021335617639124393,0.6254189014434814,-0.07604728639125824,-0.026877805590629578 -1769682191,948102400,0.0,0.0,0.0,1.0,-0.0028332669753581285,0.002723420737311244,-0.0021478133276104927,0.6153767108917236,0.00026029348373413086,-0.005050518549978733 -1769682191,979258624,0.0,0.0,0.0,1.0,-0.002376534976065159,0.002829192904755473,-0.0021721485536545515,0.46385639905929565,-0.0186344925314188,-0.0008531310595571995 -1769682192,13441024,0.0,0.0,0.0,1.0,-0.002147453371435404,0.0027882561553269625,-0.0021972826216369867,0.7664280533790588,0.019808152690529823,0.01236813422292471 -1769682192,67093248,0.0,0.0,0.0,1.0,-0.0016669431934133172,0.0025443180929869413,-0.0022163332905620337,0.624351441860199,-0.07469919323921204,0.020990822464227676 -1769682192,75052288,0.0,0.0,0.0,1.0,-0.001614073757082224,0.0023948887828737497,-0.0022176457569003105,0.7757618427276611,-0.055594608187675476,0.021678384393453598 -1769682192,111588864,0.0,0.0,0.0,1.0,-0.0013216702500358224,0.002067866502329707,-0.002162722870707512,0.6245245933532715,-0.07479013502597809,0.01392051950097084 -1769682192,157732864,0.0,0.0,0.0,1.0,-0.0026485782582312822,0.0009019740391522646,-0.002070453716441989,0.6152123212814331,0.0007011592388153076,0.0023827310651540756 -1769682192,182136832,0.0,0.0,0.0,1.0,-0.003096171887591481,0.0004457723698578775,-0.002051610965281725,0.46380916237831116,-0.018376924097537994,0.0017057866789400578 -1769682192,212041472,0.0,0.0,0.0,1.0,-0.0032368493266403675,0.00015380946570076048,-0.001991030527278781,0.7472939491271973,0.1714615672826767,0.00858381763100624 -1769682192,246156288,0.0,0.0,0.0,1.0,-0.0011528629111126065,-0.0015636829193681479,-0.0017567561008036137,0.7476698756217957,0.1711212545633316,-0.008114228025078773 -1769682192,280134400,0.0,0.0,0.0,1.0,-0.0006189410341903567,-0.0023836172185838223,-0.0016493742587044835,0.47353726625442505,-0.09412656724452972,-0.0034808428026735783 -1769682192,312901120,0.0,0.0,0.0,1.0,-0.00023448264983016998,-0.002882951172068715,-0.0015929111978039145,0.6250505447387695,-0.0750652626156807,-0.007621907629072666 -1769682192,348914176,0.0,0.0,0.0,1.0,0.00011503659334266558,-0.003212848911061883,-0.0015567216323688626,0.463924765586853,-0.018352588638663292,-0.0032043559476733208 -1769682192,378974464,0.0,0.0,0.0,1.0,0.0003632660664152354,-0.0032380514312535524,-0.0015438959235325456,0.47316882014274597,-0.09365789592266083,0.013055559247732162 -1769682192,415116800,0.0,0.0,0.0,1.0,0.0005476935766637325,-0.003249439410865307,-0.001538692507892847,0.7757488489151001,-0.05506151169538498,0.023774530738592148 -1769682192,450559488,0.0,0.0,0.0,1.0,0.0006862735608592629,-0.003181226085871458,-0.001547582563944161,0.7661755681037903,0.020650522783398628,0.02166777290403843 -1769682192,479228160,0.0,0.0,0.0,1.0,0.0007180006359703839,-0.0030624617356806993,-0.0015530904056504369,0.46349626779556274,-0.017808102071285248,0.015667354688048363 -1769682192,511994112,0.0,0.0,0.0,1.0,0.0007835426367819309,-0.002905749250203371,-0.0015601558843627572,0.45391133427619934,0.057876452803611755,0.013616630807518959 -1769682192,560964096,0.0,0.0,0.0,1.0,0.0007217552629299462,-0.0026571338530629873,-0.0015704995021224022,0.6151602864265442,0.0011680275201797485,0.004211879801005125 -1769682192,578834688,0.0,0.0,0.0,1.0,0.000732834218069911,-0.0025529656559228897,-0.0015887253684923053,0.6149477362632751,0.0014237798750400543,0.013695579022169113 -1769682192,613125376,0.0,0.0,0.0,1.0,0.0006482164026238024,-0.0023992755450308323,-0.001620489521883428,0.927328884601593,-0.035763148218393326,0.016716228798031807 -1769682192,646133504,0.0,0.0,0.0,1.0,-0.00025922851637005806,-0.002794964239001274,-0.0018995276186615229,0.47269120812416077,-0.09288499504327774,0.03653451055288315 -1769682192,679258112,0.0,0.0,0.0,1.0,-0.0007241725688800216,-0.0031145925167948008,-0.002097197575494647,0.7660234570503235,0.021117068827152252,0.028326069936156273 -1769682192,713584128,0.0,0.0,0.0,1.0,-0.0010812358232215047,-0.0034659593366086483,-0.0022836264688521624,0.7850462198257446,-0.12992458045482635,0.041795115917921066 -1769682192,750086400,0.0,0.0,0.0,1.0,-0.001342040835879743,-0.0037444611079990864,-0.002501089358702302,0.7661830186843872,0.02107076905667782,0.020989425480365753 -1769682192,779542784,0.0,0.0,0.0,1.0,-0.0015128608793020248,-0.003725485410541296,-0.0026288642548024654,0.7759162783622742,-0.05464087426662445,0.018136143684387207 -1769682192,813151488,0.0,0.0,0.0,1.0,-0.0016004022909328341,-0.003601053263992071,-0.0027368837036192417,0.7568062543869019,0.0965663343667984,0.006914704106748104 -1769682192,847503616,0.0,0.0,0.0,1.0,-0.001689239637926221,-0.0035013954620808363,-0.002854268066585064,0.4638345241546631,-0.017788609489798546,0.0008316035382449627 -1769682192,879376384,0.0,0.0,0.0,1.0,-0.0017840139335021377,-0.0034383400343358517,-0.002946801483631134,0.46373432874679565,-0.017636286094784737,0.005548564251512289 -1769682192,912013312,0.0,0.0,0.0,1.0,-0.0017324587097391486,-0.003409259021282196,-0.00304845767095685,0.7859066724777222,-0.13034570217132568,0.005446839611977339 -1769682192,950059520,0.0,0.0,0.0,1.0,-0.0017592826625332236,-0.0035403536166995764,-0.003181066829711199,0.7858231067657471,-0.1301364302635193,0.010094148106873035 -1769682192,980860160,0.0,0.0,0.0,1.0,-0.001706936745904386,-0.0036283605732023716,-0.003296254901215434,0.6247392296791077,-0.0737205371260643,0.010075523518025875 -1769682193,11702784,0.0,0.0,0.0,1.0,-0.0016643929993733764,-0.0035668627824634314,-0.0034304119180887938,0.7566518187522888,0.09714001417160034,0.011181214824318886 -1769682193,47362560,0.0,0.0,0.0,1.0,-0.002684203675016761,-0.0030612775590270758,-0.0036461963318288326,0.605073869228363,0.07806191593408585,0.02031003311276436 -1769682193,79363328,0.0,0.0,0.0,1.0,-0.0031243006233125925,-0.002456242684274912,-0.0038496050983667374,0.9076492190361023,0.11713814735412598,0.028019297868013382 -1769682193,115243008,0.0,0.0,0.0,1.0,-0.003408127697184682,-0.0018837684765458107,-0.004068861715495586,0.32200294733047485,-0.11225210875272751,0.011607730761170387 -1769682193,147981312,0.0,0.0,0.0,1.0,-0.003525076899677515,-0.0013244753936305642,-0.004464710596948862,0.48310786485671997,-0.16837947070598602,0.013782765716314316 -1769682193,179280128,0.0,0.0,0.0,1.0,-0.004519549198448658,-0.0003207888512406498,-0.00494892755523324,0.4451187551021576,0.1332460641860962,-0.0391850471496582 -1769682193,214515200,0.0,0.0,0.0,1.0,-0.004900453146547079,0.0001366647338727489,-0.005290435627102852,0.8986203074455261,0.19244597852230072,-0.012083565816283226 -1769682193,247763968,0.0,0.0,0.0,1.0,-0.005053437780588865,0.0003565022780094296,-0.005533195566385984,0.7666597366333008,0.021920502185821533,-0.0037860143929719925 -1769682193,279480832,0.0,0.0,0.0,1.0,-0.005238384939730167,0.0002859826199710369,-0.005585601553320885,0.46386557817459106,-0.01698782481253147,0.00039209285750985146 -1769682193,312031488,0.0,0.0,0.0,1.0,-0.0038350564427673817,0.0009205691167153418,-0.005411629099398851,0.6062080264091492,0.07748691737651825,-0.0392928346991539 -1769682193,359963392,0.0,0.0,0.0,1.0,-0.0027601353358477354,0.0017325002700090408,-0.005152937024831772,0.6156542301177979,0.002345588058233261,-0.020708050578832626 -1769682193,380021760,0.0,0.0,0.0,1.0,-0.002428509294986725,0.002111028879880905,-0.005002666264772415,0.6253728270530701,-0.07309271395206451,-0.014051693491637707 -1769682193,412257536,0.0,0.0,0.0,1.0,-0.0021200012415647507,0.002301853848621249,-0.004891543183475733,0.6153087019920349,0.002895444631576538,-0.003947046585381031 -1769682193,446171136,0.0,0.0,0.0,1.0,-0.0017919255187734962,0.0022486650850623846,-0.004785648547112942,0.6151092052459717,0.003220846876502037,0.00564189488068223 -1769682193,478739200,0.0,0.0,0.0,1.0,-0.0016733617521822453,0.002245226176455617,-0.004738982301205397,0.9174609184265137,0.043061815202236176,0.020712388679385185 -1769682193,512081664,0.0,0.0,0.0,1.0,-0.0014957148814573884,0.0020111985504627228,-0.004700388293713331,0.7758428454399109,-0.05203055590391159,0.02938292920589447 -1769682193,546704896,0.0,0.0,0.0,1.0,-0.0013247266178950667,0.0015992692206054926,-0.004643590189516544,0.45360708236694336,0.059674423187971115,0.01784253865480423 -1769682193,579264256,0.0,0.0,0.0,1.0,-0.001170980278402567,0.0014791327994316816,-0.004564768634736538,0.46363717317581177,-0.016045495867729187,0.012547601014375687 -1769682193,612361984,0.0,0.0,0.0,1.0,-0.0009947496000677347,0.001468118280172348,-0.004448273219168186,0.6051565408706665,0.07935480773448944,0.0063733370043337345 -1769682193,646774272,0.0,0.0,0.0,1.0,-0.000882210792042315,0.0012932006502524018,-0.0042370096780359745,0.7661613821983337,0.023876721039414406,0.018180059269070625 -1769682193,679475200,0.0,0.0,0.0,1.0,-0.0008304798393510282,0.0012914917897433043,-0.004060184583067894,0.4537730813026428,0.05972661077976227,0.008400430902838707 -1769682193,713177088,0.0,0.0,0.0,1.0,-0.0009671509033069015,0.001427148119546473,-0.00390170281752944,0.7760831117630005,-0.051561929285526276,0.020065857097506523 -1769682193,747572224,0.0,0.0,0.0,1.0,-0.0014609933132305741,0.0010898271575570107,-0.0036029298789799213,0.7665579915046692,0.0237693153321743,-0.0007821805775165558 -1769682193,779918080,0.0,0.0,0.0,1.0,-0.002188263460993767,0.0008185450569726527,-0.0034783913288265467,0.4740036427974701,-0.0917007103562355,-0.00458503607660532 -1769682193,812407296,0.0,0.0,0.0,1.0,-0.00273119262419641,0.0005417198990471661,-0.003516973927617073,0.624954104423523,-0.07136812806129456,0.012540621683001518 -1769682193,850705408,0.0,0.0,0.0,1.0,-0.0032010998111218214,4.665483720600605e-05,-0.0036595643032342196,0.604928195476532,0.08005846291780472,0.013700703158974648 -1769682193,880772352,0.0,0.0,0.0,1.0,-0.0019042888889089227,-0.0011310745030641556,-0.0036764147225767374,0.6156110167503357,0.003808002918958664,-0.01787582039833069 -1769682193,913802752,0.0,0.0,0.0,1.0,-0.0015060659497976303,-0.0018881302094087005,-0.0038241303991526365,0.6251342296600342,-0.07129047065973282,0.005334330257028341 -1769682193,958906624,0.0,0.0,0.0,1.0,-0.001101608737371862,-0.002422854769974947,-0.004113208502531052,0.45401790738105774,0.05988067016005516,-0.005875533912330866 -1769682193,979348224,0.0,0.0,0.0,1.0,-0.0009093806147575378,-0.0025412137620151043,-0.004475744441151619,0.7760871052742004,-0.05073299631476402,0.022320661693811417 -1769682194,12319488,0.0,0.0,0.0,1.0,-0.0007828436209820211,-0.0023651535157114267,-0.004889796953648329,0.47378218173980713,-0.09097269177436829,0.009540685452520847 -1769682194,46405120,0.0,0.0,0.0,1.0,-0.00036617444129660726,-0.0022523950319737196,-0.005428626202046871,0.6049145460128784,0.08052897453308105,0.011090772226452827 -1769682194,79870976,0.0,0.0,0.0,1.0,-3.673670289572328e-05,-0.0021017577964812517,-0.005739865358918905,0.7661729454994202,0.02518046274781227,0.015593476593494415 -1769682194,112108288,0.0,0.0,0.0,1.0,0.000478890142403543,-0.0018821271369233727,-0.005922690499573946,0.7862380743026733,-0.12584899365901947,0.021490463986992836 -1769682194,148675328,0.0,0.0,0.0,1.0,0.0009085358469747007,-0.001621023751795292,-0.005987906828522682,0.6049193143844604,0.0808335691690445,0.008589173667132854 -1769682194,179611648,0.0,0.0,0.0,1.0,0.0010789309162646532,-0.001598493428900838,-0.005922418087720871,0.7760526537895203,-0.04976796358823776,0.026773760095238686 -1769682194,214513920,0.0,0.0,0.0,1.0,0.0012292107567191124,-0.001623080694116652,-0.005782304797321558,0.7762116193771362,-0.04978006333112717,0.019588850438594818 -1769682194,247994624,0.0,0.0,0.0,1.0,0.0012503574835136533,-0.0017145011806860566,-0.005537961609661579,0.6147478818893433,0.0058349501341581345,0.022185396403074265 -1769682194,279353600,0.0,0.0,0.0,1.0,0.0005774461897090077,-0.0017456876812502742,-0.005592092406004667,0.9377794861793518,-0.10493649542331696,0.01446589920669794 -1769682194,328481280,0.0,0.0,0.0,1.0,-8.523876022081822e-05,-0.0019596279598772526,-0.00607264693826437,0.7861445546150208,-0.12468364089727402,0.033163100481033325 -1769682194,359921920,0.0,0.0,0.0,1.0,-0.00015520481974817812,-0.002274886006489396,-0.006609942298382521,0.9170883893966675,0.04705200716853142,0.029820457100868225 -1769682194,370061824,0.0,0.0,0.0,1.0,-0.00026752465055324137,-0.002314010402187705,-0.006865863222628832,0.7560077905654907,0.10204924643039703,0.011012931354343891 -1769682194,412094976,0.0,0.0,0.0,1.0,-0.0003089458041358739,-0.0020439540967345238,-0.007353953551501036,0.4637089967727661,-0.014148924499750137,0.012168116867542267 -1769682194,448092672,0.0,0.0,0.0,1.0,-0.0002952846116386354,-0.0019408718217164278,-0.007807823363691568,0.7661716341972351,0.026912042871117592,0.012673066928982735 -1769682194,480203264,0.0,0.0,0.0,1.0,-0.000197811663383618,-0.0016851841937750578,-0.008090635761618614,0.6048950552940369,0.08198380470275879,0.00105367973446846 -1769682194,507279872,0.0,0.0,0.0,1.0,-0.00016242192941717803,-0.0018109917873516679,-0.008460000157356262,0.6249107718467712,-0.0685289278626442,0.028418902307748795 -1769682194,547609344,0.0,0.0,0.0,1.0,-0.0003932832623831928,-0.002503610448911786,-0.008860490284860134,0.453201025724411,0.06220564991235733,0.02217596396803856 -1769682194,579116288,0.0,0.0,0.0,1.0,-0.0004945747787132859,-0.00282893143594265,-0.00896815862506628,0.45309019088745117,0.06242595240473747,0.026906060054898262 -1769682194,613600000,0.0,0.0,0.0,1.0,-0.0005426936550065875,-0.0028810014482587576,-0.008974046446383,0.9481297135353088,-0.17788125574588776,0.027475537732243538 -1769682194,655762944,0.0,0.0,0.0,1.0,0.0003665901313070208,-0.0030850120820105076,-0.00799976009875536,0.6149844527244568,0.007453957572579384,0.00972154550254345 -1769682194,680238336,0.0,0.0,0.0,1.0,0.00011228961375309154,-0.002968311309814453,-0.0074449991807341576,0.9276842474937439,-0.026415430009365082,0.014194836840033531 -1769682194,713403136,0.0,0.0,0.0,1.0,-0.00020748673705384135,-0.0027274840977042913,-0.006980701815336943,0.7664030194282532,0.028262274339795113,-0.0021297717466950417 -1769682194,749243648,0.0,0.0,0.0,1.0,-0.00048054533544927835,-0.0026057653594762087,-0.006447644904255867,0.4533960819244385,0.06262414902448654,0.007619625888764858 -1769682194,780003584,0.0,0.0,0.0,1.0,-0.0006761168478988111,-0.002481664065271616,-0.006071728654205799,0.7556884288787842,0.10446438193321228,0.010260967537760735 -1769682194,813409280,0.0,0.0,0.0,1.0,-0.0008067494491115212,-0.0023177973926067352,-0.005702716764062643,0.9277225732803345,-0.025635316967964172,0.013879397884011269 -1769682194,849278208,0.0,0.0,0.0,1.0,-0.0008920035324990749,-0.002417226554825902,-0.005214049015194178,0.7661000490188599,0.029204580932855606,0.011905577033758163 -1769682194,879131648,0.0,0.0,0.0,1.0,-0.0009741489193402231,-0.0025073918513953686,-0.004855971317738295,0.46363040804862976,-0.012403910979628563,0.01877649873495102 -1769682194,912648448,0.0,0.0,0.0,1.0,-0.0010483519872650504,-0.0024112346582114697,-0.004534238018095493,0.4638635218143463,-0.01258525438606739,0.006825682241469622 -1769682194,945930496,0.0,0.0,0.0,1.0,-0.0012256231857463717,-0.00236212438903749,-0.004216649103909731,0.7869240641593933,-0.12139547616243362,0.022378478199243546 -1769682194,979429376,0.0,0.0,0.0,1.0,-0.0014065040741115808,-0.0023155149538069963,-0.004075978882610798,0.6254271864891052,-0.0668981671333313,0.013342590071260929 -1769682195,15953920,0.0,0.0,0.0,1.0,-0.0014686585636809468,-0.002423012861981988,-0.004025085363537073,0.7659473419189453,0.029889460653066635,0.018766993656754494 -1769682195,63363072,0.0,0.0,0.0,1.0,-0.0015517559368163347,-0.002372083254158497,-0.004030698910355568,0.7975859642028809,-0.19672255218029022,0.019147777929902077 -1769682195,68328704,0.0,0.0,0.0,1.0,-0.0016620918177068233,-0.0023850479628890753,-0.004073403310030699,0.6254543662071228,-0.0666729211807251,0.013199148699641228 -1769682195,112223744,0.0,0.0,0.0,1.0,-0.0015015910612419248,-0.0020763922948390245,-0.00418057618662715,0.7555382251739502,0.10559704899787903,0.009713389910757542 -1769682197,548854528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682197,579412224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682197,612676864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682197,651532800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682197,680969984,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682197,712420352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682197,752482560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682197,780813824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682197,813421312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682197,847537920,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682197,879491328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682197,916501760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682197,947309824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682197,980279808,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,13523968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,51688704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,80081920,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,113909760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,161047808,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,179833088,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,212895488,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,246274304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,279599360,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,313015296,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,348326400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,379715584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,412878848,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.116104875924066e-05,4.60894443676807e-05,0.002383194398134947 -1769682198,446332160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,479724032,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,513217280,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,562071296,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,570911744,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,612452352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,647262208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,679890688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,712583168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,747471104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,785970944,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,813213952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,849940992,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,879300608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,914982656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,949789952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682198,979589888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,12694272,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,59095040,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,80193024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,113126144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,146390784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,182530048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,213185280,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,249255936,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.116093598189764e-05,4.6089349780231714e-05,0.002383194398134947 -1769682199,279440896,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,314727424,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,348283904,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,380083200,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.1160812290618196e-05,4.608933159033768e-05,0.002383194398134947 -1769682199,413421056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,459637248,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.116068496135995e-05,4.60893425042741e-05,0.002383194398134947 -1769682199,479366144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,514479360,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,547274240,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,580472576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,613793280,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,653031680,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,679529216,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,713768704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,749262848,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,779961344,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,812732416,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,864351232,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.1159964641556144e-05,4.608938252204098e-05,0.002383194398134947 -1769682199,873803264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.115992826176807e-05,-4.608937888406217e-05,-0.002383194398134947 -1769682199,913622528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.115985550219193e-05,4.608938252204098e-05,0.002383194398134947 -1769682199,949498112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682199,980352768,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.115972817293368e-05,4.6089375246083364e-05,0.002383194398134947 -1769682200,12973824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.1159673603251576e-05,4.6089375246083364e-05,0.002383194398134947 -1769682200,50682880,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,79653376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,112893696,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,155663616,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,179623168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,214170112,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,260712704,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,280346368,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.1159186114091426e-05,-4.6089360694168136e-05,-0.002383194398134947 -1769682200,315093504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,347288064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.115905514685437e-05,-4.608936433214694e-05,-0.002383194398134947 -1769682200,381636352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,413020160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,448744192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,479946752,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,514544384,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,550950144,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,579957504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,612649984,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,658644992,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,679801344,0.0,0.0,0.0,1.0,-3.4874034327003756e-07,-7.384572313640092e-07,2.976481027872069e-06,0.0,-0.0,0.0 -1769682200,714676480,0.0,0.0,0.0,1.0,-3.4874034327003756e-07,-7.384572313640092e-07,2.976481027872069e-06,0.0,-0.0,0.0 -1769682200,747594240,0.0,0.0,0.0,1.0,-3.4874034327003756e-07,-7.384572313640092e-07,2.976481027872069e-06,0.0,-0.0,0.0 -1769682200,780452608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,812896512,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,847276800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,880267520,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682200,914920192,0.0,0.0,0.0,1.0,1.2957970341176406e-07,4.157252533332212e-07,2.9704558528464986e-06,0.0,-0.0,0.0 -1769682200,949722880,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.1158760470570996e-05,-4.60892406408675e-05,-0.002383194398134947 -1769682200,984146176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682201,14167552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682201,51516416,0.0,0.0,0.0,1.0,-5.61993260816962e-08,4.0255582689496805e-07,2.9685895697184606e-06,0.0,-0.0,0.0 -1769682201,80684544,0.0,0.0,0.0,1.0,-4.277573850686167e-07,3.762170024401712e-07,2.9648570034623845e-06,0.0,-0.0,0.0 -1769682201,112692480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-0.010744350962340832,0.0755147710442543,-0.001691044308245182 -1769682201,146200064,0.0,0.0,0.0,1.0,1.2957967499005463e-07,4.1572519648980233e-07,2.9704558528464986e-06,0.0,-0.0,0.0 -1769682201,180784896,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682201,214642944,0.0,0.0,0.0,1.0,-5.6199340292550914e-08,4.025558553166775e-07,2.968589797092136e-06,0.0,-0.0,0.0 -1769682201,247884800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682201,280931584,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682201,312790528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682201,347690496,0.0,0.0,0.0,1.0,-5.619933318712356e-08,4.0255582689496805e-07,2.968589797092136e-06,0.0,-0.0,0.0 -1769682201,379849472,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682201,413529856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682201,460046848,0.0,0.0,0.0,1.0,-1.1840225511150493e-07,1.768393786960587e-07,4.656126748159295e-06,0.0,-0.0,0.0 -1769682201,479690496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682201,513675008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.1159251597709954e-05,-4.6089160605333745e-05,-0.002383194398134947 -1769682201,561444352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682201,580511488,0.0,0.0,0.0,1.0,-4.277573566469073e-07,3.7621722981384664e-07,2.9648570034623845e-06,0.0,-0.0,0.0 -1769682201,612676608,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682201,647673344,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682201,682579456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682201,713920000,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682201,747437056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682201,780154624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682201,815861760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682201,847981568,0.0,0.0,0.0,1.0,-2.9860956374250236e-08,3.0997711064628675e-08,2.9724642445216887e-06,0.0,-0.0,0.0 -1769682201,880405504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682201,912601856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682201,959414272,0.0,0.0,0.0,1.0,-9.164915582005051e-08,1.3727235170790664e-07,2.127771267623757e-06,0.0,-0.0,0.0 -1769682201,981423616,0.0,0.0,0.0,1.0,-2.156399858677105e-07,1.7828547527187766e-08,2.970598188767326e-06,0.0,-0.0,0.0 -1769682202,13104896,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682202,47662848,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682202,85422336,0.0,0.0,0.0,1.0,-2.4550095645281544e-07,4.882623727553437e-08,5.943062205915339e-06,0.0,-0.0,0.0 -1769682202,114481920,0.0,0.0,0.0,1.0,-2.9860959926963915e-08,3.09976897483466e-08,2.9724646992690396e-06,0.0,-0.0,0.0 -1769682202,148117760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682202,179475968,0.0,0.0,0.0,1.0,1.2605710253410507e-07,7.516445066357846e-08,5.946796136413468e-06,0.0,-0.0,0.0 -1769682202,218497792,0.0,0.0,0.0,1.0,-2.156400000785652e-07,1.782859904153611e-08,2.970598188767326e-06,0.0,-0.0,0.0 -1769682202,251586816,0.0,0.0,0.0,1.0,-4.479144877223007e-08,4.649650620081047e-08,4.458696821529884e-06,0.0,-0.0,0.0 -1769682202,280838656,0.0,0.0,0.0,1.0,-4.1634953618086e-07,2.0158417157745134e-08,4.454964255273808e-06,0.0,-0.0,0.0 -1769682202,312990976,0.0,0.0,0.0,1.0,-2.3057049247654504e-07,3.332746700834832e-08,4.456830538401846e-06,0.0,-0.0,0.0 -1769682202,357616128,0.0,0.0,0.0,1.0,-2.3057049247654504e-07,3.332747766648936e-08,4.456830993149197e-06,0.0,-0.0,0.0 -1769682202,379851008,0.0,0.0,0.0,1.0,1.409875949320849e-07,5.96654814444264e-08,4.460563104657922e-06,0.0,-0.0,0.0 -1769682202,412938752,0.0,0.0,0.0,1.0,-2.3057049247654504e-07,3.332747766648936e-08,4.456830993149197e-06,0.0,-0.0,0.0 -1769682202,464187904,0.0,0.0,0.0,1.0,-2.569084074366401e-07,4.0488552599526884e-07,4.452956090972293e-06,-5.1159498980268836e-05,4.608906965586357e-05,0.002383194398134947 -1769682202,482581504,0.0,0.0,0.0,1.0,-4.479145587765743e-08,4.649645646281897e-08,4.458696821529884e-06,0.0,-0.0,0.0 -1769682202,504058880,0.0,0.0,0.0,1.0,-2.3057049247654504e-07,3.3327520299053504e-08,4.456830993149197e-06,5.115949170431122e-05,-4.6089073293842375e-05,-0.002383194398134947 -1769682202,547624448,0.0,0.0,0.0,1.0,-2.3057049247654504e-07,3.332752740448086e-08,4.456830538401846e-06,-5.1159488066332415e-05,4.6089084207778797e-05,0.002383194398134947 -1769682202,580489472,0.0,0.0,0.0,1.0,1.409875949320849e-07,5.966536775758868e-08,4.460563559405273e-06,0.0,-0.0,0.0 -1769682202,613717248,0.0,0.0,0.0,1.0,-2.3057052089825447e-07,3.3327545168049255e-08,4.456830993149197e-06,0.0,-0.0,0.0 -1769682202,654583808,0.0,0.0,0.0,1.0,-4.4791462983084784e-08,4.649644580467793e-08,4.458697276277235e-06,0.0,-0.0,0.0 -1769682202,681798656,0.0,0.0,0.0,1.0,-2.3057052089825447e-07,3.332755937890397e-08,4.456830993149197e-06,5.115946987643838e-05,-4.608906965586357e-05,-0.002383194398134947 -1769682202,713890816,0.0,0.0,0.0,1.0,-2.3057052089825447e-07,3.332755582619029e-08,4.456830993149197e-06,0.0,-0.0,0.0 -1769682202,759813376,0.0,0.0,0.0,1.0,-2.3057052089825447e-07,3.332756648433133e-08,4.456830993149197e-06,0.0,-0.0,0.0 -1769682202,779984384,0.0,0.0,0.0,1.0,-2.3057052089825447e-07,3.332758069518604e-08,4.456830993149197e-06,0.0,-0.0,0.0 -1769682202,814251776,0.0,0.0,0.0,1.0,-2.3057052089825447e-07,3.332758424789972e-08,4.456830993149197e-06,0.0,-0.0,0.0 -1769682202,847671040,0.0,0.0,0.0,1.0,3.2676661021469044e-07,7.28340268096872e-08,4.462429842533311e-06,0.0,-0.0,0.0 -1769682202,887168768,0.0,0.0,0.0,1.0,-4.1634953618086e-07,2.0158807956249802e-08,4.454964255273808e-06,0.0,-0.0,0.0 -1769682202,912802816,0.0,0.0,0.0,1.0,-4.1634953618086e-07,2.015883993067291e-08,4.454964710021159e-06,0.0,-0.0,0.0 -1769682202,950350592,0.0,0.0,0.0,1.0,-6.021286367285938e-07,6.990104495230298e-09,4.453098426893121e-06,0.0,-0.0,0.0 -1769682202,980963072,0.0,0.0,0.0,1.0,-4.479147008851214e-08,4.649637475040436e-08,4.458697276277235e-06,0.0,-0.0,0.0 -1769682203,15610112,0.0,0.0,0.0,1.0,-2.3057052089825447e-07,3.332762688046387e-08,4.456830993149197e-06,0.0,-0.0,0.0 -1769682203,49167872,0.0,0.0,0.0,1.0,-4.163495930242789e-07,2.015890743223281e-08,4.454964710021159e-06,5.1159462600480765e-05,-4.608902600011788e-05,-0.002383194398134947 -1769682203,80348672,0.0,0.0,0.0,1.0,-4.479148429936686e-08,4.6496346328694926e-08,4.458697276277235e-06,0.0,-0.0,0.0 -1769682203,113116160,0.0,0.0,0.0,1.0,3.531040135840158e-07,-2.9872435902689176e-07,4.4663047447102144e-06,-5.115944804856554e-05,4.608904419001192e-05,0.002383194398134947 -1769682203,163691008,0.0,0.0,0.0,1.0,-1.8454080930041528e-08,-3.250617908179265e-07,4.462572633201489e-06,0.0,-0.0,0.0 -1769682203,169520896,0.0,0.0,0.0,1.0,-2.0423314595063857e-07,-3.3823047829173447e-07,4.460705440578749e-06,0.0,-0.0,0.0 -1769682203,212940288,0.0,0.0,0.0,1.0,-3.90012218076663e-07,-3.5139908050041413e-07,4.458839157450711e-06,-5.115934618515894e-05,4.608904419001192e-05,0.002383194398134947 -1769682203,246577152,0.0,0.0,0.0,1.0,-1.8454080930041528e-08,-3.250617908179265e-07,4.462572633201489e-06,0.0,-0.0,0.0 -1769682203,282164480,0.0,0.0,0.0,1.0,-2.0423314595063857e-07,-3.382304214483156e-07,4.460705440578749e-06,0.010743720456957817,-0.07551486045122147,0.0016910280101001263 -1769682203,314843136,0.0,0.0,0.0,1.0,-1.845409869360992e-08,-3.2506181923963595e-07,4.46257308794884e-06,0.0,-0.0,0.0 -1769682203,348214016,0.0,0.0,0.0,1.0,-3.900122464983724e-07,-3.513990520787047e-07,4.458839612198062e-06,0.0,-0.0,0.0 -1769682203,380381440,0.0,0.0,0.0,1.0,-1.845409869360992e-08,-3.250618476613454e-07,4.46257308794884e-06,0.0,-0.0,0.0 -1769682203,413886976,0.0,0.0,0.0,1.0,-1.8454091588182564e-08,-3.250618476613454e-07,4.462572633201489e-06,5.1159149734303355e-05,-4.6089036914054304e-05,-0.002383194398134947 -1769682203,451190784,0.0,0.0,0.0,1.0,-3.3384473852038354e-08,-3.095630347615952e-07,5.9488047554623336e-06,-5.115910971653648e-05,4.6089047827990726e-05,0.002383194398134947 -1769682203,479776000,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.115908061270602e-05,4.6089036914054304e-05,0.002383194398134947 -1769682203,512874496,0.0,0.0,0.0,1.0,-4.049426252095145e-07,-3.359001539138262e-07,5.945072643953608e-06,0.0,-0.0,0.0 -1769682203,560125952,0.0,0.0,0.0,1.0,-2.0599503613993875e-07,-5.085107659397181e-07,5.9488770602911245e-06,0.0,-0.0,0.0 -1769682203,581160448,0.0,0.0,0.0,1.0,-3.5237306406088464e-09,-3.405606037176767e-07,2.9763402835669694e-06,-5.115897874929942e-05,4.608902963809669e-05,0.002383194398134947 -1769682203,613738240,0.0,0.0,0.0,1.0,2.854997376289248e-07,4.59890145521058e-07,5.944788426859304e-06,0.0,-0.0,0.0 -1769682203,648172288,0.0,0.0,0.0,1.0,-3.338445608846996e-08,-3.095631484484329e-07,5.9488052102096844e-06,0.0,-0.0,0.0 -1769682203,684510976,0.0,0.0,0.0,1.0,-3.5237803786003496e-09,-3.4056063213938614e-07,2.9763402835669694e-06,0.0,-0.0,0.0 -1769682203,714240768,0.0,0.0,0.0,1.0,1.2605772781171254e-07,7.51634559037484e-08,5.94679704590817e-06,0.0,-0.0,0.0 -1769682203,751216384,0.0,0.0,0.0,1.0,-2.1916359571605426e-07,-3.2273152328343713e-07,5.946939381828997e-06,0.0,-0.0,0.0 -1769682203,779996160,0.0,0.0,0.0,1.0,-1.893029093480436e-07,-3.5372909223951865e-07,2.974473773065256e-06,0.0,-0.0,0.0 -1769682203,815042304,0.0,0.0,0.0,1.0,-3.338447740475203e-08,-3.0956317687014234e-07,5.9488052102096844e-06,0.0,-0.0,0.0 -1769682203,850882816,0.0,0.0,0.0,1.0,1.5239461959026812e-07,-2.9639480203513813e-07,5.950671038590372e-06,0.0,-0.0,0.0 -1769682203,880355840,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682203,913111808,0.0,0.0,0.0,1.0,-2.1916355308349011e-07,-3.22731580126856e-07,5.946939381828997e-06,0.0,-0.0,0.0 -1769682203,966001920,0.0,0.0,0.0,1.0,-4.049426820529334e-07,-3.3589992654015077e-07,5.945073098700959e-06,0.0,-0.0,0.0 -1769682203,971684352,0.0,0.0,0.0,1.0,-2.191635388726354e-07,-3.22731580126856e-07,5.946939836576348e-06,0.0,-0.0,0.0 -1769682204,12922880,0.0,0.0,0.0,1.0,-3.3384445430328924e-08,-3.095632337135612e-07,5.948806119704386e-06,0.0,-0.0,0.0 -1769682204,48120320,0.0,0.0,0.0,1.0,-1.8454144878887746e-08,-3.2506193292647367e-07,4.462572633201489e-06,0.0,-0.0,0.0 -1769682204,80590592,0.0,0.0,0.0,1.0,-1.7789662365430559e-07,-7.097884235918173e-07,4.464580797503004e-06,0.0,-0.0,0.0 -1769682204,112930048,0.0,0.0,0.0,1.0,-3.636757242020394e-07,-7.229566563182743e-07,4.462714514374966e-06,0.0,-0.0,0.0 -1769682204,147217664,0.0,0.0,0.0,1.0,-3.6367569578033e-07,-7.229567131616932e-07,4.462714969122317e-06,0.0,-0.0,0.0 -1769682204,179911680,0.0,0.0,0.0,1.0,-5.494547963280638e-07,-7.361249458881503e-07,4.460847776499577e-06,0.0,-0.0,0.0 -1769682204,213518080,0.0,0.0,0.0,1.0,-2.3056963982526213e-07,3.332786491228035e-08,4.4568319026438985e-06,0.0,-0.0,0.0 -1769682204,250569984,0.0,0.0,0.0,1.0,-2.3056963982526213e-07,3.3327872017707705e-08,4.4568319026438985e-06,0.0,-0.0,0.0 -1769682204,284277248,0.0,0.0,0.0,1.0,-3.3384292663640736e-08,-3.095634326655272e-07,5.948806119704386e-06,0.0,-0.0,0.0 -1769682204,312861184,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682204,347226368,0.0,0.0,0.0,1.0,-2.04233174372348e-07,-3.3823027933976846e-07,4.460706350073451e-06,-5.1158225687686354e-05,4.608896415447816e-05,0.002383194398134947 -1769682204,380374528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682204,414141952,0.0,0.0,0.0,1.0,-3.224094484721718e-07,-1.1100133860963979e-06,2.980356839543674e-06,0.15108337998390198,0.02150421217083931,0.00044212688226252794 -1769682204,449938176,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682204,480552960,0.0,0.0,0.0,1.0,4.914873485972748e-08,-1.0836771480171592e-06,2.984089860547101e-06,0.0,-0.0,0.0 -1769682204,512913664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.1157825510017574e-05,4.608895324054174e-05,0.002383194398134947 -1769682204,549652480,0.0,0.0,0.0,1.0,-3.523773273172992e-09,-3.405608026696427e-07,2.9763402835669694e-06,0.0,-0.0,0.0 -1769682204,580603648,0.0,0.0,0.0,1.0,-1.8930286671547947e-07,-3.537289501309715e-07,2.9744740004389314e-06,0.0,-0.0,0.0 -1769682204,618385664,0.0,0.0,0.0,1.0,2.2812443489783618e-08,-7.121190606085293e-07,2.980215185743873e-06,0.0,-0.0,0.0 -1769682204,650309888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682204,681045760,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682204,713627648,0.0,0.0,0.0,1.0,2.281243993706994e-08,-7.121190037651104e-07,2.9802154131175485e-06,0.0,-0.0,0.0 -1769682204,761677056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682204,780194560,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682204,813369856,0.0,0.0,0.0,1.0,2.0859155824837217e-07,-6.989509984123288e-07,2.9820812414982356e-06,5.115731619298458e-05,-4.6089036914054304e-05,-0.002383194398134947 -1769682204,847959552,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682204,881282304,0.0,0.0,0.0,1.0,2.2812461253352012e-08,-7.121191174519481e-07,2.9802154131175485e-06,0.0,-0.0,0.0 -1769682204,913455104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682204,948805120,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682204,980887296,0.0,0.0,0.0,1.0,2.2812432831642582e-08,-7.121190606085293e-07,2.9802154131175485e-06,0.0,-0.0,0.0 -1769682205,13743104,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682205,49545984,0.0,0.0,0.0,1.0,1.5591959368066455e-07,4.416537535689713e-08,2.974332119265455e-06,0.0,-0.0,0.0 -1769682205,81024768,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682205,115131136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682205,162513920,0.0,0.0,0.0,1.0,-2.9859510419782964e-08,3.099743040024805e-08,2.9724658361374168e-06,0.0,-0.0,0.0 -1769682205,182123264,0.0,0.0,0.0,1.0,9.236840270432367e-08,-1.984498254614664e-08,3.6178873870085226e-06,-5.115689054946415e-05,4.608917879522778e-05,0.002383194398134947 -1769682205,213227776,0.0,0.0,0.0,1.0,3.3691677003844234e-08,9.500776343429607e-08,2.328910113646998e-06,0.0,-0.0,0.0 -1769682205,266850816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682205,277556992,0.0,0.0,0.0,1.0,-2.9859570815915504e-08,3.099743750567541e-08,2.9724658361374168e-06,0.0,-0.0,0.0 -1769682205,331454720,0.0,0.0,0.0,1.0,-2.9859567263201825e-08,3.0997441058389086e-08,2.9724658361374168e-06,0.0,-0.0,0.0 -1769682205,348093184,0.0,0.0,0.0,1.0,-2.156386926799314e-07,1.7829531628876794e-08,2.9705995530093787e-06,0.0,-0.0,0.0 -1769682205,385018624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682205,413339648,0.0,0.0,0.0,1.0,-2.9859567263201825e-08,3.0997416189393334e-08,2.9724658361374168e-06,0.0,-0.0,0.0 -1769682205,496827392,0.0,0.0,0.0,1.0,-8.253111616340902e-08,7.741138574601791e-07,2.964716713904636e-06,-5.115709063829854e-05,4.608917151927017e-05,0.002383194398134947 -1769682205,516192000,0.0,0.0,0.0,1.0,-8.253111616340902e-08,7.741138574601791e-07,2.964716713904636e-06,0.0,-0.0,0.0 -1769682205,548017152,0.0,0.0,0.0,1.0,1.032480199114616e-07,7.87281749126123e-07,2.9665827696589986e-06,0.0,-0.0,0.0 -1769682205,579902976,0.0,0.0,0.0,1.0,-8.253111616340902e-08,7.741138574601791e-07,2.9647169412783114e-06,0.01074308343231678,-0.07551494985818863,0.0016910114791244268 -1769682205,614350848,0.0,0.0,0.0,1.0,1.0324804833317103e-07,7.87281749126123e-07,2.9665827696589986e-06,0.0,-0.0,0.0 -1769682205,660438528,0.0,0.0,0.0,1.0,-8.25310877416996e-08,7.74113914303598e-07,2.9647169412783114e-06,0.0,-0.0,0.0 -1769682205,668539648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682205,713044224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682205,747598080,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682205,782151936,0.0,0.0,0.0,1.0,-8.253111616340902e-08,7.741139711470169e-07,2.9647169412783114e-06,0.0,-0.0,0.0 -1769682205,814215936,0.0,0.0,0.0,1.0,-8.253110195255431e-08,7.741139711470169e-07,2.9647169412783114e-06,0.0,-0.0,0.0 -1769682205,848543232,0.0,0.0,0.0,1.0,-8.253110905798167e-08,7.741139711470169e-07,2.964717168651987e-06,0.0,-0.0,0.0 -1769682205,880548864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682205,914795264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682205,948289536,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682205,980253952,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682206,13656064,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682206,58860544,0.0,0.0,0.0,1.0,1.0324804833317103e-07,7.87281749126123e-07,2.9665827696589986e-06,0.0,-0.0,0.0 -1769682206,414201856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682206,450503680,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682206,480825088,0.0,0.0,0.0,1.0,1.5591905366818537e-07,4.4165066270807074e-08,2.9743323466391303e-06,0.0,-0.0,0.0 -1769682206,514312448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682206,547335168,0.0,0.0,0.0,1.0,-2.986008240668525e-08,3.099749434909427e-08,2.9724662908847677e-06,0.0,-0.0,0.0 -1769682206,570462720,0.0,0.0,0.0,1.0,-2.986008240668525e-08,3.099749434909427e-08,2.9724662908847677e-06,0.0,-0.0,0.0 -1769682206,613355264,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682206,650707712,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682206,680594432,0.0,0.0,0.0,1.0,1.559190820898948e-07,4.416502719095661e-08,2.9743323466391303e-06,0.0,-0.0,0.0 -1769682206,714924800,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682206,753233152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682206,780522240,0.0,0.0,0.0,1.0,-2.986007885397157e-08,3.0997497901807947e-08,2.972466518258443e-06,0.0,-0.0,0.0 -1769682206,813116416,0.0,0.0,0.0,1.0,-2.986008240668525e-08,3.099748724366691e-08,2.972466518258443e-06,0.0,-0.0,0.0 -1769682206,858145024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682206,881164544,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682206,913673216,0.0,0.0,0.0,1.0,1.5591906787904009e-07,4.4164973900251425e-08,2.9743325740128057e-06,0.0,-0.0,0.0 -1769682206,957926400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682206,979968768,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682207,447247872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682207,480645376,0.0,0.0,0.0,1.0,2.8902869075864146e-07,8.004488449842029e-07,2.9684499622817384e-06,0.0,-0.0,0.0 -1769682207,514481664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682207,548655872,0.0,0.0,0.0,1.0,1.0324950494577934e-07,7.872815217524476e-07,2.966583451780025e-06,0.0,-0.0,0.0 -1769682207,580645888,0.0,0.0,0.0,1.0,1.0324950494577934e-07,7.872814649090287e-07,2.966583451780025e-06,0.0,-0.0,0.0 -1769682207,615678208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682207,647806976,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.115847670822404e-05,-4.608945891959593e-05,-0.002383194398134947 -1769682207,680773632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.115852763992734e-05,4.608945164363831e-05,0.002383194398134947 -1769682207,713639168,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.115858220960945e-05,-4.6089462557574734e-05,-0.002383194398134947 -1769682207,751612416,0.0,0.0,0.0,1.0,4.748078197280847e-07,8.136159408422827e-07,2.970316472783452e-06,0.0,-0.0,0.0 -1769682207,781714176,0.0,0.0,0.0,1.0,2.8902869075864146e-07,8.004487312973652e-07,2.968450189655414e-06,0.0,-0.0,0.0 -1769682207,814317312,0.0,0.0,0.0,1.0,1.0324951205120669e-07,7.872815785958664e-07,2.9665836791537004e-06,0.0,-0.0,0.0 -1769682207,848845568,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682207,880267008,0.0,0.0,0.0,1.0,1.0324952626206141e-07,7.872814649090287e-07,2.9665836791537004e-06,0.0,-0.0,0.0 -1769682207,913544192,0.0,0.0,0.0,1.0,2.890287191803509e-07,8.004486744539463e-07,2.968449734908063e-06,0.0,-0.0,0.0 -1769682207,947030528,0.0,0.0,0.0,1.0,6.603198698940105e-08,3.517192226354382e-07,3.614062734413892e-06,0.0,-0.0,0.0 -1769682207,981445120,0.0,0.0,0.0,1.0,-2.986090663625873e-08,3.099762935221406e-08,2.972466518258443e-06,0.0,-0.0,0.0 -1769682208,14342400,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682208,480090624,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682208,514722816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682208,550673664,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682208,581160448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682208,613378816,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682208,647109888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682208,682750208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682208,714509056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682208,749421824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682208,781450496,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682208,814075648,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682208,848402432,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682208,881190656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682208,914659328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682208,949089024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682208,980747776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682209,14102528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682209,49723392,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682209,551373056,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682209,582344448,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682209,614155776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682209,648739328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682209,681752832,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682209,713648640,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682209,749011456,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682209,784227840,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682209,815459328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682209,848587008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682209,880320256,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682209,914726656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682209,951537152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682209,983013376,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682210,13873152,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682210,63742720,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682210,70483968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682210,614204928,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682210,647528192,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682210,681203968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682210,715659776,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682210,752173312,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682210,780635136,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682210,814579968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682210,851224576,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682210,881192960,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682210,913957888,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682210,960615680,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682210,980291072,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682211,14420480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-5.115654130349867e-05,4.608980816556141e-05,0.002383194398134947 -1769682211,49052672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682211,82545920,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682211,113846272,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682211,147550208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682211,183842048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682211,214430208,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682211,682818048,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682211,715521024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.115591920912266e-05,-4.608984454534948e-05,-0.002383194398134947 -1769682211,765939968,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682211,772672512,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682211,813689344,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682211,863396864,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682211,870596352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682211,913689088,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682211,948365824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682211,981578752,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682212,15378688,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682212,49292288,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682212,81242368,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682212,114604544,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682212,150271232,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682212,182477824,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682212,214076160,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682212,261332224,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682212,281572352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682212,763267328,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682212,769348352,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682212,814838528,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682212,848485632,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682212,881574656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682212,914497024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682212,949743872,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682212,980566784,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682213,16034304,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682213,60377856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682213,80902656,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,5.115468957228586e-05,-4.6089648094493896e-05,-0.002383194398134947 -1769682213,114817792,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682213,160107008,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682213,181013504,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682213,214041856,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682213,251510016,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682213,284535296,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682213,852500480,0.0,0.0,0.0,1.0,-0.0013328943168744445,-0.03460562229156494,-0.0017352803843095899,-0.6239258646965027,0.06215896084904671,-0.14984378218650818 -1769682213,881910528,0.0,0.0,0.0,1.0,-0.00038092094473540783,-0.02360665611922741,-0.002037872327491641,-0.46200302243232727,0.007831873372197151,-0.1654626429080963 -1769682213,913990144,0.0,0.0,0.0,1.0,0.0006700223311781883,-0.013701433315873146,-0.0025026779621839523,-0.7641828656196594,-0.03537118434906006,-0.16789667308330536 -1769682213,960889344,0.0,0.0,0.0,1.0,0.0011709383688867092,-0.003744096029549837,-0.0030922547448426485,-0.6026344895362854,-0.08897766470909119,-0.1434098184108734 -1769682213,969658368,0.0,0.0,0.0,1.0,0.001268660882487893,-0.00022686264128424227,-0.003333750180900097,-0.7862903475761414,0.11630097776651382,-0.12780536711215973 -1769682214,15030016,0.0,0.0,0.0,1.0,0.0012166957603767514,0.003801289713010192,-0.0037533342838287354,-0.7650666236877441,-0.034216251224279404,-0.09146008640527725 -1769682214,50361088,0.0,0.0,0.0,1.0,0.0009687258861958981,0.004998783115297556,-0.00411904975771904,-0.30169159173965454,-0.04394002631306648,-0.036027319729328156 -1769682214,81829632,0.0,0.0,0.0,1.0,0.000651398382615298,0.004748926032334566,-0.004368472844362259,-0.6364968419075012,0.13963188230991364,-0.019552070647478104 -1769682214,114897408,0.0,0.0,0.0,1.0,0.00038407096872106194,0.003987985197454691,-0.004607532173395157,-0.604182243347168,-0.08670307695865631,-0.0007088687270879745 -1769682214,150551040,0.0,0.0,0.0,1.0,2.654320269357413e-06,0.0024731315206736326,-0.004910718649625778,-0.593542754650116,-0.16196458041667938,0.01982954889535904 -1769682214,181376000,0.0,0.0,0.0,1.0,-0.00026147550670430064,0.0013995853951200843,-0.0051290192641317844,-0.3132476210594177,0.03253732621669769,0.024268383160233498 -1769682214,215461376,0.0,0.0,0.0,1.0,-0.0004648249305319041,0.00021528889192268252,-0.005353997461497784,-0.31336721777915955,0.03266586735844612,0.03379771485924721 -1769682214,254120448,0.0,0.0,0.0,1.0,-0.00075545534491539,-0.0016319729620590806,-0.0056998697109520435,-0.46433159708976746,0.010699108242988586,0.027649782598018646 -1769682214,281085184,0.0,0.0,0.0,1.0,-0.0009165640221908689,-0.0026685423217713833,-0.005960182286798954,-0.6152864694595337,-0.011306742206215858,0.02153243124485016 -1769682214,314329600,0.0,0.0,0.0,1.0,-0.0010210908949375153,-0.00345710595138371,-0.006239684764295816,-0.6261431574821472,0.06398367881774902,0.015288772992789745 -1769682214,362276096,0.0,0.0,0.0,1.0,-0.0012059600558131933,-0.00289446790702641,-0.006675149314105511,-0.776603639125824,0.041032738983631134,-0.03364528715610504 -1769682214,370404864,0.0,0.0,0.0,1.0,-0.0012727233115583658,-0.0017477415967732668,-0.0068314457312226295,-0.4856410622596741,0.16039368510246277,-0.025300849229097366 -1769682214,414927616,0.0,0.0,0.0,1.0,-0.001072006649337709,0.001713159610517323,-0.006996124982833862,-0.625572681427002,0.06258946657180786,-0.03704738989472389 -1769682214,448020480,0.0,0.0,0.0,1.0,-0.00100320007186383,0.0050460402853786945,-0.007057578768581152,-0.496320515871048,0.2349914014339447,-0.06026621535420418 -1769682214,950551040,0.0,0.0,0.0,1.0,-0.000937566626816988,-0.004122212529182434,-0.010918901301920414,-0.7652089595794678,-0.038638390600681305,-0.062189631164073944 -1769682214,988251392,0.0,0.0,0.0,1.0,-0.0007886664243414998,-0.0020940275862812996,-0.01124725304543972,-0.7653501629829407,-0.03863862156867981,-0.04782569035887718 -1769682215,15065344,0.0,0.0,0.0,1.0,-0.0006882635061629117,-0.0004222061834298074,-0.011583682149648666,-0.7652885317802429,-0.03898600488901138,-0.05257229879498482 -1769682215,49886976,0.0,0.0,0.0,1.0,-0.000699173950124532,0.0005782590014860034,-0.012058292515575886,-0.3356984257698059,0.1803511083126068,-0.02575288526713848 -1769682215,81252608,0.0,0.0,0.0,1.0,-0.0006289560114964843,0.0012075448175892234,-0.012399613857269287,-0.7542141675949097,-0.11442111432552338,-0.015400144271552563 -1769682215,115252736,0.0,0.0,0.0,1.0,-0.000711113796569407,0.0016487326938658953,-0.012735605239868164,-0.6261482238769531,0.058952249586582184,-0.021917562931776047 -1769682215,151410944,0.0,0.0,0.0,1.0,-0.0006741333054378629,0.002315776189789176,-0.013152018189430237,-0.6147220730781555,-0.01674242690205574,-0.01813589408993721 -1769682215,181591040,0.0,0.0,0.0,1.0,-0.0007014073198661208,0.0032161944545805454,-0.013421320356428623,-0.6262238621711731,0.058418963104486465,-0.019635599106550217 -1769682215,214305280,0.0,0.0,0.0,1.0,-0.0007547374698333442,0.0035563718993216753,-0.01371673122048378,-0.7656822800636292,-0.04009627923369408,-0.005175989121198654 -1769682215,258866432,0.0,0.0,0.0,1.0,-0.000842719164211303,0.0022360943257808685,-0.014200789853930473,-0.9166772961616516,-0.06338436901569366,0.012561468407511711 -1769682215,281754368,0.0,0.0,0.0,1.0,-0.0009971554391086102,0.001121298992075026,-0.014606209471821785,-1.0674561262130737,-0.08704157173633575,0.011270174756646156 -1769682215,315438592,0.0,0.0,0.0,1.0,-0.0010847540106624365,0.0003555464791134,-0.015031247399747372,-0.6266660094261169,0.05780210345983505,0.011181369423866272 -1769682215,348140544,0.0,0.0,0.0,1.0,-0.0012196027673780918,-0.0005836899508722126,-0.0156474057585001,-0.9398686289787292,0.08583343029022217,0.00010127667337656021 -1769682215,383158528,0.0,0.0,0.0,1.0,-0.0012715780176222324,-0.000894172873813659,-0.01612766645848751,-0.4642590284347534,0.00527329184114933,0.016273807734251022 -1769682215,416108800,0.0,0.0,0.0,1.0,-0.0012687741545960307,-0.001035082619637251,-0.016619492322206497,-0.7538979053497314,-0.117618627846241,0.005692929960787296 -1769682215,449895936,0.0,0.0,0.0,1.0,-0.001342089264653623,-0.0008997860131785274,-0.017285894602537155,-0.7773223519325256,0.032381799072027206,-0.009053485468029976 -1769682215,481461504,0.0,0.0,0.0,1.0,-0.001341892872005701,-0.000688179163262248,-0.0177980437874794,-0.6383981108665466,0.13094854354858398,-0.01636977307498455 -1769682215,515430656,0.0,0.0,0.0,1.0,-0.001409523538313806,-0.00045572390081360936,-0.018319260329008102,-0.626594066619873,0.05529584735631943,-0.012551641091704369 -1769682216,15818240,0.0,0.0,0.0,1.0,-0.0018802249105647206,0.0013047632528468966,-0.02809607796370983,-0.7648913860321045,-0.05269535630941391,-0.007912594825029373 -1769682216,55197184,0.0,0.0,0.0,1.0,-0.0026237929705530405,0.0009315616334788501,-0.029013125225901604,-0.9279491901397705,-0.0043260566890239716,-0.022544994950294495 -1769682216,82661120,0.0,0.0,0.0,1.0,-0.0030260030180215836,0.0007844464271329343,-0.0296845193952322,-0.6530621647834778,0.19698262214660645,-0.022620031610131264 -1769682216,114466304,0.0,0.0,0.0,1.0,-0.0028545644599944353,0.0007468010298907757,-0.030225325375795364,-0.7517356276512146,-0.13010279834270477,-0.006651660427451134 -1769682216,150411776,0.0,0.0,0.0,1.0,-0.0017751384293660522,0.0002509830810595304,-0.030750857666134834,-0.5162244439125061,0.29691624641418457,-0.02499866671860218 -1769682216,173456896,0.0,0.0,0.0,1.0,-0.0013657251838594675,-0.00015436256944667548,-0.03103136643767357,-0.6273280382156372,0.04490896314382553,-0.019935784861445427 -1769682216,217024512,0.0,0.0,0.0,1.0,-0.0009735539788380265,-0.0005321307689882815,-0.03166875243186951,-0.64061439037323,0.11924763768911362,-0.02125534787774086 -1769682216,248967424,0.0,0.0,0.0,1.0,-0.0007254116935655475,-0.0007341448799706995,-0.03240233659744263,-0.7910830974578857,0.0918608009815216,-0.015414879657328129 -1769682216,282017792,0.0,0.0,0.0,1.0,-0.0005869264132343233,-0.0008364543318748474,-0.0330052375793457,-0.7912284731864929,0.0911540761590004,-0.010626459494233131 -1769682216,314620416,0.0,0.0,0.0,1.0,-0.000417733914218843,-0.0009365203441120684,-0.03364573046565056,-0.6412244439125061,0.117449551820755,-0.0021276716142892838 -1769682216,352665856,0.0,0.0,0.0,1.0,-0.00036987161729484797,-0.0010426228400319815,-0.03456488624215126,-0.49127086997032166,0.14379191398620605,0.00160287506878376 -1769682216,381427200,0.0,0.0,0.0,1.0,-0.0004675575182773173,-0.0012022292939946055,-0.03534264117479324,-0.6687396168708801,0.2658858001232147,-0.011874081566929817 -1769682216,414572032,0.0,0.0,0.0,1.0,-0.0004634243668988347,-0.0012337095104157925,-0.0361691415309906,-0.641631543636322,0.11520611494779587,-0.0020514209754765034 -1769682216,452051712,0.0,0.0,0.0,1.0,-0.0004921245854347944,-0.001145948306657374,-0.03731866180896759,-0.4777994751930237,0.06682392209768295,-0.008931100368499756 -1769682216,482475776,0.0,0.0,0.0,1.0,-0.0005956458626314998,-0.0010101532097905874,-0.03822978213429451,-0.7918316721916199,0.08548734337091446,-0.012829596176743507 -1769682216,514237952,0.0,0.0,0.0,1.0,-0.0006722211255691946,-0.000891759293153882,-0.03914133459329605,-0.7919036746025085,0.08452828228473663,-0.015189185738563538 -1769682216,561804800,0.0,0.0,0.0,1.0,-0.0006215281900949776,-0.0008773647132329643,-0.0403592474758625,-0.3705212473869324,0.3181114196777344,-0.013914653100073338 -1769682216,569531136,0.0,0.0,0.0,1.0,-0.0006382535211741924,-0.0008548222249373794,-0.04098747298121452,-0.6422231793403625,0.11108564585447311,-0.011472485959529877 -1769682217,115889664,0.0,0.0,0.0,1.0,-0.004193434026092291,-0.002274434780701995,-0.06281445175409317,-0.6776812672615051,0.24213889241218567,-0.013095621950924397 -1769682217,150471936,0.0,0.0,0.0,1.0,-0.004037827253341675,-0.002263525268062949,-0.06425255537033081,-0.6452746987342834,0.09138428419828415,-0.015399022027850151 -1769682217,181701632,0.0,0.0,0.0,1.0,-0.0039969985373318195,-0.0022350812796503305,-0.06531225144863129,-0.49656882882118225,0.1234419196844101,-0.01179087907075882 -1769682217,215188224,0.0,0.0,0.0,1.0,-0.004042886663228273,-0.0022258476819843054,-0.06635569781064987,-0.6792641878128052,0.23778076469898224,-0.010461707599461079 -1769682217,251087360,0.0,0.0,0.0,1.0,-0.004028938245028257,-0.002283945679664612,-0.06769368797540665,-0.62896728515625,0.01283989567309618,-0.006919211708009243 -1769682217,282400256,0.0,0.0,0.0,1.0,-0.004037609323859215,-0.0023274593986570835,-0.06870696693658829,-0.8462749123573303,0.27471041679382324,-0.00542342197149992 -1769682217,315241216,0.0,0.0,0.0,1.0,-0.004026728216558695,-0.002396490192040801,-0.069705531001091,-0.4976140260696411,0.1190432608127594,-0.013963745906949043 -1769682217,352760832,0.0,0.0,0.0,1.0,-0.00397402374073863,-0.0024254564195871353,-0.0709431990981102,-0.7165683507919312,0.3797928988933563,-0.0075671374797821045 -1769682217,383354624,0.0,0.0,0.0,1.0,-0.003987970296293497,-0.002442772965878248,-0.07183123379945755,-0.6644443273544312,0.1556394249200821,-0.0017744945362210274 -1769682217,416128768,0.0,0.0,0.0,1.0,-0.004015766084194183,-0.002471146173775196,-0.07266025245189667,-0.646940290927887,0.07999051362276077,-0.0029968200251460075 -1769682217,449959680,0.0,0.0,0.0,1.0,-0.004059385508298874,-0.0024976918939501047,-0.07376416772603989,-0.6831395626068115,0.2262263298034668,-0.014614498242735863 -1769682217,473621504,0.0,0.0,0.0,1.0,-0.004203638527542353,-0.0024494596291333437,-0.07436089217662811,-0.6654064059257507,0.15120120346546173,-0.006337602157145739 -1769682217,514808832,0.0,0.0,0.0,1.0,-0.005465354770421982,-0.0018074511317536235,-0.0755847692489624,-0.6661295890808105,0.14950931072235107,0.019972164183855057 -1769682217,548225024,0.0,0.0,0.0,1.0,-0.0068368748761713505,-0.0007824270869605243,-0.07696536183357239,-0.5370721220970154,0.2585192322731018,0.008187208324670792 -1769682217,582387712,0.0,0.0,0.0,1.0,-0.007633517496287823,-0.0002679878380149603,-0.07815227657556534,-0.5188347101211548,0.1832408756017685,0.0021201707422733307 -1769682217,615708160,0.0,0.0,0.0,1.0,-0.007805646397173405,0.0014978647232055664,-0.07943757623434067,-0.38938888907432556,0.2927378714084625,-0.09546949714422226 -1769682217,649132800,0.0,0.0,0.0,1.0,-0.007594882510602474,0.0038523171097040176,-0.08114250004291534,-0.5380733609199524,0.25321537256240845,-0.08942762762308121 -1769682217,683330048,0.0,0.0,0.0,1.0,-0.0076383985579013824,0.0050004408694803715,-0.08250948041677475,-0.5389125347137451,0.25213220715522766,-0.06799004971981049 -1769682217,715337216,0.0,0.0,0.0,1.0,-0.006749232765287161,0.005245557986199856,-0.08390974253416061,-0.5399210453033447,0.25115734338760376,-0.03226238489151001 -1769682218,214541312,0.0,0.0,0.0,1.0,-0.0037543936632573605,-0.0012912364909425378,-0.10781178623437881,-0.4290660619735718,0.34399697184562683,-0.019766632467508316 -1769682218,260973312,0.0,0.0,0.0,1.0,-0.0035920024383813143,-0.0015457968693226576,-0.10969684273004532,-0.2853858172893524,0.38891899585723877,-0.013381593860685825 -1769682218,281366784,0.0,0.0,0.0,1.0,-0.0035472542513161898,-0.0015231590950861573,-0.11108265072107315,-0.4082346260547638,0.26823127269744873,-0.006942370440810919 -1769682218,314480128,0.0,0.0,0.0,1.0,-0.003503852291032672,-0.00146023731213063,-0.11240790784358978,-0.5542381405830383,0.21922019124031067,0.005869513377547264 -1769682218,348481536,0.0,0.0,0.0,1.0,-0.0036799204535782337,-0.001113654812797904,-0.11417663842439651,-0.3141324520111084,0.4581611752510071,0.002732128370553255 -1769682218,382337280,0.0,0.0,0.0,1.0,-0.003897508606314659,-0.0010168526787310839,-0.11560539156198502,-0.411435604095459,0.26366785168647766,0.0075095598585903645 -1769682218,415413504,0.0,0.0,0.0,1.0,-0.004098161123692989,-0.00084016373148188,-0.11708853393793106,-0.4370137155056,0.334397554397583,0.00443456694483757 -1769682218,449421824,0.0,0.0,0.0,1.0,-0.004361055791378021,-0.000723989331163466,-0.11916910856962204,-0.29443246126174927,0.38238459825515747,0.0036666938103735447 -1769682218,482745344,0.0,0.0,0.0,1.0,-0.004661500919610262,-0.0007485841633751988,-0.12083248794078827,-0.6090564131736755,0.3521345555782318,0.0046843551099300385 -1769682218,515256064,0.0,0.0,0.0,1.0,-0.004980724770575762,-0.0007374347769655287,-0.12266411632299423,-0.32269760966300964,0.4520920515060425,-0.0016788714565336704 -1769682218,550416384,0.0,0.0,0.0,1.0,-0.0041365851648151875,-0.00029618979897350073,-0.12485301494598389,-0.12970077991485596,0.35884130001068115,0.008489996194839478 -1769682218,581934336,0.0,0.0,0.0,1.0,-0.004001809284090996,5.5411801440641284e-05,-0.12666717171669006,-0.30057746171951294,0.37764203548431396,0.008674678392708302 -1769682218,614966784,0.0,0.0,0.0,1.0,-0.003728407435119152,0.0002409525914117694,-0.12849223613739014,-0.21182866394519806,0.5725230574607849,0.008951033465564251 -1769682218,659201536,0.0,0.0,0.0,1.0,-0.005094244610518217,-0.0009343720157630742,-0.13152986764907837,-0.47424814105033875,0.39286166429519653,0.054234154522418976 -1769682218,681180928,0.0,0.0,0.0,1.0,-0.005955694243311882,-0.0017426209524273872,-0.13369423151016235,-0.3059042990207672,0.3738365173339844,0.0422423854470253 -1769682218,715095552,0.0,0.0,0.0,1.0,-0.00661001680418849,-0.002365994732826948,-0.135780468583107,-0.3071989119052887,0.3725086450576782,0.025646328926086426 -1769682218,761345536,0.0,0.0,0.0,1.0,-0.007188319228589535,-0.0028856301214545965,-0.13837821781635284,-0.22252629697322845,0.568442165851593,0.009471419267356396 -1769682218,768659968,0.0,0.0,0.0,1.0,-0.007438205182552338,-0.0030269359704107046,-0.13960710167884827,-0.1960875689983368,0.4968392550945282,0.007776565849781036 -1769682219,282203136,0.0,0.0,0.0,1.0,-0.00492990855127573,0.004080926068127155,-0.1634616106748581,-0.06323006749153137,0.4783520996570587,-0.01472544763237238 -1769682219,315528192,0.0,0.0,0.0,1.0,-0.0036542818415910006,0.0035969887394458055,-0.16476553678512573,-0.029999537393450737,0.7508179545402527,-0.018744299188256264 -1769682219,352013056,0.0,0.0,0.0,1.0,-0.003078474197536707,0.0026158096734434366,-0.16649849712848663,-0.000789949088357389,0.6824122071266174,-0.015919188037514687 -1769682219,381622016,0.0,0.0,0.0,1.0,-0.002886640839278698,0.002036471152678132,-0.16792403161525726,0.06469164788722992,0.546345055103302,0.0015196023741737008 -1769682219,417160192,0.0,0.0,0.0,1.0,-0.002899307757616043,0.0015842737630009651,-0.1694357693195343,-0.13973279297351837,0.2713509500026703,0.008169429376721382 -1769682219,452340736,0.0,0.0,0.0,1.0,-0.0027516193222254515,0.001177451340481639,-0.1714814305305481,0.057825807482004166,0.5470286011695862,0.030243294313549995 -1769682219,481389568,0.0,0.0,0.0,1.0,-0.0025433737318962812,0.0009053086396306753,-0.17301999032497406,-0.2501254975795746,0.4719046950340271,0.007214751094579697 -1769682219,514671104,0.0,0.0,0.0,1.0,-0.0019055467564612627,0.0005050553008913994,-0.17449070513248444,-0.2885916531085968,0.5378312468528748,0.0021435455419123173 -1769682219,559576832,0.0,0.0,0.0,1.0,-0.0015260281506925821,6.594390288228169e-05,-0.1763928085565567,-0.29227346181869507,0.5358046889305115,-0.004975600633770227 -1769682219,581442560,0.0,0.0,0.0,1.0,-0.0014489670284092426,-0.00012698842328973114,-0.17786958813667297,-0.2583172619342804,0.46744677424430847,0.0025215321220457554 -1769682219,615535104,0.0,0.0,0.0,1.0,-0.0013507541734725237,-0.0002585865731816739,-0.1793622076511383,-0.37260696291923523,0.6657904386520386,0.003973177168518305 -1769682219,649675776,0.0,0.0,0.0,1.0,-0.0009955493733286858,-0.00037371297366917133,-0.18137702345848083,0.0010028474498540163,0.6150816679000854,0.008663216605782509 -1769682219,686424064,0.0,0.0,0.0,1.0,-0.0007318719290196896,-0.0009215506142936647,-0.1829681545495987,-0.1729498952627182,0.6049301624298096,0.03035150095820427 -1769682219,714955008,0.0,0.0,0.0,1.0,-0.0011255333665758371,-0.0010650934418663383,-0.18442799150943756,0.2959713339805603,0.7029435634613037,0.03416554629802704 -1769682219,767133952,0.0,0.0,0.0,1.0,-0.001504996558651328,-0.0011243419721722603,-0.18631614744663239,-0.1416379064321518,0.5370742082595825,0.01641681231558323 -1769682219,773274624,0.0,0.0,0.0,1.0,-0.0017710537649691105,-0.001101433066651225,-0.18724794685840607,-0.14358612895011902,0.5365538001060486,0.011670514941215515 -1769682219,814768640,0.0,0.0,0.0,1.0,-0.0019866859074681997,-0.0010734725510701537,-0.18901437520980835,-0.0966239720582962,0.7451595067977905,0.008214278146624565 -1769682220,359399680,0.0,0.0,0.0,1.0,0.001207544468343258,0.0007535341428592801,-0.21601425111293793,-0.13074807822704315,0.6697492599487305,0.0016837208531796932 -1769682220,381934848,0.0,0.0,0.0,1.0,0.0017398531781509519,0.0009994424181059003,-0.21741034090518951,-0.1584376096725464,0.6990097761154175,-0.010406779125332832 -1769682220,415100160,0.0,0.0,0.0,1.0,0.0022214967757463455,0.0011831664014607668,-0.21875527501106262,-0.09083238989114761,0.8524243831634521,0.0007051471620798111 -1769682220,448713984,0.0,0.0,0.0,1.0,0.002594508696347475,0.0013904403895139694,-0.22046874463558197,-0.16920001804828644,0.6964715123176575,-0.005763388704508543 -1769682220,473122816,0.0,0.0,0.0,1.0,0.002728193998336792,0.0015171216800808907,-0.22134003043174744,0.0885029062628746,0.8586341738700867,0.0028940225020051003 -1769682220,515689984,0.0,0.0,0.0,1.0,0.0027923083398491144,0.0016883352072909474,-0.2230457067489624,0.05648541823029518,0.8887432217597961,0.005038843490183353 -1769682220,549412352,0.0,0.0,0.0,1.0,0.0028758763801306486,0.0017910171300172806,-0.2247486263513565,-0.13540855050086975,0.6342360377311707,-0.012833332642912865 -1769682220,581809664,0.0,0.0,0.0,1.0,0.002535229781642556,0.001567572122439742,-0.2260543704032898,-0.04854346439242363,0.7614367604255676,-0.008776959031820297 -1769682220,615325440,0.0,0.0,0.0,1.0,0.002193486550822854,0.0014029421145096421,-0.22734996676445007,-0.028798583894968033,0.7322382926940918,-0.0039032730273902416 -1769682220,648875776,0.0,0.0,0.0,1.0,0.0015439309645444155,0.001508162822574377,-0.22915217280387878,0.028635703027248383,0.8902475237846375,-0.023857703432440758 -1769682220,682469632,0.0,0.0,0.0,1.0,0.0011968391481786966,0.0016370391240343451,-0.23047420382499695,0.23781156539916992,0.8784307241439819,-0.00942173320800066 -1769682220,714934016,0.0,0.0,0.0,1.0,0.0009232340380549431,0.001723326276987791,-0.23186743259429932,0.06726117432117462,0.8339056968688965,0.0050268350169062614 -1769682220,750099712,0.0,0.0,0.0,1.0,0.0005513892974704504,0.0015904089668765664,-0.23412854969501495,-0.1646444946527481,0.6272306442260742,0.010758060030639172 -1769682220,782114304,0.0,0.0,0.0,1.0,0.0001043716911226511,0.0014301815535873175,-0.23585309088230133,-0.057972777634859085,0.7303752303123474,0.02694566175341606 -1769682220,816260608,0.0,0.0,0.0,1.0,-0.000160514609888196,0.0013891098788008094,-0.2374044805765152,-0.010512393899261951,0.6747010350227356,0.02252337709069252 -1769682220,861400832,0.0,0.0,0.0,1.0,-0.0001187552697956562,0.0013414632994681597,-0.23921586573123932,-0.20594079792499542,0.6505723595619202,0.0034085658844560385 -1769682220,870354688,0.0,0.0,0.0,1.0,-9.164726361632347e-05,0.0013686122838407755,-0.24000002443790436,-0.07330615073442459,0.7291074395179749,0.0007215052610263228 -1769682220,915350528,0.0,0.0,0.0,1.0,-0.00012346729636192322,0.0016285594319924712,-0.2413301169872284,0.18954631686210632,0.8899965286254883,0.0025248106103390455 -1769682220,948540672,0.0,0.0,0.0,1.0,8.44856258481741e-05,0.0017631049267947674,-0.24234643578529358,0.15350833535194397,0.9184280037879944,0.019046997651457787 -1769682221,384669952,0.0,0.0,0.0,1.0,0.0037271573673933744,-2.0273408154025674e-05,-0.2522755265235901,0.085309699177742,0.9059682488441467,-0.0003096577129326761 -1769682221,416197376,0.0,0.0,0.0,1.0,0.0033343613613396883,0.00034042162587866187,-0.25333118438720703,0.07843172550201416,0.9065896272659302,-0.00040085799992084503 -1769682221,453061632,0.0,0.0,0.0,1.0,0.0029943983536213636,0.0006978483870625496,-0.2547938823699951,0.12980009615421295,0.8610024452209473,0.002300076186656952 -1769682221,483143936,0.0,0.0,0.0,1.0,0.0029123856220394373,0.000953210168518126,-0.2559100091457367,0.12319593876600266,0.8619723916053772,0.0022264490835368633 -1769682221,515273984,0.0,0.0,0.0,1.0,0.0030759312212467194,0.0010785909835249186,-0.25701287388801575,0.08594977855682373,0.8856189250946045,-0.0028358169365674257 -1769682221,549494016,0.0,0.0,0.0,1.0,0.0032353177666664124,0.001077387947589159,-0.2583675682544708,0.018076414242386818,0.7404274940490723,0.007345087360590696 -1769682221,581816320,0.0,0.0,0.0,1.0,0.0034105731174349785,0.0009674580069258809,-0.2593044340610504,0.0697508454322815,0.8869362473487854,0.011273645795881748 -1769682221,615223552,0.0,0.0,0.0,1.0,0.003537947777658701,0.0008402090752497315,-0.26016002893447876,-0.02460598759353161,0.7625579237937927,-0.00018976221326738596 -1769682221,654693632,0.0,0.0,0.0,1.0,0.003782278159633279,0.000621446524746716,-0.261282354593277,0.08503583073616028,0.8664987683296204,0.011285399086773396 -1769682221,682871808,0.0,0.0,0.0,1.0,0.0037927995435893536,0.00039581910823471844,-0.2621382772922516,0.16353487968444824,0.9937095046043396,0.00822613574564457 -1769682221,715100416,0.0,0.0,0.0,1.0,0.003948963712900877,0.00022769550560042262,-0.26295971870422363,0.10321995615959167,0.8466807007789612,0.008942827582359314 -1769682221,750121984,0.0,0.0,0.0,1.0,0.0038997670635581017,-2.450568717904389e-05,-0.26405051350593567,0.17713715136051178,0.9757811427116394,0.015347806736826897 -1769682221,784613632,0.0,0.0,0.0,1.0,0.003762188134714961,-0.00011007314606104046,-0.2648775577545166,0.16935819387435913,0.977143406867981,0.017621133476495743 -1769682221,815586304,0.0,0.0,0.0,1.0,0.003736641025170684,-0.00017627984925638884,-0.2656446695327759,0.12936340272426605,0.9987552165985107,0.0053445142693817616 -1769682221,851360000,0.0,0.0,0.0,1.0,0.00393114797770977,-0.00032148571335710585,-0.26650914549827576,0.10436616837978363,0.8300878405570984,0.003968250006437302 -1769682221,881757440,0.0,0.0,0.0,1.0,0.004238085821270943,-0.00047515222104266286,-0.26702389121055603,0.17612247169017792,0.9617586731910706,0.007951756939291954 -1769682221,917550848,0.0,0.0,0.0,1.0,0.003932359162718058,-0.0006009858334437013,-0.2675897777080536,0.12387142330408096,0.8122772574424744,0.008781601674854755 -1769682221,958086400,0.0,0.0,0.0,1.0,0.003934066742658615,0.0007013106951490045,-0.26847708225250244,0.0589548759162426,1.0219495296478271,-0.005006843246519566 -1769682222,483210240,0.0,0.0,0.0,1.0,0.005244850181043148,0.0016772621311247349,-0.25767990946769714,0.07144726067781448,0.7933826446533203,-0.006774095818400383 -1769682222,515293184,0.0,0.0,0.0,1.0,0.0054374514147639275,0.0024257898330688477,-0.2558433711528778,0.00960115622729063,0.6518018841743469,-0.001135439146310091 -1769682222,549235200,0.0,0.0,0.0,1.0,0.0059965443797409534,0.002244662493467331,-0.2533997595310211,0.1638842225074768,0.7536975145339966,0.024900181218981743 -1769682222,582323200,0.0,0.0,0.0,1.0,0.0059999385848641396,0.0006411445210687816,-0.25186222791671753,0.30011239647865295,1.0276638269424438,0.03492971882224083 -1769682222,617937920,0.0,0.0,0.0,1.0,0.005956728011369705,-0.0014249514788389206,-0.2506382167339325,0.1685204952955246,0.9124672412872314,0.03991151601076126 -1769682222,653165056,0.0,0.0,0.0,1.0,0.005856436677277088,-0.0026864379178732634,-0.24885393679141998,0.05817004665732384,0.626230001449585,0.03713547810912132 -1769682222,681587712,0.0,0.0,0.0,1.0,0.006507144309580326,-0.0021012190263718367,-0.2474994957447052,0.15268361568450928,0.9153162837028503,0.032345645129680634 -1769682222,715181312,0.0,0.0,0.0,1.0,0.007339807227253914,-0.0012760157696902752,-0.24600975215435028,0.1336294561624527,0.7596451044082642,0.028881823644042015 -1769682222,758742272,0.0,0.0,0.0,1.0,0.008218815550208092,-0.0003974016581196338,-0.24377815425395966,0.12639304995536804,0.7610059976577759,0.009563707746565342 -1769682222,772212480,0.0,0.0,0.0,1.0,0.008645138703286648,0.0008359908824786544,-0.2423841953277588,0.08686540275812149,0.7734131217002869,-0.038584087044000626 -1769682222,814968064,0.0,0.0,0.0,1.0,0.009568747133016586,0.0036596297286450863,-0.239053413271904,0.143522247672081,0.5945456624031067,-0.010299966670572758 -1769682222,850885632,0.0,0.0,0.0,1.0,0.009919323958456516,0.004609914030879736,-0.2355833351612091,0.2178829461336136,0.7311651110649109,0.002809833502396941 -1769682222,883919872,0.0,0.0,0.0,1.0,0.009570986032485962,0.0033690063282847404,-0.23337596654891968,0.29175999760627747,0.8685219883918762,0.018292419612407684 -1769682222,916107776,0.0,0.0,0.0,1.0,0.008841801434755325,0.0005659924354404211,-0.23164352774620056,0.363901287317276,1.0069749355316162,0.021784203127026558 -1769682222,948922112,0.0,0.0,0.0,1.0,0.007768007926642895,-0.0023308221716433764,-0.22989146411418915,0.1606646478176117,0.5888212323188782,0.0036472678184509277 -1769682222,982191616,0.0,0.0,0.0,1.0,0.006649942137300968,-0.003290593856945634,-0.2287837713956833,0.15676704049110413,0.589950680732727,-0.010792715474963188 -1769682223,16723456,0.0,0.0,0.0,1.0,0.005888690240681171,-0.0037024717312306166,-0.22767587006092072,0.07762405276298523,0.4527965188026428,-0.009747487492859364 -1769682223,48747008,0.0,0.0,0.0,1.0,0.0055163465440273285,-0.0034948489628732204,-0.22608071565628052,0.03625384718179703,0.6199582815170288,-0.007395141292363405 -1769682223,83129856,0.0,0.0,0.0,1.0,0.005090647377073765,-0.0031441550236195326,-0.22486825287342072,0.06924223899841309,0.6112625002861023,-0.01667025312781334 -1769682223,114959360,0.0,0.0,0.0,1.0,0.005012644454836845,-0.002696637064218521,-0.2234555184841156,-0.04404781758785248,0.4805266857147217,-0.00871008075773716 -1769682223,149073408,0.0,0.0,0.0,1.0,0.005444953218102455,-0.0020791273564100266,-0.22131426632404327,0.05586306005716324,0.7694774866104126,-0.007009880617260933 -1769682223,181595392,0.0,0.0,0.0,1.0,0.005978054367005825,-0.0013334692921489477,-0.2195037305355072,0.0557207390666008,0.6126574873924255,-0.024166539311408997 -1769682223,215761152,0.0,0.0,0.0,1.0,0.007108238525688648,-0.0005216628778725863,-0.21762357652187347,-0.06598754972219467,0.7938427925109863,-0.0322159007191658 -1769682223,249556480,0.0,0.0,0.0,1.0,0.007228114642202854,0.0004292100202292204,-0.21515502035617828,-0.13359498977661133,0.4940487742424011,-0.005074919201433659 -1769682223,282949888,0.0,0.0,0.0,1.0,0.007459609303623438,0.0007033186266198754,-0.2134062945842743,-0.06177029386162758,0.4785661995410919,-0.01637957990169525 -1769682223,315197696,0.0,0.0,0.0,1.0,0.007508797571063042,0.0007885349914431572,-0.21157105267047882,-0.04583444818854332,0.7850832343101501,0.0009425666648894548 -1769682223,349733888,0.0,0.0,0.0,1.0,0.004693504422903061,-0.0006679070647805929,-0.20929454267024994,-0.020515412092208862,0.3139423429965973,-0.044994596391916275 -1769682235,251281408,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-3.469299554126337e-05,2.8886790460092016e-05,0.0023837615735828876 -1769682235,284360192,0.0,0.0,0.0,1.0,-2.5088178290388896e-07,-1.6368252886422852e-07,7.710929821769241e-06,0.0,-0.0,0.0 -1769682235,307036672,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,-3.4692940971581265e-05,2.8886775908176787e-05,0.0023837615735828876 -1769682235,350732032,0.0,0.0,0.0,1.0,-2.3778613922331715e-07,-1.3930574027654075e-07,9.090326784644276e-06,0.0,-0.0,0.0 -1769682235,383137024,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682235,417087744,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682235,454083584,0.0,0.0,0.0,1.0,-4.4682477096102957e-07,-2.4171222889890487e-07,7.70998030930059e-06,0.0,-0.0,0.0 -1769682235,470484480,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682235,516899584,0.0,0.0,0.0,1.0,4.62890312746822e-08,-3.8027681625862897e-07,9.093850167118944e-06,-3.4692751796683297e-05,2.8886723157484084e-05,0.0023837615735828876 -1769682235,550847488,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 -1769682235,570887680,0.0,0.0,0.0,1.0,1.7121331552516494e-07,-2.4200451775868714e-07,9.09392019821098e-06,3.469271177891642e-05,-2.8886719519505277e-05,-0.0023837615735828876 -1769682235,616463616,0.0,0.0,0.0,1.0,-0.0,0.0,-0.0,0.0,-0.0,0.0 diff --git a/applications/tests/test_autoware/src/lib.rs b/applications/tests/test_autoware/src/lib.rs deleted file mode 100644 index 2d58963da..000000000 --- a/applications/tests/test_autoware/src/lib.rs +++ /dev/null @@ -1,637 +0,0 @@ -#![no_std] -#![allow(static_mut_refs)] -extern crate alloc; - -use alloc::{borrow::Cow, format, string::String, vec, vec::Vec}; -use awkernel_async_lib::dag::{create_dag, finish_create_dags}; -use awkernel_async_lib::net::IpAddr; -use awkernel_async_lib::scheduler::SchedulerType; -use awkernel_lib::delay::wait_microsec; -use awkernel_lib::sync::mutex::{MCSNode, Mutex}; -use core::net::Ipv4Addr; -use core::time::Duration; -use csv_core::{ReadRecordResult, Reader}; -use core::sync::atomic::{AtomicBool, AtomicUsize, Ordering}; - -use imu_corrector::{ImuCorrector, ImuWithCovariance}; -use imu_driver::{build_imu_msg_from_csv_row, ImuCsvRow, ImuMsg, TamagawaImuParser}; -use vehicle_velocity_converter::{ - build_velocity_report_from_csv_row, reactor_helpers, Twist, TwistWithCovariance, - TwistWithCovarianceStamped, VehicleVelocityConverter, VelocityCsvRow, -}; -use ekf_localizer::{ - get_or_initialize_default_module, EKFOdometry, Point3D, Pose, PoseWithCovariance, Quaternion, -}; - -const LOG_ENABLE: bool = false; - -const INTERFACE_ID: u64 = 0; -const INTERFACE_ADDR: Ipv4Addr = Ipv4Addr::new(10, 0, 2, 64); -const UDP_TCP_DST_ADDR: Ipv4Addr = Ipv4Addr::new(10, 0, 2, 2); -const UDP_DST_PORT: u16 = 26099; - -static mut LATEST_JSON_DATA: Option = None; -static JSON_DATA_READY: AtomicBool = AtomicBool::new(false); -static JSON_DATA_LENGTH: AtomicUsize = AtomicUsize::new(0); - -const IMU_CSV_DATA_STR: &str = include_str!("../imu_raw.csv"); -const VELOCITY_CSV_DATA_STR: &str = include_str!("../velocity_status.csv"); - -static mut IMU_CSV_DATA: Option> = None; -static mut VELOCITY_CSV_DATA: Option> = None; -static IMU_CSV_COUNT: Mutex = Mutex::new(0); -static VELOCITY_CSV_COUNT: Mutex = Mutex::new(0); - -pub async fn run() { - wait_microsec(1000000); - - if let Err(e) = initialize_csv_data() { - log::warn!("Failed to initialize CSV data: {}", e); - } - - log::info!("Starting Autoware test application with simplified TCP networking"); - - let dag = create_dag(); - let _dag_id = dag.get_id(); - - dag.register_periodic_reactor::<_, (i32, i32, i32)>( - "start_dummy_data".into(), - move || -> (i32, i32, i32) { - (1, 2, 3) - }, - vec![ - Cow::from("start_imu"), - Cow::from("start_vel"), - Cow::from("start_pose"), - ], - SchedulerType::GEDF(5), - Duration::from_millis(50), - ) - .await; - - dag.register_reactor::<_, (i32,), (ImuMsg,)>( - "imu_driver".into(), - move |(_start_msg,): (i32,)| -> (ImuMsg,) { - let mut node = MCSNode::new(); - let mut count_guard = IMU_CSV_COUNT.lock(&mut node); - let count = *count_guard; - let data = unsafe { IMU_CSV_DATA.as_ref() }; - - let imu_msg = if let Some(csv_data) = data { - if csv_data.is_empty() { - let mut parser = TamagawaImuParser::new("imu_link"); - let awkernel_timestamp = get_awkernel_uptime_timestamp(); - let static_dummy_data = parser.generate_static_dummy_data(awkernel_timestamp); - parser - .parse_binary_data(&static_dummy_data, awkernel_timestamp) - .unwrap_or_default() - } else { - let idx = count % csv_data.len(); - let row = &csv_data[idx]; - let awkernel_timestamp = get_awkernel_uptime_timestamp(); - build_imu_msg_from_csv_row(row, "imu_link", awkernel_timestamp) - } - } else { - let mut parser = TamagawaImuParser::new("imu_link"); - let awkernel_timestamp = get_awkernel_uptime_timestamp(); - let static_dummy_data = parser.generate_static_dummy_data(awkernel_timestamp); - parser - .parse_binary_data(&static_dummy_data, awkernel_timestamp) - .unwrap_or_default() - }; - - *count_guard += 1; - if *count_guard >= 5700 { - *count_guard = 0; - log::info!("rust_e2e_app: finish csv for IMU"); - loop {} - } - - if LOG_ENABLE { - log::debug!( - "IMU data in imu_driver_node,num={}, timestamp={}", - count, - imu_msg.header.timestamp - ); - } - - (imu_msg,) - }, - vec![Cow::from("start_imu")], - vec![Cow::from("imu_data")], - SchedulerType::GEDF(5), - ) - .await; - - dag.register_reactor::<_, (i32,), (TwistWithCovarianceStamped,)>( - "vehicle_velocity_converter".into(), - move |(_start_msg,): (i32,)| -> (TwistWithCovarianceStamped,) { - let converter = VehicleVelocityConverter::default(); - - let mut node = MCSNode::new(); - let mut count_guard = VELOCITY_CSV_COUNT.lock(&mut node); - let count = *count_guard; - let data = unsafe { VELOCITY_CSV_DATA.as_ref() }; - - let csv_data = data.expect("VELOCITY_CSV_DATA must be initialized"); - let idx = count % csv_data.len(); - let row = &csv_data[idx]; - let awkernel_timestamp = get_awkernel_uptime_timestamp(); - let velocity_report = - build_velocity_report_from_csv_row(row, "base_link", awkernel_timestamp); - - *count_guard += 1; - if *count_guard >= 5700 { - *count_guard = 0; - log::info!("rust_e2e_app: finish csv for Velocity"); - loop {} - } - - let twist_msg = converter.convert_velocity_report(&velocity_report); - - if LOG_ENABLE { - log::debug!("Vehicle velocity converter: Converted velocity report to twist - linear.x={:.3}, angular.z={:.3}, awkernel_timestamp={}", - twist_msg.twist.twist.linear.x, - twist_msg.twist.twist.angular.z, - twist_msg.header.timestamp - ); - } - - (twist_msg,) - }, - vec![Cow::from("start_vel")], - vec![Cow::from("velocity_twist")], - SchedulerType::GEDF(5), - ) - .await; - - dag.register_reactor::<_, (ImuMsg,), (ImuWithCovariance,)>( - "imu_corrector".into(), - |(imu_msg,): (ImuMsg,)| -> (ImuWithCovariance,) { - let corrector = ImuCorrector::new(); - let corrected = corrector.correct_imu_with_covariance(&imu_msg, None); - (corrected,) - }, - vec![Cow::from("imu_data")], - vec![Cow::from("corrected_imu_data")], - SchedulerType::GEDF(5), - ) - .await; - - dag.register_reactor::<_, ( - ImuWithCovariance, - TwistWithCovarianceStamped, - ), (TwistWithCovarianceStamped,)>( - "gyro_odometer".into(), - |(imu_with_cov, vehicle_twist): ( - ImuWithCovariance, - TwistWithCovarianceStamped, - )| - -> (TwistWithCovarianceStamped,) { - let current_timestamp = imu_with_cov.header.timestamp; - let current_time = get_awkernel_uptime_timestamp(); - - let gyro_odometer = match gyro_odometer::get_or_initialize() { - Ok(core) => core, - Err(_) => { - return (reactor_helpers::create_empty_twist(current_timestamp),); - } - }; - - gyro_odometer.add_vehicle_twist(vehicle_twist); - gyro_odometer.add_imu(imu_with_cov); - - match gyro_odometer.process_and_get_result(current_time) { - Some(result) => (gyro_odometer.process_result(result),), - None => (reactor_helpers::create_empty_twist(current_timestamp),), - } - }, - vec![Cow::from("corrected_imu_data"), Cow::from("velocity_twist")], - vec![Cow::from("twist_with_covariance")], - SchedulerType::GEDF(5), - ) - .await; - - dag.register_reactor::<_, (i32,), (Pose,)>( - "pose_dummy_generator".into(), - move |(_start_msg,): (i32,)| -> (Pose,) { - let x = 0.0; - let y = 0.0; - let z = 0.0; - - let pose = Pose { - position: Point3D { x, y, z }, - orientation: Quaternion { - x: 0.0, - y: 0.0, - z: 0.0, - w: 1.0, - }, - }; - - (pose,) - }, - vec![Cow::from("start_pose")], - vec![Cow::from("dummy_pose")], - SchedulerType::GEDF(5), - ) - .await; - - dag.register_reactor::<_, (Pose, TwistWithCovarianceStamped), (Pose, EKFOdometry)>( - "ekf_localizer".into(), - |(pose, twist): (Pose, TwistWithCovarianceStamped)| -> (Pose, EKFOdometry) { - let ekf = get_or_initialize_default_module(); - - static mut INITIALIZED: bool = false; - unsafe { - if !INITIALIZED { - ekf.initialize(pose.clone()); - INITIALIZED = true; - } - } - - // Use a fixed 50ms timestep to match the Autoware publisher cadence. - const FIXED_DT: f64 = 0.05; - let dt = FIXED_DT; - - if dt > 0.0 { - ekf.predict(dt); - } - - let vx = twist.twist.twist.linear.x; - let wz = twist.twist.twist.angular.z; - ekf.update_velocity(vx, wz); - - let ekf_pose = ekf.get_current_pose(false); - - let pose_covariance = ekf.get_current_pose_covariance(); - let twist_covariance = ekf.get_current_twist_covariance(); - - let ekf_twist = ekf.get_current_twist(); - - let odometry = EKFOdometry { - header: imu_driver::Header { - frame_id: "map", - timestamp: twist.header.timestamp, - }, - child_frame_id: "base_link", - pose: PoseWithCovariance { - pose: ekf_pose.clone(), - covariance: pose_covariance, - }, - twist: TwistWithCovariance { - twist: Twist { - linear: imu_driver::Vector3::new(ekf_twist.linear.x, ekf_twist.linear.y, ekf_twist.linear.z), - angular: imu_driver::Vector3::new(ekf_twist.angular.x, ekf_twist.angular.y, ekf_twist.angular.z), - }, - covariance: twist_covariance, - }, - }; - - (ekf_pose, odometry) - }, - vec![Cow::from("dummy_pose"), Cow::from("twist_with_covariance")], - vec![Cow::from("estimated_pose"), Cow::from("ekf_odometry")], - SchedulerType::GEDF(5), - ) - .await; - - dag.register_sink_reactor::<_, (Pose, EKFOdometry)>( - "ekf_sink".into(), - move |(_pose, ekf_odom): (Pose, EKFOdometry)| { - - let json_data = format!( - r#"{{"header":{{"frame_id":"{}","timestamp":{}}},"child_frame_id":"{}","pose":{{"pose":{{"position":{{"x":{:.6},"y":{:.6},"z":{:.6}}},"orientation":{{"x":{:.6},"y":{:.6},"z":{:.6},"w":{:.6}}}}},"covariance":[{}]}},"twist":{{"twist":{{"linear":{{"x":{:.6},"y":{:.6},"z":{:.6}}},"angular":{{"x":{:.6},"y":{:.6},"z":{:.6}}}}},"covariance":[{}]}}}}"#, - ekf_odom.header.frame_id, - ekf_odom.header.timestamp, - ekf_odom.child_frame_id, - ekf_odom.pose.pose.position.x, - ekf_odom.pose.pose.position.y, - ekf_odom.pose.pose.position.z, - ekf_odom.pose.pose.orientation.x, - ekf_odom.pose.pose.orientation.y, - ekf_odom.pose.pose.orientation.z, - ekf_odom.pose.pose.orientation.w, - ekf_odom.pose.covariance.iter().map(|&x| format!("{:.6}", x)).collect::>().join(","), - ekf_odom.twist.twist.linear.x, - ekf_odom.twist.twist.linear.y, - ekf_odom.twist.twist.linear.z, - ekf_odom.twist.twist.angular.x, - ekf_odom.twist.twist.angular.y, - ekf_odom.twist.twist.angular.z, - ekf_odom.twist.covariance.iter().map(|&x| format!("{:.6}", x)).collect::>().join(",") - ); - - save_json_data_to_global(json_data); - }, - vec![Cow::from("estimated_pose"), Cow::from("ekf_odometry")], - SchedulerType::GEDF(5), - Duration::from_millis(50), - ) - .await; - - let result = finish_create_dags(&[dag.clone()]).await; - - match result { - Ok(_) => { - log::info!("Autoware test application DAGs created successfully"); - } - Err(errors) => { - log::error!("Failed to create Autoware test application DAGs"); - for error in errors { - log::error!("- {error}"); - } - } - } - - log::info!("Autoware test application DAG completed"); - - log::info!("=== Network test start ==="); - log::info!("Interface ID: {}", INTERFACE_ID); - log::info!("Interface IP: {}", INTERFACE_ADDR); - log::info!("Destination IP: {}", UDP_TCP_DST_ADDR); - awkernel_lib::net::add_ipv4_addr(INTERFACE_ID, INTERFACE_ADDR, 24); - log::info!( - "Configured IPv4 address {} on interface {}", - INTERFACE_ADDR, - INTERFACE_ID - ); - - log::info!("Waiting for network stack initialization..."); - awkernel_async_lib::sleep(Duration::from_secs(2)).await; - - log::info!("Starting periodic UDP sender task"); - start_periodic_udp_sender().await; - - log::info!("Waiting for JSON data to become ready..."); - let mut wait_count = 0; - const MAX_WAIT_COUNT: u32 = 3; - - while !JSON_DATA_READY.load(Ordering::Relaxed) && wait_count < MAX_WAIT_COUNT { - awkernel_async_lib::sleep(Duration::from_secs(1)).await; - wait_count += 1; - } - - if JSON_DATA_READY.load(Ordering::Relaxed) { - } else { - log::warn!("JSON data was not ready. Periodic UDP sender task remains waiting"); - } - - log::info!("Autoware test application completed"); -} - -fn initialize_csv_data() -> Result<(), &'static str> { - unsafe { - if IMU_CSV_DATA.is_none() { - let imu_data = parse_imu_csv(IMU_CSV_DATA_STR)?; - if imu_data.is_empty() { - return Err("IMU CSV is empty"); - } - log::info!("Loaded IMU CSV data: {} rows", imu_data.len()); - IMU_CSV_DATA = Some(imu_data); - } - - if VELOCITY_CSV_DATA.is_none() { - let velocity_data = parse_velocity_csv(VELOCITY_CSV_DATA_STR)?; - if velocity_data.is_empty() { - return Err("Velocity CSV is empty"); - } - log::info!("Loaded velocity CSV data: {} rows", velocity_data.len()); - VELOCITY_CSV_DATA = Some(velocity_data); - } - } - - Ok(()) -} - -fn parse_imu_csv(csv: &str) -> Result, &'static str> { - let mut rows = Vec::new(); - - parse_csv_records(csv, |fields| { - if fields.len() < 12 { - return Err("IMU CSV has insufficient columns"); - } - - let timestamp = parse_timestamp(fields[0], fields[1])?; - let orientation = imu_driver::Quaternion { - x: parse_f64(fields[2])?, - y: parse_f64(fields[3])?, - z: parse_f64(fields[4])?, - w: parse_f64(fields[5])?, - }; - let angular_velocity = imu_driver::Vector3::new( - parse_f64(fields[6])?, - parse_f64(fields[7])?, - parse_f64(fields[8])?, - ); - let linear_acceleration = imu_driver::Vector3::new( - parse_f64(fields[9])?, - parse_f64(fields[10])?, - parse_f64(fields[11])?, - ); - - rows.push(ImuCsvRow { - timestamp, - orientation, - angular_velocity, - linear_acceleration, - }); - Ok(()) - })?; - - Ok(rows) -} - -fn parse_velocity_csv(csv: &str) -> Result, &'static str> { - let mut rows = Vec::new(); - - parse_csv_records(csv, |fields| { - if fields.len() < 5 { - return Err("Velocity CSV has insufficient columns"); - } - - let timestamp = parse_timestamp(fields[0], fields[1])?; - let longitudinal_velocity = parse_f64(fields[2])?; - let lateral_velocity = parse_f64(fields[3])?; - let heading_rate = parse_f64(fields[4])?; - - rows.push(VelocityCsvRow { - timestamp, - longitudinal_velocity, - lateral_velocity, - heading_rate, - }); - Ok(()) - })?; - - Ok(rows) -} - -fn parse_csv_records(csv: &str, mut on_record: F) -> Result<(), &'static str> -where - F: FnMut(&[&str]) -> Result<(), &'static str>, -{ - let mut reader = Reader::new(); - let mut input = csv.as_bytes(); - let mut output = vec![0u8; 4096]; - let mut ends = vec![0usize; 32]; - let mut header_skipped = false; - - loop { - let (result, in_read, _out_written, num_fields) = - reader.read_record(input, &mut output, &mut ends); - input = &input[in_read..]; - - if matches!(result, ReadRecordResult::OutputFull) { - return Err("CSV output buffer is too small"); - } - - if num_fields == 0 { - if matches!(result, ReadRecordResult::InputEmpty | ReadRecordResult::End) { - break; - } - continue; - } - - let mut fields: Vec<&str> = Vec::with_capacity(num_fields); - let mut start = 0usize; - for i in 0..num_fields { - let end = ends[i]; - let slice = &output[start..end]; - let field = core::str::from_utf8(slice).map_err(|_| "Failed to decode CSV UTF-8")?; - fields.push(field); - start = end; - } - - if !header_skipped { - header_skipped = true; - } else { - on_record(&fields)?; - } - - if matches!(result, ReadRecordResult::End) { - break; - } - } - - Ok(()) -} - -fn parse_timestamp(sec: &str, nsec: &str) -> Result { - let sec_val = parse_u64(sec)?; - let nsec_val = parse_u64(nsec)?; - let ts = sec_val - .checked_mul(1_000_000_000) - .and_then(|v| v.checked_add(nsec_val)) - .ok_or("Timestamp calculation overflowed")?; - Ok(ts) -} - -fn parse_u64(field: &str) -> Result { - let trimmed = field.trim(); - if trimmed.is_empty() { - return Ok(0); - } - trimmed.parse::().map_err(|_| "Failed to parse u64") -} - -fn parse_f64(field: &str) -> Result { - let trimmed = field.trim(); - if trimmed.is_empty() { - return Ok(0.0); - } - trimmed.parse::().map_err(|_| "Failed to parse f64") -} - -fn get_awkernel_uptime_timestamp() -> u64 { - let uptime_nanos = awkernel_lib::delay::uptime_nano(); - if uptime_nanos > u64::MAX as u128 { - u64::MAX - } else { - uptime_nanos as u64 - } -} - -pub async fn start_periodic_udp_sender() { - awkernel_async_lib::spawn( - "periodic_udp_sender".into(), - periodic_udp_sender_task(), - awkernel_async_lib::scheduler::SchedulerType::GEDF(5), - ) - .await; -} - -async fn periodic_udp_sender_task() { - let socket_result = awkernel_async_lib::net::udp::UdpSocket::bind_on_interface( - INTERFACE_ID, - &Default::default(), - ); - - let mut socket = match socket_result { - Ok(socket) => socket, - Err(e) => { - log::error!( - "Periodic UDP sender task: failed to create UDP socket: {:?}", - e - ); - return; - } - }; - - let dst_addr = IpAddr::new_v4(UDP_TCP_DST_ADDR); - let mut counter = 0; - - loop { - if !JSON_DATA_READY.load(Ordering::Relaxed) { - awkernel_async_lib::sleep(Duration::from_secs(1)).await; - continue; - } - - let json_data = unsafe { LATEST_JSON_DATA.as_ref().map(|s| s.clone()) }; - - if let Some(data) = json_data { - match socket.send(data.as_bytes(), &dst_addr, UDP_DST_PORT).await { - Ok(_) => { - counter += 1; - log::info!( - "Periodic UDP sender task: send success #{} ({} bytes)", - counter, - data.len() - ); - - let mut buf = [0u8; 1024]; - if let Some(Ok((n, src_addr, src_port))) = awkernel_async_lib::timeout( - Duration::from_millis(100), - socket.recv(&mut buf), - ) - .await - { - if let Ok(response) = core::str::from_utf8(&buf[..n]) { - log::debug!( - "Periodic UDP sender task: response received: {}:{} - {}", - src_addr.get_addr(), - src_port, - response - ); - } - } - } - Err(e) => { - log::warn!("Periodic UDP sender task: send failed: {:?}", e); - } - } - } else { - log::warn!("Periodic UDP sender task: failed to get JSON data"); - } - - awkernel_async_lib::sleep(Duration::from_millis(5)).await; - } -} - -fn save_json_data_to_global(json_data: String) { - unsafe { - LATEST_JSON_DATA = Some(json_data.clone()); - } - JSON_DATA_READY.store(true, Ordering::Relaxed); - JSON_DATA_LENGTH.store(json_data.len(), Ordering::Relaxed); -} diff --git a/applications/tests/test_autoware/vehicle_velocity_converter/Cargo.toml b/applications/tests/test_autoware/vehicle_velocity_converter/Cargo.toml deleted file mode 100644 index 093a4714e..000000000 --- a/applications/tests/test_autoware/vehicle_velocity_converter/Cargo.toml +++ /dev/null @@ -1,11 +0,0 @@ -[package] -name = "vehicle_velocity_converter" -version = "0.1.0" -edition = "2021" - -[dependencies] -log = "0.4" -heapless = "0.7" -awkernel_lib = { path = "../../../../awkernel_lib", default-features = false } -awkernel_async_lib = { path = "../../../../awkernel_async_lib", default-features = false } -imu_driver = { path = "../imu_driver", default-features = false } diff --git a/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs b/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs deleted file mode 100644 index b6ab471d8..000000000 --- a/applications/tests/test_autoware/vehicle_velocity_converter/src/lib.rs +++ /dev/null @@ -1,289 +0,0 @@ -// Copyright 2021 TierIV -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#![no_std] - -use imu_driver::{Header, Vector3}; - -#[derive(Debug, Clone)] -pub struct VelocityReport { - pub header: Header, - pub longitudinal_velocity: f64, - pub lateral_velocity: f64, - pub heading_rate: f64, -} - -#[derive(Debug, Clone)] -pub struct VelocityCsvRow { - pub timestamp: u64, - pub longitudinal_velocity: f64, - pub lateral_velocity: f64, - pub heading_rate: f64, -} - -pub fn build_velocity_report_from_csv_row( - row: &VelocityCsvRow, - frame_id: &'static str, - timestamp: u64, -) -> VelocityReport { - VelocityReport { - header: Header { - frame_id, - timestamp, - }, - longitudinal_velocity: row.longitudinal_velocity, - lateral_velocity: row.lateral_velocity, - heading_rate: row.heading_rate, - } -} - -#[derive(Debug, Clone)] -pub struct TwistWithCovarianceStamped { - pub header: Header, - pub twist: TwistWithCovariance, -} - -#[derive(Debug, Clone)] -pub struct TwistWithCovariance { - pub twist: Twist, - pub covariance: [f64; 36], -} - -#[derive(Debug, Clone)] -pub struct Twist { - pub linear: Vector3, - pub angular: Vector3, -} - -#[repr(C)] -pub struct Odometry { - pub velocity: f64, -} - -pub struct VehicleVelocityConverter { - frame_id: &'static str, - stddev_vx: f64, - stddev_wz: f64, - speed_scale_factor: f64, -} - -impl VehicleVelocityConverter { - pub fn new( - frame_id: &'static str, - stddev_vx: f64, - stddev_wz: f64, - speed_scale_factor: f64, - ) -> Self { - Self { - frame_id, - stddev_vx, - stddev_wz, - speed_scale_factor, - } - } - - pub fn from_params_array( - velocity_stddev_xx: Option, - angular_velocity_stddev_zz: Option, - speed_scale_factor: Option, - frame_id: &'static str, - ) -> Self { - let stddev_vx = velocity_stddev_xx.unwrap_or(0.2); - let stddev_wz = angular_velocity_stddev_zz.unwrap_or(0.1); - let speed_scale_factor = speed_scale_factor.unwrap_or(1.0); - - Self::new(frame_id, stddev_vx, stddev_wz, speed_scale_factor) - } - - pub fn default() -> Self { - Self::new("base_link", 0.2, 0.1, 1.0) - } - - pub fn convert_velocity_report(&self, msg: &VelocityReport) -> TwistWithCovarianceStamped { - let _frame_id_mismatch = msg.header.frame_id != self.frame_id; - - TwistWithCovarianceStamped { - header: msg.header.clone(), - twist: TwistWithCovariance { - twist: Twist { - linear: Vector3 { - x: msg.longitudinal_velocity * self.speed_scale_factor, - y: msg.lateral_velocity, - z: 0.0, - }, - angular: Vector3 { - x: 0.0, - y: 0.0, - z: msg.heading_rate, - }, - }, - covariance: self.create_covariance_matrix(), - }, - } - } - - fn create_covariance_matrix(&self) -> [f64; 36] { - let mut covariance = [0.0; 36]; - covariance[0 + 0 * 6] = self.stddev_vx * self.stddev_vx; - covariance[1 + 1 * 6] = 10000.0; - covariance[2 + 2 * 6] = 10000.0; - covariance[3 + 3 * 6] = 10000.0; - covariance[4 + 4 * 6] = 10000.0; - covariance[5 + 5 * 6] = self.stddev_wz * self.stddev_wz; - - covariance - } - - pub fn get_frame_id(&self) -> &'static str { - self.frame_id - } - - pub fn get_stddev_vx(&self) -> f64 { - self.stddev_vx - } - - pub fn get_stddev_wz(&self) -> f64 { - self.stddev_wz - } - - pub fn get_speed_scale_factor(&self) -> f64 { - self.speed_scale_factor - } -} - -pub mod reactor_helpers { - use super::*; - - pub fn create_empty_twist(timestamp: u64) -> TwistWithCovarianceStamped { - TwistWithCovarianceStamped { - header: Header { - frame_id: "base_link", - timestamp, - }, - twist: TwistWithCovariance { - twist: Twist { - linear: Vector3 { - x: 0.0, - y: 0.0, - z: 0.0, - }, - angular: Vector3 { - x: 0.0, - y: 0.0, - z: 0.0, - }, - }, - covariance: [0.0; 36], - }, - } - } -} - -#[cfg(test)] -mod tests { - use super::*; - - #[test] - fn test_vehicle_velocity_converter_creation() { - let converter = VehicleVelocityConverter::new("base_link", 0.1, 0.1, 1.0); - - assert_eq!(converter.get_frame_id(), "base_link"); - assert_eq!(converter.get_stddev_vx(), 0.1); - assert_eq!(converter.get_stddev_wz(), 0.1); - assert_eq!(converter.get_speed_scale_factor(), 1.0); - } - - #[test] - fn test_vehicle_velocity_converter_default() { - let converter = VehicleVelocityConverter::default(); - assert_eq!(converter.get_frame_id(), "base_link"); - assert_eq!(converter.get_stddev_vx(), 0.1); - assert_eq!(converter.get_stddev_wz(), 0.1); - assert_eq!(converter.get_speed_scale_factor(), 1.0); - } - - #[test] - fn test_convert_velocity_report_success() { - let converter = VehicleVelocityConverter::new("base_link", 0.1, 0.1, 1.0); - - let velocity_report = VelocityReport { - header: Header { - frame_id: "base_link", - timestamp: 1234567890, - }, - longitudinal_velocity: 10.0, - lateral_velocity: 2.0, - heading_rate: 0.5, - }; - - let result = converter.convert_velocity_report(&velocity_report); - assert!(result.is_ok()); - - let twist_msg = result.unwrap(); - assert_eq!(twist_msg.twist.twist.linear.x, 10.0); - assert_eq!(twist_msg.twist.twist.linear.y, 2.0); - assert_eq!(twist_msg.twist.twist.angular.z, 0.5); - assert_eq!(twist_msg.twist.covariance[0], 0.01); - assert_eq!(twist_msg.twist.covariance[35], 0.01); - } - - #[test] - fn test_convert_velocity_report_wrong_frame_id() { - let converter = VehicleVelocityConverter::new("base_link", 0.1, 0.1, 1.0); - - let velocity_report = VelocityReport { - header: Header { - frame_id: "wrong_frame", - timestamp: 1234567890, - }, - longitudinal_velocity: 10.0, - lateral_velocity: 2.0, - heading_rate: 0.5, - }; - - let result = converter.convert_velocity_report(&velocity_report); - assert!(result.is_err()); - assert_eq!(result.unwrap_err(), "frame_id mismatch"); - } - - #[test] - fn test_from_params_array() { - let converter = VehicleVelocityConverter::from_params_array( - Some(0.2), - Some(0.3), - Some(1.5), - "base_link", - ); - - assert_eq!(converter.get_stddev_vx(), 0.2); - assert_eq!(converter.get_stddev_wz(), 0.3); - assert_eq!(converter.get_speed_scale_factor(), 1.5); - } - - #[test] - fn test_from_params_array_with_defaults() { - let converter = VehicleVelocityConverter::from_params_array(None, None, None, "base_link"); - - assert_eq!(converter.get_stddev_vx(), 0.1); - assert_eq!(converter.get_stddev_wz(), 0.1); - assert_eq!(converter.get_speed_scale_factor(), 1.0); - } - - #[test] - fn test_reactor_helpers() { - let empty_twist = reactor_helpers::create_empty_twist(1234567890); - assert_eq!(empty_twist.header.frame_id, "base_link"); - assert_eq!(empty_twist.twist.twist.linear.x, 0.0); - } -} diff --git a/applications/tests/test_autoware/velocity_status.csv b/applications/tests/test_autoware/velocity_status.csv deleted file mode 100644 index 395e34668..000000000 --- a/applications/tests/test_autoware/velocity_status.csv +++ /dev/null @@ -1,5700 +0,0 @@ -timestamp_sec,timestamp_nanosec,longitudinal_velocity,lateral_velocity,heading_rate -1769682011,700255232,0.0,-0.0,569.3849487304688 -1769682011,758522112,0.0,-0.0,569.3849487304688 -1769682011,769631744,0.0,-0.0,569.3849487304688 -1769682011,808847872,0.0,-0.0,569.3849487304688 -1769682011,864361984,0.0,-0.0,569.3849487304688 -1769682011,880172544,0.0,-0.0,569.3849487304688 -1769682011,910094592,0.0,-0.0,569.3849487304688 -1769682011,950354688,0.0,-0.0,569.3849487304688 -1769682011,978123520,0.0,-0.0,569.3849487304688 -1769682012,10280960,0.0,-0.0,569.3849487304688 -1769682012,51739648,0.0,-0.0,569.3849487304688 -1769682012,75805440,0.0,-0.0,569.3849487304688 -1769682012,113769472,0.0,-0.0,569.3849487304688 -1769682012,158029824,0.0,-0.0,569.3849487304688 -1769682012,169788672,0.0,-0.0,569.3849487304688 -1769682012,209098496,0.0,-0.0,569.3849487304688 -1769682012,263562240,0.0,-0.0,569.3849487304688 -1769682012,273020416,0.0,-0.0,569.3849487304688 -1769682012,308360704,0.0,-0.0,569.3849487304688 -1769682012,355533824,0.0,-0.0,569.3849487304688 -1769682012,375906560,0.0,-0.0,569.3849487304688 -1769682012,399995904,0.0,-0.0,569.3849487304688 -1769682012,451935232,0.0,-0.0,569.3849487304688 -1769682012,475962624,0.0,-0.0,569.3849487304688 -1769682012,511308544,0.0,-0.0,569.3849487304688 -1769682012,554384128,0.0,-0.0,569.3849487304688 -1769682012,572859904,0.0,-0.0,569.3849487304688 -1769682012,608497408,0.0,-0.0,569.3849487304688 -1769682012,646467584,0.0,-0.0,569.3849487304688 -1769682012,669081344,0.0,-0.0,569.3849487304688 -1769682012,709002496,0.0,-0.0,569.3849487304688 -1769682012,746405120,0.0,-0.0,569.3849487304688 -1769682012,775781120,0.0,-0.0,569.3849487304688 -1769682012,808895232,0.0,-0.0,569.3849487304688 -1769682012,852572928,0.0,-0.0,569.3849487304688 -1769682012,876762624,0.0,-0.0,569.3849487304688 -1769682012,908988928,0.0,-0.0,569.3849487304688 -1769682012,947235328,0.0,-0.0,569.3849487304688 -1769682012,979264256,0.0,-0.0,569.3849487304688 -1769682013,8980992,0.0,-0.0,569.3849487304688 -1769682013,42661376,0.0,-0.0,569.3849487304688 -1769682013,66936576,0.0,-0.0,569.3849487304688 -1769682013,109064192,0.0,-0.0,569.3849487304688 -1769682013,143434752,0.0,-0.0,569.3849487304688 -1769682013,175307776,0.0,-0.0,569.3849487304688 -1769682013,212890112,0.0,-0.0,569.3849487304688 -1769682013,257614592,0.0,-0.0,569.3849487304688 -1769682013,267284992,0.0,-0.0,569.3849487304688 -1769682013,308487424,0.0,-0.0,569.3849487304688 -1769682013,362421248,0.0,-0.0,569.3849487304688 -1769682013,379762176,0.0,-0.0,569.3849487304688 -1769682013,408749568,0.0,-0.0,569.3849487304688 -1769682013,445525760,0.0,-0.0,569.3849487304688 -1769682013,476374272,0.0,-0.0,569.3849487304688 -1769682013,510556928,0.0,-0.0,569.3849487304688 -1769682013,548176128,0.0,-0.0,569.3849487304688 -1769682013,576049920,0.0,-0.0,569.3849487304688 -1769682013,613592064,0.0,-0.0,569.3849487304688 -1769682013,658866432,0.0,-0.0,569.3849487304688 -1769682013,668812032,0.0,-0.0,569.3849487304688 -1769682013,708560896,0.0,-0.0,569.3849487304688 -1769682013,753995776,0.0,-0.0,569.3849487304688 -1769682013,776591872,0.0,-0.0,569.3849487304688 -1769682013,809442816,0.0,-0.0,569.3849487304688 -1769682013,842308864,0.0,-0.0,569.3849487304688 -1769682013,877677056,0.0,-0.0,569.3849487304688 -1769682013,909456640,0.0,-0.0,569.3849487304688 -1769682013,961141760,0.0,-0.0,569.3849487304688 -1769682013,967884544,0.0,-0.0,569.3849487304688 -1769682014,13824,0.0,-0.0,569.3849487304688 -1769682014,60951552,0.0,-0.0,569.3849487304688 -1769682014,72105984,0.0,-0.0,569.3849487304688 -1769682014,109562368,0.0,-0.0,569.3849487304688 -1769682014,162879488,0.0,-0.0,569.3849487304688 -1769682014,174462208,0.0,-0.0,569.3849487304688 -1769682014,209085184,0.0,-0.0,569.3849487304688 -1769682014,243574784,0.0,-0.0,569.3849487304688 -1769682014,275991552,0.0,-0.0,569.3849487304688 -1769682014,309744128,0.0,-0.0,569.3849487304688 -1769682014,353015296,0.0,-0.0,569.3849487304688 -1769682014,375981056,0.0,-0.0,569.3849487304688 -1769682014,408406784,0.0,-0.0,569.3849487304688 -1769682014,459114752,0.0,-0.0,569.3849487304688 -1769682014,468640512,0.0,-0.0,569.3849487304688 -1769682014,508637440,0.0,-0.0,569.3849487304688 -1769682014,543428352,0.0,-0.0,569.3849487304688 -1769682014,577775360,0.0,-0.0,569.3849487304688 -1769682014,609924608,0.0,-0.0,569.3849487304688 -1769682014,644710656,0.0,-0.0,569.3849487304688 -1769682014,675723520,0.0,-0.0,569.3849487304688 -1769682014,708867840,0.0,-0.0,569.3849487304688 -1769682014,742886400,0.0,-0.0,569.3849487304688 -1769682014,776319232,0.0,-0.0,569.3849487304688 -1769682014,812282368,0.0,-0.0,569.3849487304688 -1769682014,845304576,0.0,-0.0,569.3849487304688 -1769682014,877685504,0.0,-0.0,569.3849487304688 -1769682014,910222848,0.0,-0.0,569.3849487304688 -1769682014,957992960,0.0,-0.0,569.3849487304688 -1769682014,969115392,0.0,-0.0,569.3849487304688 -1769682015,10092032,0.0,-0.0,569.3849487304688 -1769682015,43204608,0.0,-0.0,569.3849487304688 -1769682015,77753344,0.0,-0.0,569.3849487304688 -1769682015,109543680,0.0,-0.0,569.3849487304688 -1769682015,144401664,0.0,-0.0,569.3849487304688 -1769682015,178896384,0.0,-0.0,569.3849487304688 -1769682015,209269504,0.0,-0.0,569.3849487304688 -1769682015,245459712,0.0,-0.0,569.3849487304688 -1769682015,278455808,0.0,-0.0,569.3849487304688 -1769682015,313575424,0.0,-0.0,569.3849487304688 -1769682015,348885760,0.0,-0.0,569.3849487304688 -1769682015,375457792,0.0,-0.0,569.3849487304688 -1769682015,409125632,0.0,-0.0,569.3849487304688 -1769682015,453744128,0.0,-0.0,569.3849487304688 -1769682015,475828992,0.0,-0.0,569.3849487304688 -1769682015,509189120,0.0,-0.0,569.3849487304688 -1769682015,543340288,0.0,-0.0,569.3849487304688 -1769682015,579919616,0.0,-0.0,569.3849487304688 -1769682015,611710464,0.0,-0.0,569.3849487304688 -1769682015,645071360,0.0,-0.0,569.3849487304688 -1769682015,675676416,0.0,-0.0,569.3849487304688 -1769682015,708974848,0.0,-0.0,569.3849487304688 -1769682015,754650624,0.0,-0.0,569.3849487304688 -1769682015,775636736,0.0,-0.0,569.3849487304688 -1769682015,808608000,0.0,-0.0,569.3849487304688 -1769682015,861485056,0.0,-0.0,569.3849487304688 -1769682015,868991744,0.0,-0.0,569.3849487304688 -1769682015,910497792,0.0,-0.0,569.3849487304688 -1769682015,944608768,0.0,-0.0,569.3849487304688 -1769682015,979958016,0.0,-0.0,569.3849487304688 -1769682016,8975104,0.0,-0.0,569.3849487304688 -1769682016,44931584,0.0,-0.0,569.3849487304688 -1769682016,75618048,0.0,-0.0,569.3849487304688 -1769682016,109694976,0.0,-0.0,569.3849487304688 -1769682016,144407808,0.0,-0.0,569.3849487304688 -1769682016,176874496,0.0,-0.0,569.3849487304688 -1769682016,209109248,0.0,-0.0,569.3849487304688 -1769682016,265109760,0.0,-0.0,569.3849487304688 -1769682016,274155264,0.0,-0.0,569.3849487304688 -1769682016,309134848,0.0,-0.0,569.3849487304688 -1769682016,342443008,0.0,-0.0,569.3849487304688 -1769682016,376755712,0.0,-0.0,569.3849487304688 -1769682016,410583552,0.0,-0.0,569.3849487304688 -1769682016,456397312,0.0,-0.0,569.3849487304688 -1769682016,475862016,0.0,-0.0,569.3849487304688 -1769682016,509884672,0.0,-0.0,569.3849487304688 -1769682016,551685376,0.0,-0.0,569.3849487304688 -1769682016,576078592,0.0,-0.0,569.3849487304688 -1769682016,608886784,0.0,-0.0,569.3849487304688 -1769682016,643988992,0.0,-0.0,569.3849487304688 -1769682016,665050112,0.0,-0.0,569.3849487304688 -1769682016,713223168,0.0,-0.0,569.3849487304688 -1769682016,746755840,0.0,-0.0,569.3849487304688 -1769682016,828164608,0.0,-0.0,569.3849487304688 -1769682016,830391808,0.0,-0.0,569.3849487304688 -1769682016,863160576,0.0,-0.0,569.3849487304688 -1769682016,870770944,0.0,-0.0,569.3849487304688 -1769682016,910422528,0.0,-0.0,569.3849487304688 -1769682016,943827968,0.0,-0.0,569.3849487304688 -1769682016,975929856,0.0,-0.0,569.3849487304688 -1769682017,9383936,0.0,-0.0,569.3849487304688 -1769682017,48541952,0.0,-0.0,569.3849487304688 -1769682017,76783616,0.0,-0.0,569.3849487304688 -1769682017,109331968,0.0,-0.0,569.3849487304688 -1769682017,158212608,0.0,-0.0,569.3849487304688 -1769682017,169605120,0.0,-0.0,569.3849487304688 -1769682017,208920064,0.0,-0.0,569.3849487304688 -1769682017,243268864,0.0,-0.0,569.3849487304688 -1769682017,275956992,0.0,-0.0,569.3849487304688 -1769682017,309727488,0.0,-0.0,569.3849487304688 -1769682017,357306112,0.0,-0.0,569.3849487304688 -1769682017,383682304,0.0,-0.0,569.3849487304688 -1769682017,409618432,0.0,-0.0,569.3849487304688 -1769682017,445664768,0.0,-0.0,569.3849487304688 -1769682017,476822528,0.0,-0.0,569.3849487304688 -1769682017,510077440,0.0,-0.0,569.3849487304688 -1769682017,549352960,0.0,-0.0,569.3849487304688 -1769682017,576484096,0.0,-0.0,569.3849487304688 -1769682017,609178368,0.0,-0.0,569.3849487304688 -1769682017,662101248,0.0,-0.0,569.3849487304688 -1769682017,668743936,0.0,-0.0,569.3849487304688 -1769682017,708879616,0.0,-0.0,569.3849487304688 -1769682017,743879424,0.0,-0.0,569.3849487304688 -1769682017,776214784,0.0,-0.0,569.3849487304688 -1769682017,809252864,0.0,-0.0,569.3849487304688 -1769682017,845326592,0.0,-0.0,569.3849487304688 -1769682017,876781312,0.0,-0.0,569.3849487304688 -1769682017,914567168,0.0,-0.0,569.3849487304688 -1769682017,946809600,0.0,-0.0,569.3849487304688 -1769682017,976403712,0.0,-0.0,569.3849487304688 -1769682018,8882688,0.0,-0.0,569.3849487304688 -1769682018,57296896,0.0,-0.0,569.3849487304688 -1769682018,66685952,0.0,-0.0,569.3849487304688 -1769682018,110140928,0.0,-0.0,569.3849487304688 -1769682018,142674688,0.0,-0.0,569.3849487304688 -1769682018,180656896,0.0,-0.0,569.3849487304688 -1769682018,209013248,0.0,-0.0,569.3849487304688 -1769682018,244921088,0.0,-0.0,569.3849487304688 -1769682018,277340928,0.0,-0.0,569.3849487304688 -1769682018,312886784,0.0,-0.0,569.3849487304688 -1769682018,353472000,0.00963905081152916,0.0038882032968103886,569.3850708007812 -1769682018,377942016,0.020210010930895805,0.00901066418737173,569.3860473632812 -1769682018,409864448,0.03129139170050621,0.012583667412400246,569.3878784179688 -1769682018,463794176,0.046559493988752365,0.014734799042344093,569.3907470703125 -1769682018,473165312,0.05780423432588577,0.015113649889826775,569.392822265625 -1769682018,509708288,0.06921159476041794,0.014711441472172737,569.3945922851562 -1769682018,548221952,0.08465200662612915,0.01368725299835205,569.396240234375 -1769682018,576468992,0.09643234312534332,0.012721788138151169,569.3968505859375 -1769682018,609244416,0.10836578905582428,0.01174214482307434,569.39697265625 -1769682018,646269696,0.12459100037813187,0.010521039366722107,569.3964233398438 -1769682018,675729408,0.13693653047084808,0.00967089831829071,569.3956909179688 -1769682018,715028480,0.1493261158466339,0.008894070982933044,569.3946533203125 -1769682018,750859520,0.16531477868556976,0.008028239011764526,569.3931274414062 -1769682018,775893760,0.1771790087223053,0.007413260638713837,569.3919677734375 -1769682018,808829184,0.18889310956001282,0.0068847015500068665,569.3908081054688 -1769682018,858827264,0.20497219264507294,0.006218567490577698,569.3895874023438 -1769682018,865270016,0.21297457814216614,0.005882948637008667,569.3890380859375 -1769682018,912216576,0.22905504703521729,0.005356132984161377,569.3881225585938 -1769682018,954541312,0.2443806231021881,0.004935204982757568,569.3875732421875 -1769682018,982667264,0.2542468011379242,0.004653647541999817,569.3875122070312 -1769682019,9133056,0.26301226019859314,0.004430167376995087,569.3876342773438 -1769682019,62677504,0.27643805742263794,0.004156246781349182,569.3883666992188 -1769682019,72739840,0.28907084465026855,0.004025071859359741,569.388916015625 -1769682019,100164608,0.2973051965236664,0.003893539309501648,569.3893432617188 -1769682019,148498688,0.31804442405700684,0.0037523210048675537,569.390625 -1769682019,178371328,0.33059680461883545,0.0036843419075012207,569.3916015625 -1769682019,209343488,0.3429432511329651,0.0036125928163528442,569.3927612304688 -1769682019,248334336,0.35973021388053894,0.003522023558616638,569.3945922851562 -1769682019,278630144,0.3724035322666168,0.003471165895462036,569.396240234375 -1769682019,309206016,0.3850468397140503,0.0034292638301849365,569.3980102539062 -1769682019,342484992,0.4019630253314972,0.0033818185329437256,569.4006958007812 -1769682019,376893952,0.41457265615463257,0.003342658281326294,569.4029541015625 -1769682019,410846720,0.4273275136947632,0.003273293375968933,569.4053955078125 -1769682019,446523392,0.44413766264915466,0.003113269805908203,569.4088745117188 -1769682019,480477952,0.45669275522232056,0.00306093692779541,569.4117431640625 -1769682019,509204992,0.46934008598327637,0.0029453039169311523,569.414794921875 -1769682019,554383104,0.4861355423927307,0.0027658194303512573,569.4191284179688 -1769682019,576036864,0.49872374534606934,0.0026638060808181763,569.422607421875 -1769682019,612462592,0.5112838745117188,0.0025794953107833862,569.42626953125 -1769682019,649218560,0.5279158353805542,0.002412661910057068,569.431396484375 -1769682019,676426240,0.5403468012809753,0.00232754647731781,569.4354858398438 -1769682019,709230848,0.552673876285553,0.0021771490573883057,569.439697265625 -1769682019,760854784,0.5692882537841797,0.002044767141342163,569.4456176757812 -1769682019,770100480,0.5775577425956726,0.002010822296142578,569.44873046875 -1769682019,809977600,0.594025731086731,0.001890331506729126,569.4550170898438 -1769682019,844037376,0.6103975772857666,0.0017547607421875,569.4617309570312 -1769682019,879037440,0.6225874423980713,0.001660376787185669,569.4668579101562 -1769682019,911650048,0.6347853541374207,0.0015984773635864258,569.47216796875 -1769682019,949195264,0.6510071158409119,0.0014482736587524414,569.4795532226562 -1769682019,976909568,0.6629921793937683,0.0013468265533447266,569.4851684570312 -1769682020,11323136,0.6750698089599609,0.0012751221656799316,569.4909057617188 -1769682020,58280448,0.690972626209259,0.0011684298515319824,569.4988403320312 -1769682020,71481088,0.6988595724105835,0.0011286437511444092,569.5029296875 -1769682020,111899648,0.7142924070358276,0.000997692346572876,569.5111694335938 -1769682020,160490752,0.7296130657196045,0.0009110569953918457,569.5196533203125 -1769682020,176830208,0.7410564422607422,0.0008169412612915039,569.5261840820312 -1769682020,200724224,0.7485756278038025,0.0007818043231964111,569.530517578125 -1769682020,267350784,0.7674989104270935,0.0006407201290130615,569.5416870117188 -1769682020,274970624,0.7786628007888794,0.000598520040512085,569.5484619140625 -1769682020,299857920,0.786003589630127,0.0005528032779693604,569.5530395507812 -1769682020,363693824,0.8042759299278259,0.000466763973236084,569.564697265625 -1769682020,373732096,0.8151874542236328,0.000398486852645874,569.57177734375 -1769682020,409488640,0.8259691596031189,0.00037151575088500977,569.5789184570312 -1769682020,459198976,0.8401409387588501,0.00034877657890319824,569.5885620117188 -1769682020,467980544,0.8471816778182983,0.0003236234188079834,569.5933837890625 -1769682020,509995008,0.8612171411514282,0.00024640560150146484,569.6031494140625 -1769682020,545180928,0.8750429153442383,0.0001806020736694336,569.6129150390625 -1769682020,573110016,0.8818517923355103,0.00014221668243408203,569.6178588867188 -1769682020,609743104,0.8954381942749023,7.647275924682617e-05,569.6278686523438 -1769682020,644400384,0.9087090492248535,2.8401613235473633e-05,569.6378784179688 -1769682020,678212864,0.9185709953308105,-5.27501106262207e-06,569.6454467773438 -1769682020,710027264,0.9283717274665833,-4.437565803527832e-05,569.653076171875 -1769682020,756964096,0.9420464038848877,-0.000674813985824585,569.6644897460938 -1769682020,778515200,0.9523967504501343,-0.0006685256958007812,569.67626953125 -1769682020,810356224,0.9627034664154053,-0.0005375146865844727,569.6902465820312 -1769682020,859299328,0.976203203201294,-0.00035879015922546387,569.71142578125 -1769682020,873161472,0.9828912019729614,-0.00020202994346618652,569.7227172851562 -1769682020,911720704,0.9961962699890137,-5.46574592590332e-05,569.746337890625 -1769682020,943036672,1.0093625783920288,4.583597183227539e-05,569.77099609375 -1769682020,976241664,1.019111156463623,0.00015661120414733887,569.7897338867188 -1769682021,11999232,1.0287154912948608,0.00024899840354919434,569.8087158203125 -1769682021,46505984,1.0410023927688599,0.00029599666595458984,569.8341674804688 -1769682021,76540416,1.050072193145752,0.0003516674041748047,569.8531494140625 -1769682021,109599232,1.0590667724609375,0.00041943788528442383,569.8720703125 -1769682021,161479168,1.0709161758422852,0.0005351603031158447,569.8970947265625 -1769682021,172013568,1.0767099857330322,0.0006052255630493164,569.9094848632812 -1769682021,210874112,1.088144063949585,0.0006151199340820312,569.9341430664062 -1769682021,247316480,1.0993202924728394,0.0006768703460693359,569.9583129882812 -1769682021,277769216,1.107635259628296,0.0007089376449584961,569.9763793945312 -1769682021,309600000,1.1159093379974365,0.0008350610733032227,569.9940795898438 -1769682021,343551232,1.1267750263214111,0.0009257197380065918,570.0174560546875 -1769682021,376654848,1.1348093748092651,0.0009786486625671387,570.0347900390625 -1769682021,410927360,1.142700433731079,0.0010250210762023926,570.0519409179688 -1769682021,445985536,1.1536376476287842,0.00039833784103393555,570.0741577148438 -1769682021,476542976,1.162210464477539,-0.000638127326965332,570.0875244140625 -1769682021,512369664,1.1706992387771606,-0.0016736388206481934,570.0982666015625 -1769682021,558393856,1.181755542755127,-0.002892613410949707,570.1096801757812 -1769682021,568260608,1.1872248649597168,-0.003498256206512451,570.1144409179688 -1769682021,609369600,1.1980537176132202,-0.004607975482940674,570.12255859375 -1769682021,647580416,1.2086665630340576,-0.005419671535491943,570.12939453125 -1769682021,678950656,1.2164682149887085,-0.005872368812561035,570.1339721679688 -1769682021,710074880,1.224184513092041,-0.006252467632293701,570.1381225585938 -1769682021,761200640,1.2342007160186768,-0.006584107875823975,570.143310546875 -1769682021,776425472,1.24160635471344,-0.006773233413696289,570.1470336914062 -1769682021,809286400,1.2488266229629517,-0.00686955451965332,570.1506958007812 -1769682021,851734528,1.258319616317749,-0.006914675235748291,570.1554565429688 -1769682021,881456384,1.2653332948684692,-0.006907284259796143,570.1590576171875 -1769682021,909940480,1.272186040878296,-0.006901741027832031,570.16259765625 -1769682021,944397056,1.2810794115066528,-0.006790101528167725,570.1672973632812 -1769682021,976044032,1.287627935409546,-0.00670778751373291,570.1707763671875 -1769682022,9891584,1.2940423488616943,-0.006606757640838623,570.17431640625 -1769682022,58281728,1.3023005723953247,-0.006484031677246094,570.1788330078125 -1769682022,70839808,1.3063623905181885,-0.006422996520996094,570.1810302734375 -1769682022,109234688,1.3142986297607422,-0.006267666816711426,570.185302734375 -1769682022,165016064,1.3219280242919922,-0.006155133247375488,570.1893310546875 -1769682022,173906688,1.327533483505249,-0.006082713603973389,570.1922607421875 -1769682022,210400256,1.3329973220825195,-0.00602489709854126,570.1951293945312 -1769682022,252211968,1.3400907516479492,-0.005932509899139404,570.19873046875 -1769682022,278469120,1.3452608585357666,-0.005863487720489502,570.2013549804688 -1769682022,309937152,1.3503382205963135,-0.005833804607391357,570.2039184570312 -1769682022,349891072,1.356782078742981,-0.0058089494705200195,570.2073364257812 -1769682022,378356736,1.361559510231018,-0.005807816982269287,570.2098388671875 -1769682022,410752000,1.3661987781524658,-0.005770325660705566,570.2122802734375 -1769682022,463164416,1.372117042541504,-0.00576549768447876,570.215576171875 -1769682022,475961088,1.3763995170593262,-0.005698859691619873,570.2178955078125 -1769682022,510950912,1.3805235624313354,-0.005669713020324707,570.22021484375 -1769682022,546003968,1.3857985734939575,-0.005613863468170166,570.2229614257812 -1769682022,567844352,1.38837730884552,-0.005531370639801025,570.2242431640625 -1769682022,609457664,1.3933947086334229,-0.00550311803817749,570.2265625 -1769682022,647819264,1.3981637954711914,-0.005510389804840088,570.2286376953125 -1769682022,676432640,1.4018484354019165,-0.005817294120788574,570.230224609375 -1769682022,710038784,1.4053689241409302,-0.00605463981628418,570.23193359375 -1769682022,753816832,1.4098438024520874,-0.006459414958953857,570.2342529296875 -1769682022,776315136,1.4131042957305908,-0.006767928600311279,570.2360229492188 -1769682022,810235648,1.4162051677703857,-0.006992697715759277,570.2378540039062 -1769682022,847983104,1.4201807975769043,-0.007283568382263184,570.2403564453125 -1769682022,877674496,1.423040747642517,-0.007479190826416016,570.2423706054688 -1769682022,909826048,1.4258060455322266,-0.007583260536193848,570.244384765625 -1769682022,944297216,1.4291646480560303,-0.007718145847320557,570.2471923828125 -1769682022,967449856,1.4308050870895386,-0.0077522993087768555,570.2486572265625 -1769682023,11631616,1.4349595308303833,-0.008425712585449219,570.2513427734375 -1769682023,51687936,1.43901526927948,-0.008259296417236328,570.25341796875 -1769682023,78000384,1.4420115947723389,-0.008024275302886963,570.2548217773438 -1769682023,110402048,1.4448353052139282,-0.0077492594718933105,570.2560424804688 -1769682023,149427456,1.4484431743621826,-0.007448375225067139,570.2575073242188 -1769682023,176985088,1.450972080230713,-0.007249176502227783,570.258544921875 -1769682023,209675264,1.4530045986175537,-0.00708085298538208,570.2594604492188 -1769682023,259544064,1.4553520679473877,-0.0069068074226379395,570.260498046875 -1769682023,266912000,1.4564688205718994,-0.006808817386627197,570.260986328125 -1769682023,311222016,1.4586056470870972,-0.006687819957733154,570.261962890625 -1769682023,348101120,1.46038818359375,-0.0066176652908325195,570.2627563476562 -1769682023,371555072,1.461255431175232,-0.006569087505340576,570.26318359375 -1769682023,410250240,1.4628708362579346,-0.00655055046081543,570.2637939453125 -1769682023,448106752,1.4642748832702637,-0.0065007805824279785,570.2643432617188 -1769682023,476479744,1.465095043182373,-0.006479918956756592,570.2647094726562 -1769682023,500643584,1.4656414985656738,-0.006459712982177734,570.264892578125 -1769682023,547759616,1.4665926694869995,-0.006450831890106201,570.2652587890625 -1769682023,576055296,1.4670159816741943,-0.006396353244781494,570.265380859375 -1769682023,609672192,1.4673590660095215,-0.006432831287384033,570.2654418945312 -1769682023,650035200,1.4675931930541992,-0.006460309028625488,570.2655029296875 -1769682023,677083136,1.46766197681427,-0.006436705589294434,570.2655029296875 -1769682023,709906944,1.4676696062088013,-0.0064713358879089355,570.2654418945312 -1769682023,766795520,1.4674938917160034,-0.006406247615814209,570.2654418945312 -1769682023,774999552,1.4672491550445557,-0.00642627477645874,570.2654418945312 -1769682023,810286080,1.4668655395507812,-0.006418883800506592,570.2655029296875 -1769682023,845579776,1.4661850929260254,-0.006449103355407715,570.265625 -1769682023,876539904,1.4655284881591797,-0.0064386725425720215,570.2657470703125 -1769682023,910625536,1.464797019958496,-0.006431698799133301,570.2659912109375 -1769682023,949912320,1.4639121294021606,-0.006606400012969971,570.2666015625 -1769682023,979220992,1.463228702545166,-0.006471157073974609,570.2681274414062 -1769682024,9494784,1.4624919891357422,-0.006299257278442383,570.270263671875 -1769682024,48824320,1.461342215538025,-0.005999863147735596,570.2738037109375 -1769682024,78976768,1.4603530168533325,-0.00581049919128418,570.2767333984375 -1769682024,111081216,1.459296703338623,-0.005657374858856201,570.27978515625 -1769682024,143403008,1.4575475454330444,-0.005473434925079346,570.283935546875 -1769682024,176911360,1.4559658765792847,-0.0053931474685668945,570.2870483398438 -1769682024,210180352,1.4542919397354126,-0.005321085453033447,570.2901611328125 -1769682024,247812864,1.4518803358078003,-0.005165219306945801,570.2942504882812 -1769682024,276721152,1.4499311447143555,-0.005102753639221191,570.2972412109375 -1769682024,310908160,1.4479113817214966,-0.005037426948547363,570.300048828125 -1769682024,346422528,1.4450902938842773,-0.0049359798431396484,570.3037109375 -1769682024,376124160,1.4428856372833252,-0.004870891571044922,570.3062744140625 -1769682024,409735680,1.4405992031097412,-0.004857778549194336,570.308837890625 -1769682024,446251264,1.4373998641967773,-0.004820466041564941,570.3119506835938 -1769682024,477371136,1.4349311590194702,-0.004778146743774414,570.314208984375 -1769682024,509789184,1.4324043989181519,-0.004737377166748047,570.31640625 -1769682024,561978112,1.4288465976715088,-0.0046776533126831055,570.3190307617188 -1769682024,568792064,1.427140235900879,-0.00473630428314209,570.3203125 -1769682024,611080448,1.4238603115081787,-0.005158901214599609,570.3214111328125 -1769682024,645825024,1.4204686880111694,-0.005579590797424316,570.3208618164062 -1769682024,676946944,1.4178593158721924,-0.0058307647705078125,570.3195190429688 -1769682024,709777920,1.4151439666748047,-0.006087601184844971,570.3175659179688 -1769682024,757107456,1.4114354848861694,-0.006300687789916992,570.3140869140625 -1769682024,766074624,1.4095600843429565,-0.006425082683563232,570.3121337890625 -1769682024,810304512,1.4057164192199707,-0.006579220294952393,570.3076171875 -1769682024,860168704,1.4017140865325928,-0.006653845310211182,570.3026123046875 -1769682024,875788032,1.398675799369812,-0.006672859191894531,570.298583984375 -1769682024,910029056,1.3955953121185303,-0.006637096405029297,570.2943725585938 -1769682024,945895680,1.3914016485214233,-0.006598412990570068,570.2886352539062 -1769682024,967036672,1.3892947435379028,-0.0065847039222717285,570.28564453125 -1769682025,14262016,1.3849163055419922,-0.006494402885437012,570.2796020507812 -1769682025,46508288,1.3803998231887817,-0.006346166133880615,570.2733154296875 -1769682025,76677888,1.3770029544830322,-0.006285488605499268,570.2684326171875 -1769682025,110007552,1.373533844947815,-0.006217062473297119,570.263427734375 -1769682025,152466688,1.36881422996521,-0.006015360355377197,570.2564086914062 -1769682025,178351616,1.3652430772781372,-0.00590139627456665,570.2508544921875 -1769682025,209779456,1.361573576927185,-0.005802810192108154,570.2451171875 -1769682025,249698048,1.356640338897705,-0.0056459903717041016,570.2371215820312 -1769682025,278513920,1.3528919219970703,-0.005554318428039551,570.2308349609375 -1769682025,310361344,1.3490948677062988,-0.005461752414703369,570.2243041992188 -1769682025,344456192,1.3438917398452759,-0.005258440971374512,570.2152709960938 -1769682025,366577408,1.3412437438964844,-0.00521010160446167,570.2106323242188 -1769682025,410379776,1.3359510898590088,-0.0050969719886779785,570.2010498046875 -1769682025,458596096,1.3299224376678467,-0.004411220550537109,570.1909790039062 -1769682025,468074240,1.3265104293823242,-0.003742516040802002,570.1853637695312 -1769682025,501568256,1.3196752071380615,-0.0022454261779785156,570.173583984375 -1769682025,548381696,1.3127775192260742,-0.0008481144905090332,570.160888671875 -1769682025,579007744,1.3075554370880127,0.00010949373245239258,570.1509399414062 -1769682025,613205248,1.3023066520690918,0.000948786735534668,570.1407470703125 -1769682025,650180096,1.2952643632888794,0.0018725991249084473,570.1267700195312 -1769682025,677007872,1.2899545431137085,0.0024089813232421875,570.1160278320312 -1769682025,709657088,1.2845860719680786,0.00283128023147583,570.1051635742188 -1769682025,762062848,1.277322769165039,0.0032035112380981445,570.09033203125 -1769682025,769367808,1.2736775875091553,0.0033341050148010254,570.082763671875 -1769682025,811301120,1.2663185596466064,0.0035970211029052734,570.0675048828125 -1769682025,845297664,1.2588778734207153,0.003710627555847168,570.0520629882812 -1769682025,896216320,1.2532851696014404,0.0036906003952026367,570.040283203125 -1769682025,915953920,1.247652530670166,0.0036672353744506836,570.0285034179688 -1769682025,949428224,1.2401466369628906,0.003451824188232422,570.0127563476562 -1769682025,965853952,1.2365556955337524,0.0033254027366638184,570.0048828125 -1769682026,9931264,1.22934889793396,0.003306448459625244,569.9888916015625 -1769682026,59662080,1.2220090627670288,0.003249943256378174,569.9729614257812 -1769682026,67353600,1.218313455581665,0.0032047033309936523,569.9650268554688 -1769682026,112329472,1.2108241319656372,0.0031914710998535156,569.94921875 -1769682026,152102144,1.2032591104507446,0.0031793713569641113,569.933349609375 -1769682026,178870016,1.197577953338623,0.0031754374504089355,569.92138671875 -1769682026,210887424,1.191680669784546,0.003114759922027588,569.9093017578125 -1769682026,247811072,1.1835047006607056,0.0030919313430786133,569.8930053710938 -1769682026,277165824,1.1772501468658447,0.003103971481323242,569.880615234375 -1769682026,312314880,1.1709585189819336,0.0031049251556396484,569.8682250976562 -1769682026,360579584,1.1625046730041504,0.003117680549621582,569.8516845703125 -1769682026,371497472,1.1582728624343872,0.0030648112297058105,569.8433227539062 -1769682026,410829312,1.1497864723205566,0.003114044666290283,569.8267211914062 -1769682026,456234240,1.1433812379837036,0.0031099319458007812,569.8142700195312 -1769682026,473700096,1.1346864700317383,0.003108382225036621,569.797607421875 -1769682026,510818048,1.1281338930130005,0.00312119722366333,569.7850952148438 -1769682026,546595072,1.1193509101867676,0.0031461715698242188,569.768310546875 -1769682026,568272384,1.114918828010559,0.0030820369720458984,569.7598876953125 -1769682026,610980608,1.1060948371887207,0.00315701961517334,569.7429809570312 -1769682026,661186816,1.0972572565078735,0.00310593843460083,569.7258911132812 -1769682026,667794944,1.0928001403808594,0.003069758415222168,569.7173461914062 -1769682026,709958912,1.083855152130127,0.003171265125274658,569.7001342773438 -1769682026,752225280,1.0748409032821655,0.003210723400115967,569.6827392578125 -1769682026,777706496,1.0680482387542725,0.003205239772796631,569.669677734375 -1769682026,811253760,1.0612399578094482,0.003212064504623413,569.6564331054688 -1769682026,855318528,1.0521458387374878,0.003198176622390747,569.6387329101562 -1769682026,877013760,1.0453118085861206,0.003284662961959839,569.6253662109375 -1769682026,910053376,1.0379053354263306,0.0037120580673217773,569.6116333007812 -1769682026,960334336,1.0276094675064087,0.003562629222869873,569.5892944335938 -1769682026,967832064,1.0224577188491821,0.0033068954944610596,569.5767211914062 -1769682027,11836928,1.0120668411254883,0.002973586320877075,569.5494384765625 -1769682027,44439808,1.0016783475875854,0.002626180648803711,569.520263671875 -1769682027,79593216,0.9938756823539734,0.0023915469646453857,569.4974365234375 -1769682027,110434304,0.9861663579940796,0.002217620611190796,569.4740600585938 -1769682027,151532800,0.9759067296981812,0.0020374655723571777,569.4424438476562 -1769682027,177962752,0.9681947827339172,0.0018832981586456299,569.4183959960938 -1769682027,213708288,0.9608729481697083,0.0018936693668365479,569.3942260742188 -1769682027,261926912,0.9543876647949219,0.001827925443649292,569.362548828125 -1769682027,275143168,0.9495632648468018,0.001761108636856079,569.3382568359375 -1769682027,310466816,0.9447576403617859,0.0016674399375915527,569.313720703125 -1769682027,364397824,0.9383409023284912,0.0016127228736877441,569.28076171875 -1769682027,373976832,0.9335269927978516,0.0015704333782196045,569.256103515625 -1769682027,411624704,0.9286788702011108,0.0015349090099334717,569.2313842773438 -1769682027,445452032,0.9221639633178711,0.0014999806880950928,569.1985473632812 -1769682027,476713728,0.9171479940414429,0.0014852583408355713,569.174072265625 -1769682027,510582528,0.9121495485305786,0.0014577209949493408,569.1495971679688 -1769682027,548461312,0.905417799949646,0.0014188289642333984,569.1170654296875 -1769682027,567404288,0.9020519256591797,0.001373887062072754,569.1008911132812 -1769682027,644111360,0.895104169845581,0.0013123154640197754,569.0687866210938 -1769682027,656914432,0.8881554007530212,0.0012467801570892334,569.0368041992188 -1769682027,684760064,0.8827405571937561,0.0012216567993164062,569.0130004882812 -1769682027,698005248,0.8791128396987915,0.001092463731765747,568.9971923828125 -1769682027,751879168,0.8699343800544739,0.001028597354888916,568.958251953125 -1769682027,767991552,0.8662237524986267,0.0009391605854034424,568.9428100585938 -1769682027,813732096,0.8586432933807373,0.000856935977935791,568.9124145507812 -1769682027,866561024,0.8510111570358276,0.0007573366165161133,568.8824462890625 -1769682027,875343616,0.8450344800949097,0.0006998777389526367,568.8602294921875 -1769682027,910790144,0.8390195369720459,0.0006293356418609619,568.8381958007812 -1769682027,963478784,0.8308883309364319,0.0004868805408477783,568.809326171875 -1769682027,969682176,0.8268053531646729,0.00042572617530822754,568.794921875 -1769682028,10211584,0.8182531595230103,0.0006546676158905029,568.7664794921875 -1769682028,49096448,0.8086415529251099,0.0016969144344329834,568.7416381835938 -1769682028,80280832,0.8013898134231567,0.002469360828399658,568.7257080078125 -1769682028,110780160,0.7939980030059814,0.00321120023727417,568.7115478515625 -1769682028,146125056,0.7840884923934937,0.004038304090499878,568.6947631835938 -1769682028,177079040,0.7766256332397461,0.0045822858810424805,568.6831665039062 -1769682028,211643392,0.7691256403923035,0.005023211240768433,568.67236328125 -1769682028,254212352,0.759049117565155,0.005441337823867798,568.6587524414062 -1769682028,277073920,0.7514827251434326,0.005681425333023071,568.6491088867188 -1769682028,310291456,0.7438399195671082,0.005835920572280884,568.6397705078125 -1769682028,360554240,0.7335982322692871,0.005937367677688599,568.6276245117188 -1769682028,368471040,0.7284496426582336,0.005967527627944946,568.6217651367188 -1769682028,412475136,0.7180731296539307,0.00596049427986145,568.610107421875 -1769682028,445781760,0.7076643109321594,0.005873769521713257,568.5985107421875 -1769682028,481013504,0.6998646855354309,0.005782127380371094,568.5899658203125 -1769682028,510216192,0.6920592188835144,0.0056719183921813965,568.5814819335938 -1769682028,560651776,0.6816635727882385,0.005577415227890015,568.5701904296875 -1769682028,566945792,0.6764436960220337,0.0054922401905059814,568.5646362304688 -1769682028,614487296,0.6659978628158569,0.005387485027313232,568.5535888671875 -1769682028,660991744,0.6554663777351379,0.00529053807258606,568.5426635742188 -1769682028,674107648,0.6475256681442261,0.005171984434127808,568.5345458984375 -1769682028,710073344,0.6395736932754517,0.005112737417221069,568.5264892578125 -1769682028,760282368,0.6291705369949341,0.004980891942977905,568.5158081054688 -1769682028,768824320,0.6239858865737915,0.004955947399139404,568.5105590820312 -1769682028,811567360,0.6135975122451782,0.004886448383331299,568.5000610351562 -1769682028,845769728,0.603320837020874,0.004808485507965088,568.4896850585938 -1769682028,882558464,0.595665454864502,0.00478518009185791,568.48193359375 -1769682028,911276544,0.5881590247154236,0.004753082990646362,568.4742431640625 -1769682028,945028096,0.5780695080757141,0.004675716161727905,568.4640502929688 -1769682028,978710272,0.5705798864364624,0.004644900560379028,568.4564819335938 -1769682029,12293632,0.5630281567573547,0.004650980234146118,568.4489135742188 -1769682029,56102400,0.5529813170433044,0.004574805498123169,568.43896484375 -1769682029,76901376,0.5453642010688782,0.004523545503616333,568.4315185546875 -1769682029,110517504,0.5377165079116821,0.0044913142919540405,568.4241943359375 -1769682029,157400064,0.5275828838348389,0.004421904683113098,568.4146118164062 -1769682029,167223808,0.5225407481193542,0.0044068992137908936,568.4098510742188 -1769682029,210168320,0.5124862790107727,0.004338309168815613,568.4005737304688 -1769682029,247192320,0.5023321509361267,0.0042601078748703,568.391357421875 -1769682029,282624000,0.4946204721927643,0.004167869687080383,568.384765625 -1769682029,310194944,0.4869912266731262,0.004110455513000488,568.378173828125 -1769682029,347652608,0.47687584161758423,0.003982469439506531,568.3696899414062 -1769682029,377350912,0.4692350924015045,0.003923505544662476,568.363525390625 -1769682029,411024384,0.4615742862224579,0.0038654357194900513,568.3574829101562 -1769682029,448530176,0.4513756334781647,0.0037002116441726685,568.3497924804688 -1769682029,477465600,0.4437216818332672,0.0036225616931915283,568.3441162109375 -1769682029,511297536,0.4345254898071289,0.0035324394702911377,568.338623046875 -1769682029,560945152,0.4181818664073944,0.0033995360136032104,568.33203125 -1769682029,588105216,0.40223538875579834,0.0032590925693511963,568.3275756835938 -1769682029,599667712,0.39161762595176697,0.0032034069299697876,568.324951171875 -1769682029,650412032,0.3650931417942047,0.003013819456100464,568.3193969726562 -1769682029,677948160,0.3504143953323364,0.002849876880645752,568.3164672851562 -1769682029,712882176,0.33759579062461853,0.0022565722465515137,568.3139038085938 -1769682029,749582592,0.319652259349823,0.0016498416662216187,568.3112182617188 -1769682029,779251968,0.30560117959976196,0.0012362897396087646,568.3099365234375 -1769682029,810401792,0.29346051812171936,0.0009064674377441406,568.3088989257812 -1769682029,860771072,0.27422070503234863,0.00036190450191497803,568.3080444335938 -1769682029,870544384,0.26522013545036316,0.00012759119272232056,568.307861328125 -1769682029,911330048,0.2497471570968628,-0.0002217516303062439,568.3076171875 -1769682029,954052864,0.2318413108587265,-0.0004913285374641418,568.3076782226562 -1769682029,978973184,0.2193201184272766,-0.0006867200136184692,568.3079223632812 -1769682030,10588928,0.20785000920295715,-0.0008244365453720093,568.308349609375 -1769682030,50333696,0.1947534829378128,-0.000963069498538971,568.3088989257812 -1769682030,76921344,0.18529489636421204,-0.0010307952761650085,568.309326171875 -1769682030,112819200,0.17582686245441437,-0.0010975450277328491,568.3097534179688 -1769682030,155048192,0.16318705677986145,-0.0011465847492218018,568.310302734375 -1769682030,177158400,0.15369611978530884,-0.001230582594871521,568.3108520507812 -1769682030,210197760,0.14420393109321594,-0.001211009919643402,568.3114013671875 -1769682030,255967744,0.126634418964386,-0.0012980923056602478,568.3125 -1769682030,265013760,0.1184837818145752,-0.0012944899499416351,568.3131713867188 -1769682030,312213760,0.10499685257673264,-0.0012997016310691833,568.3146362304688 -1769682030,346783232,0.0923539251089096,-0.001350313425064087,568.3161010742188 -1769682030,379937536,0.08287496119737625,-0.0013518482446670532,568.317138671875 -1769682030,410745344,0.07339383661746979,-0.001361347734928131,568.3181762695312 -1769682030,450412544,0.06074490398168564,-0.0014066118746995926,568.3196411132812 -1769682030,477702400,0.051249679177999496,-0.0013838186860084534,568.3207397460938 -1769682030,514553088,0.04175219684839249,-0.001406269147992134,568.3219604492188 -1769682030,557469952,0.0,-0.0,568.323486328125 -1769682030,570848000,0.0,-0.0,568.323486328125 -1769682030,610797312,0.0,-0.0,568.323486328125 -1769682030,663069184,0.0,-0.0,568.323486328125 -1769682030,669417984,0.0,-0.0,568.323486328125 -1769682030,711440384,0.0,-0.0,568.323486328125 -1769682030,748741888,0.0,-0.0,568.323486328125 -1769682030,778473472,0.0,-0.0,568.323486328125 -1769682030,810345472,0.0,-0.0,568.323486328125 -1769682030,849885440,0.0,-0.0,568.323486328125 -1769682030,877724160,0.0,-0.0,568.323486328125 -1769682030,916821504,0.0,-0.0,568.323486328125 -1769682030,949130240,0.0,-0.0,568.323486328125 -1769682030,977305088,0.0,-0.0,568.323486328125 -1769682031,10384896,0.0,-0.0,568.323486328125 -1769682031,57372928,0.0,-0.0,568.323486328125 -1769682031,77635584,0.0,-0.0,568.323486328125 -1769682031,111345408,0.0,-0.0,568.323486328125 -1769682031,143959040,0.0,-0.0,568.323486328125 -1769682031,184395008,0.0,-0.0,568.323486328125 -1769682031,210745856,0.0,-0.0,568.323486328125 -1769682031,250777600,0.0,-0.0,568.323486328125 -1769682031,277001728,0.0,-0.0,568.323486328125 -1769682031,310998272,0.0,-0.0,568.323486328125 -1769682031,349408000,0.0,-0.0,568.323486328125 -1769682031,378355712,0.0,-0.0,568.323486328125 -1769682031,410254336,0.0,-0.0,568.323486328125 -1769682031,461301248,0.0,-0.0,568.323486328125 -1769682031,471190528,0.0,-0.0,568.323486328125 -1769682031,500407552,0.0,-0.0,568.323486328125 -1769682031,546347520,0.0,-0.0,568.323486328125 -1769682031,580910080,0.0,-0.0,568.323486328125 -1769682031,610586624,0.0,-0.0,568.323486328125 -1769682031,648016128,0.0,-0.0,568.323486328125 -1769682031,677543424,0.0,-0.0,568.323486328125 -1769682031,714375680,0.0,-0.0,568.323486328125 -1769682031,750040832,0.0,-0.0,568.323486328125 -1769682031,776999168,0.0,-0.0,568.323486328125 -1769682031,810507008,0.0,-0.0,568.323486328125 -1769682031,853347328,0.0,-0.0,568.323486328125 -1769682031,878041088,0.0,-0.0,568.323486328125 -1769682031,913138432,0.0,-0.0,568.323486328125 -1769682031,946487040,0.0,-0.0,568.323486328125 -1769682031,978632192,0.0,-0.0,568.323486328125 -1769682032,10790912,0.0,-0.0,568.323486328125 -1769682032,48818176,0.0,-0.0,568.323486328125 -1769682032,82276096,0.0,-0.0,568.323486328125 -1769682032,107709440,0.0,-0.0,568.323486328125 -1769682032,154711040,0.0,-0.0,568.323486328125 -1769682032,179374336,0.0,-0.0,568.323486328125 -1769682032,212811776,0.0,-0.0,568.323486328125 -1769682032,262229760,0.0,-0.0,568.323486328125 -1769682032,275307776,0.0,-0.0,568.323486328125 -1769682032,310843904,0.0,-0.0,568.323486328125 -1769682032,346019328,0.0,-0.0,568.323486328125 -1769682032,377274112,0.0,-0.0,568.323486328125 -1769682032,410601728,0.0,-0.0,568.323486328125 -1769682032,444560128,0.0,-0.0,568.323486328125 -1769682032,477168384,0.0,-0.0,568.323486328125 -1769682032,502210816,0.0,-0.0,568.323486328125 -1769682032,545907968,0.0,-0.0,568.323486328125 -1769682032,577404928,0.0,-0.0,568.323486328125 -1769682032,610657280,0.0,-0.0,568.323486328125 -1769682032,647803904,0.0,-0.0,568.323486328125 -1769682032,680634112,0.0,-0.0,568.323486328125 -1769682032,710440448,0.0,-0.0,568.323486328125 -1769682032,745906176,0.0,-0.0,568.323486328125 -1769682032,777254912,0.0,-0.0,568.323486328125 -1769682032,811275264,0.0,-0.0,568.323486328125 -1769682032,844671744,0.0,-0.0,568.323486328125 -1769682032,877242624,0.0,-0.0,568.323486328125 -1769682032,911954944,0.0,-0.0,568.323486328125 -1769682032,945617408,0.0,-0.0,568.323486328125 -1769682032,977945600,0.0,-0.0,568.323486328125 -1769682033,11794432,0.0,-0.0,568.323486328125 -1769682033,60879104,0.0,-0.0,568.323486328125 -1769682033,69714432,0.0,-0.0,568.323486328125 -1769682033,111066880,0.0,-0.0,568.323486328125 -1769682033,158437632,0.0,-0.0,568.323486328125 -1769682033,166098688,0.0,-0.0,568.323486328125 -1769682033,210859520,0.0,-0.0,568.323486328125 -1769682033,244612608,0.0,-0.0,568.323486328125 -1769682033,281619968,0.0,-0.0,568.323486328125 -1769682033,311275008,0.0,-0.0,568.323486328125 -1769682033,347122176,0.0,-0.0,568.323486328125 -1769682033,377266944,0.0,-0.0,568.323486328125 -1769682033,413937920,0.0,-0.0,568.323486328125 -1769682033,450033408,0.0,-0.0,568.323486328125 -1769682033,478630400,0.0,-0.0,568.323486328125 -1769682033,511009024,0.0,-0.0,568.323486328125 -1769682033,556636416,0.0,-0.0,568.323486328125 -1769682033,577266944,0.0,-0.0,568.323486328125 -1769682033,611532288,0.0,-0.0,568.323486328125 -1769682033,644963584,0.0,-0.0,568.323486328125 -1769682033,680730624,0.0,-0.0,568.323486328125 -1769682033,710942208,0.0,-0.0,568.323486328125 -1769682033,747179520,0.0,-0.0,568.323486328125 -1769682033,777428992,0.0,-0.0,568.323486328125 -1769682033,811333632,0.0,-0.0,568.323486328125 -1769682033,848051968,0.0,-0.0,568.323486328125 -1769682033,877368832,0.0,-0.0,568.323486328125 -1769682033,911312384,0.0,-0.0,568.323486328125 -1769682033,964037120,0.0,-0.0,568.323486328125 -1769682033,972689664,0.0,-0.0,568.323486328125 -1769682034,12852480,0.0,-0.0,568.323486328125 -1769682034,51555584,0.0,-0.0,568.323486328125 -1769682034,77428224,0.0,-0.0,568.323486328125 -1769682034,111391744,0.0,-0.0,568.323486328125 -1769682034,146973440,0.0,-0.0,568.323486328125 -1769682034,179236096,0.0,-0.0,568.323486328125 -1769682034,211236352,0.0,-0.0,568.323486328125 -1769682034,250308864,0.0,-0.0,568.323486328125 -1769682034,279852032,0.0,-0.0,568.323486328125 -1769682034,311110144,0.0,-0.0,568.323486328125 -1769682034,346388992,0.0,-0.0,568.323486328125 -1769682034,377884928,0.0,-0.0,568.323486328125 -1769682034,410956032,0.0,-0.0,568.323486328125 -1769682034,445188864,0.0,-0.0,568.323486328125 -1769682034,478537472,0.0,-0.0,568.323486328125 -1769682034,499556864,0.0,-0.0,568.323486328125 -1769682034,558608896,0.0,-0.0,568.323486328125 -1769682034,566222336,0.0,-0.0,568.323486328125 -1769682034,610942720,0.0,-0.0,568.323486328125 -1769682034,649748992,0.0,-0.0,568.323486328125 -1769682034,678623744,0.0,-0.0,568.323486328125 -1769682034,711161856,0.0,-0.0,568.323486328125 -1769682034,744919040,0.0,-0.0,568.323486328125 -1769682034,770488576,0.0,-0.0,568.323486328125 -1769682034,810967552,0.0,-0.0,568.323486328125 -1769682034,844198656,0.0,-0.0,568.323486328125 -1769682034,877826816,0.0,-0.0,568.323486328125 -1769682034,911442944,0.0,-0.0,568.323486328125 -1769682034,947166464,0.0,-0.0,568.323486328125 -1769682034,977293568,0.0,-0.0,568.323486328125 -1769682035,10707712,0.0,-0.0,568.323486328125 -1769682035,48817664,0.0,-0.0,568.323486328125 -1769682035,78212608,0.0,-0.0,568.323486328125 -1769682035,110927616,0.0,-0.0,568.323486328125 -1769682035,144241664,0.0,-0.0,568.323486328125 -1769682035,180390144,0.0,-0.0,568.323486328125 -1769682035,211495680,0.0,-0.0,568.323486328125 -1769682035,245824768,0.0,-0.0,568.323486328125 -1769682035,278438912,0.0,-0.0,568.323486328125 -1769682035,312543744,0.0,-0.0,568.323486328125 -1769682035,350884352,0.0,-0.0,568.323486328125 -1769682035,378329600,0.0,-0.0,568.323486328125 -1769682035,410887680,0.0,-0.0,568.323486328125 -1769682035,449850880,0.0,-0.0,568.323486328125 -1769682035,478678272,0.0,-0.0,568.323486328125 -1769682035,510786304,0.0,-0.0,568.323486328125 -1769682035,560483328,0.0,-0.0,568.323486328125 -1769682035,568632576,0.0,-0.0,568.323486328125 -1769682035,613108992,0.0,-0.0,568.323486328125 -1769682035,646489088,0.0,-0.0,568.323486328125 -1769682035,678986240,0.0,-0.0,568.323486328125 -1769682035,711233280,0.0,-0.0,568.323486328125 -1769682035,745938176,0.0,-0.0,568.323486328125 -1769682035,778034688,0.0,-0.0,568.323486328125 -1769682035,813909504,0.0,-0.0,568.323486328125 -1769682035,861506560,0.0,-0.0,568.323486328125 -1769682035,869815040,0.0,-0.0,568.323486328125 -1769682035,910958592,0.0,-0.0,568.323486328125 -1769682035,957783296,0.0,-0.0,568.323486328125 -1769682035,964920832,0.0,-0.0,568.323486328125 -1769682036,11871488,0.0,-0.0,568.323486328125 -1769682036,46388992,0.0,-0.0,568.323486328125 -1769682036,79678720,0.0,-0.0,568.323486328125 -1769682036,112663808,0.0,-0.0,568.323486328125 -1769682036,147660288,0.0,-0.0,568.323486328125 -1769682036,178141440,0.0,-0.0,568.323486328125 -1769682036,213507328,0.0,-0.0,568.323486328125 -1769682036,260341760,0.0,-0.0,568.323486328125 -1769682036,267788544,0.0,-0.0,568.323486328125 -1769682036,311344640,0.0,-0.0,568.323486328125 -1769682036,357347840,0.0,-0.0,568.323486328125 -1769682036,367428608,0.0,-0.0,568.323486328125 -1769682036,411094784,0.0,-0.0,568.323486328125 -1769682036,447497472,0.0,-0.0,568.323486328125 -1769682036,479294208,0.0,-0.0,568.323486328125 -1769682036,511515392,0.0,-0.0,568.323486328125 -1769682036,545165824,0.0,-0.0,568.323486328125 -1769682036,564911360,0.0,-0.0,568.323486328125 -1769682036,611600640,0.0,-0.0,568.323486328125 -1769682036,665410816,0.0,-0.0,568.323486328125 -1769682036,667355392,0.0,-0.0,568.323486328125 -1769682036,710890752,0.0,-0.0,568.323486328125 -1769682036,753034752,0.0,-0.0,568.323486328125 -1769682036,777930240,0.0,-0.0,568.323486328125 -1769682036,810848512,0.0,-0.0,568.323486328125 -1769682036,846670336,0.0,-0.0,568.323486328125 -1769682036,878987008,0.0,-0.0,568.323486328125 -1769682036,913356032,0.0,-0.0,568.323486328125 -1769682036,948589824,0.0,-0.0,568.323486328125 -1769682036,977628672,0.0,-0.0,568.323486328125 -1769682037,13882880,0.0,-0.0,568.323486328125 -1769682037,57195008,0.0,-0.0,568.323486328125 -1769682037,79206400,0.0,-0.0,568.323486328125 -1769682037,111496192,0.0,-0.0,568.323486328125 -1769682037,162307840,0.0,-0.0,568.323486328125 -1769682037,170710016,0.0,-0.0,568.323486328125 -1769682037,211749376,0.0,-0.0,568.323486328125 -1769682037,244899840,0.0,-0.0,568.323486328125 -1769682037,278977024,0.0,-0.0,568.323486328125 -1769682037,311112192,0.0,-0.0,568.323486328125 -1769682037,345214208,0.0,-0.0,568.323486328125 -1769682037,377905664,0.0,-0.0,568.323486328125 -1769682037,415186688,0.0,-0.0,568.323486328125 -1769682037,449613312,0.0,-0.0,568.323486328125 -1769682037,478336256,0.0,-0.0,568.323486328125 -1769682037,510944768,0.0,-0.0,568.323486328125 -1769682037,558311680,0.0,-0.0,568.323486328125 -1769682037,569397504,0.0,-0.0,568.323486328125 -1769682037,613230080,0.0,-0.0,568.323486328125 -1769682037,645111552,0.0,-0.0,568.323486328125 -1769682037,681391104,0.0,-0.0,568.323486328125 -1769682037,713490176,0.0,-0.0,568.323486328125 -1769682037,755211776,0.0,-0.0,568.323486328125 -1769682037,778462720,0.0,-0.0,568.323486328125 -1769682037,798923008,0.0,-0.0,568.323486328125 -1769682037,849284864,0.0,-0.0,568.323486328125 -1769682037,877931264,0.0,-0.0,568.323486328125 -1769682037,911852288,0.0,-0.0,568.323486328125 -1769682037,964865280,0.0,-0.0,568.323486328125 -1769682037,975822080,0.0,-0.0,568.323486328125 -1769682038,13005056,0.0,-0.0,568.323486328125 -1769682038,46932736,0.0,-0.0,568.323486328125 -1769682038,66534656,0.0,-0.0,568.323486328125 -1769682038,111244032,0.0,-0.0,568.323486328125 -1769682038,146597120,0.0,-0.0,568.323486328125 -1769682038,177817088,0.0,-0.0,568.323486328125 -1769682038,211213824,0.0,-0.0,568.323486328125 -1769682038,246549248,0.0,-0.0,568.323486328125 -1769682038,278257920,0.0,-0.0,568.323486328125 -1769682038,311378944,0.0,-0.0,568.323486328125 -1769682038,351210752,0.0,-0.0,568.323486328125 -1769682038,379072256,0.0,-0.0,568.323486328125 -1769682038,411606016,0.0,-0.0,568.323486328125 -1769682038,463187200,0.0,-0.0,568.323486328125 -1769682038,470382336,0.0,-0.0,568.323486328125 -1769682038,511718656,0.0,-0.0,568.323486328125 -1769682038,545495296,0.0,-0.0,568.323486328125 -1769682038,581912832,0.0,-0.0,568.323486328125 -1769682038,611838720,0.0,-0.0,568.323486328125 -1769682038,652561408,0.0,-0.0,568.323486328125 -1769682038,677951744,0.0,-0.0,568.323486328125 -1769682038,713323264,0.0,-0.0,568.323486328125 -1769682038,760099072,0.0,-0.0,568.323486328125 -1769682038,770226944,0.0,-0.0,568.323486328125 -1769682038,812808192,0.0,-0.0,568.323486328125 -1769682038,861056512,0.0,-0.0,568.323486328125 -1769682038,869102592,0.0,-0.0,568.323486328125 -1769682038,913009152,0.0,-0.0,568.323486328125 -1769682038,945923328,0.0,-0.0,568.323486328125 -1769682038,980034560,0.0,-0.0,568.323486328125 -1769682039,11477760,0.0,-0.0,568.323486328125 -1769682039,46122240,0.0,-0.0,568.323486328125 -1769682039,78223104,0.0,-0.0,568.323486328125 -1769682039,114045184,0.0,-0.0,568.323486328125 -1769682039,149462528,0.0,-0.0,568.323486328125 -1769682039,179556608,0.0,-0.0,568.323486328125 -1769682039,211515136,0.0,-0.0,568.323486328125 -1769682039,258198272,0.0,-0.0,568.323486328125 -1769682039,267484416,0.0,-0.0,568.323486328125 -1769682039,314381824,0.0,-0.0,568.323486328125 -1769682039,345506304,0.0,-0.0,568.323486328125 -1769682039,380849408,0.004304932430386543,-0.0003387089818716049,568.3233032226562 -1769682039,411998720,0.010385260917246342,-0.0005474374629557133,568.3225708007812 -1769682039,447040768,0.021574074402451515,-0.0008427798748016357,568.3211059570312 -1769682039,478358784,0.03132953867316246,-0.0009535057470202446,568.3195190429688 -1769682039,515328768,0.041746724396944046,-0.0011375341564416885,568.317626953125 -1769682039,555527936,0.05619187653064728,-0.0012403745204210281,568.3148803710938 -1769682039,577938432,0.06737158447504044,-0.0013482943177223206,568.3126831054688 -1769682039,611113216,0.07889772206544876,-0.0014522597193717957,568.310302734375 -1769682039,658479616,0.09468492865562439,-0.0015175938606262207,568.306884765625 -1769682039,667680256,0.10273553431034088,-0.0015335269272327423,568.3052368164062 -1769682039,711694848,0.1193932443857193,-0.0015384145081043243,568.3016357421875 -1769682039,746969344,0.1364668756723404,-0.001567050814628601,568.2979125976562 -1769682039,783238400,0.1494489163160324,-0.0015780627727508545,568.2950439453125 -1769682039,811693312,0.16244125366210938,-0.001562073826789856,568.2921142578125 -1769682039,849479680,0.17987367510795593,-0.001544564962387085,568.2881469726562 -1769682039,878272256,0.19306673109531403,-0.0015404969453811646,568.2850341796875 -1769682039,913654016,0.20670358836650848,-0.0015006139874458313,568.281982421875 -1769682039,962109184,0.22613760828971863,-0.0014638155698776245,568.2777709960938 -1769682039,969804032,0.23627284169197083,-0.001462496817111969,568.275634765625 -1769682040,11296512,0.2567726969718933,-0.0013962611556053162,568.271240234375 -1769682040,68576256,0.27826350927352905,-0.0013244599103927612,568.2666625976562 -1769682040,70912256,0.28904828429222107,-0.0013183653354644775,568.264404296875 -1769682040,111466752,0.31204864382743835,-0.00134354829788208,568.259765625 -1769682040,145849344,0.33623233437538147,-0.0012784600257873535,568.2548217773438 -1769682040,178264064,0.35447147488594055,-0.0012617707252502441,568.2510986328125 -1769682040,212143872,0.3733103275299072,-0.001230284571647644,568.247314453125 -1769682040,253830656,0.3995092809200287,-0.001223236322402954,568.2421875 -1769682040,280110080,0.4196745753288269,-0.0011937618255615234,568.23828125 -1769682040,311152896,0.4408283233642578,-0.00122736394405365,568.2342529296875 -1769682040,365725696,0.4695686101913452,-0.0011677742004394531,568.2288818359375 -1769682040,374702592,0.4915226101875305,-0.0011626780033111572,568.2247924804688 -1769682040,411502336,0.5131500959396362,-0.0011919587850570679,568.2206420898438 -1769682040,462358272,0.5433793663978577,-0.0011799931526184082,568.21533203125 -1769682040,473967872,0.5664262771606445,-0.00118979811668396,568.211181640625 -1769682040,513156864,0.5899602770805359,-0.001141667366027832,568.2072143554688 -1769682040,546928384,0.6222689151763916,-0.0012237131595611572,568.2017822265625 -1769682040,578087424,0.6460424661636353,-0.0012307465076446533,568.19775390625 -1769682040,600729088,0.6616698503494263,-0.0012030601501464844,568.1951293945312 -1769682040,663548928,0.6994315385818481,-0.001234978437423706,568.1887817382812 -1769682040,671150848,0.720598578453064,-0.0012783408164978027,568.185302734375 -1769682040,700176128,0.7347152829170227,-0.0012572705745697021,568.1831665039062 -1769682040,757230848,0.7706850171089172,-0.0012704133987426758,568.1780395507812 -1769682040,768660224,0.7859275341033936,-0.0012997090816497803,568.176025390625 -1769682040,814699776,0.8171172142028809,-0.001349031925201416,568.1723022460938 -1769682040,869078272,0.8491211533546448,-0.0014038681983947754,568.1687622070312 -1769682040,873262336,0.8650867938995361,-0.001435995101928711,568.1671142578125 -1769682040,911824384,0.8971108794212341,-0.0014728903770446777,568.1640014648438 -1769682040,949116928,0.9291914701461792,-0.0015884637832641602,568.161376953125 -1769682040,978084608,0.9522980451583862,-0.0010297000408172607,568.1597290039062 -1769682041,13385216,0.9748398661613464,-0.000980287790298462,568.1588134765625 -1769682041,52774144,1.0042719841003418,-0.0011716187000274658,568.1583862304688 -1769682041,78231296,1.0255126953125,-0.0013151764869689941,568.1585693359375 -1769682041,112159232,1.0463204383850098,-0.0015009641647338867,568.1591796875 -1769682041,150008320,1.0749872922897339,-0.001716911792755127,568.1605834960938 -1769682041,170556672,1.0898969173431396,-0.0018076896667480469,568.1614990234375 -1769682041,199648000,1.1122981309890747,-0.0019145607948303223,568.1630859375 -1769682041,265998848,1.1515237092971802,-0.002238929271697998,568.1658935546875 -1769682041,278992896,1.1782214641571045,-0.002914130687713623,568.1661987304688 -1769682041,311483136,1.2046902179718018,-0.003213047981262207,568.1669921875 -1769682041,353374720,1.240330457687378,-0.003376483917236328,568.1686401367188 -1769682041,378348288,1.2670241594314575,-0.0034794211387634277,568.1702880859375 -1769682041,413697792,1.2936267852783203,-0.0035396814346313477,568.1722412109375 -1769682041,450527232,1.3296847343444824,-0.003555774688720703,568.1753540039062 -1769682041,478223616,1.3571369647979736,-0.0035824179649353027,568.1778564453125 -1769682041,511684352,1.3845794200897217,-0.0035862326622009277,568.1806030273438 -1769682041,551581696,1.4212216138839722,-0.003688216209411621,568.1846313476562 -1769682041,579405824,1.4487062692642212,-0.0037074685096740723,568.1878051757812 -1769682041,611560448,1.4764418601989746,-0.0038043856620788574,568.191162109375 -1769682041,657152768,1.5135058164596558,-0.0038946866989135742,568.19580078125 -1769682041,682241024,1.5409843921661377,-0.00392526388168335,568.1995239257812 -1769682041,697703424,1.5593030452728271,-0.003939986228942871,568.2019653320312 -1769682041,748988160,1.6062021255493164,-0.0041877031326293945,568.2103881835938 -1769682041,779028736,1.6342921257019043,-0.0038141608238220215,568.217529296875 -1769682041,813942784,1.662163496017456,-0.0033930540084838867,568.2257690429688 -1769682041,858355200,1.6992520093917847,-0.002874016761779785,568.23779296875 -1769682041,870343936,1.7179925441741943,-0.002626776695251465,568.244140625 -1769682041,911939584,1.755455493927002,-0.002307116985321045,568.257080078125 -1769682041,958129408,1.7926301956176758,-0.0019795894622802734,568.2703857421875 -1769682041,970277376,1.8110836744308472,-0.0017562508583068848,568.277099609375 -1769682042,13817856,1.8479464054107666,-0.0015311241149902344,568.2906494140625 -1769682042,95481856,1.8846153020858765,-0.0013523101806640625,568.3041381835938 -1769682042,97551616,1.9119657278060913,-0.001221001148223877,568.3141479492188 -1769682042,116605952,1.9391804933547974,-0.001114487648010254,568.3240356445312 -1769682042,145895936,1.9752777814865112,-0.0009805560111999512,568.3370971679688 -1769682042,165394944,1.9934489727020264,-0.000908970832824707,568.343505859375 -1769682042,211656192,2.0294389724731445,-0.0008262395858764648,568.35595703125 -1769682042,260762624,2.064894914627075,-0.000735163688659668,568.367919921875 -1769682042,269780480,2.0824875831604004,-0.0006489157676696777,568.3737182617188 -1769682042,315244544,2.1176998615264893,-0.0008147954940795898,568.385009765625 -1769682042,347353088,2.1535491943359375,-0.0018912553787231445,568.39306640625 -1769682042,379076864,2.171339273452759,-0.0025583505630493164,568.3956909179688 -1769682042,411797504,2.206681251525879,-0.0038840770721435547,568.3984985351562 -1769682042,449799680,2.2413272857666016,-0.005098462104797363,568.39892578125 -1769682042,466523648,2.2584991455078125,-0.0056067705154418945,568.3984375 -1769682042,516496384,2.292602777481079,-0.006503939628601074,568.3965454101562 -1769682042,556445440,2.32637619972229,-0.007175445556640625,568.3937377929688 -1769682042,578158592,2.3514597415924072,-0.00756072998046875,568.3911743164062 -1769682042,611541248,2.376433849334717,-0.007854580879211426,568.3883056640625 -1769682042,660338432,2.4093241691589355,-0.008067607879638672,568.3840942382812 -1769682042,672816640,2.432866096496582,-0.007409095764160156,568.3806762695312 -1769682042,700648448,2.4472761154174805,-0.005617737770080566,568.3777465820312 -1769682042,745887232,2.4825785160064697,0.0024118423461914062,568.3687133789062 -1769682042,781462272,2.5036370754241943,0.0074405670166015625,568.3624267578125 -1769682042,812183040,2.5244300365448,0.01211249828338623,568.3553466796875 -1769682042,847670016,2.5515079498291016,0.017657756805419922,568.3445434570312 -1769682042,878487808,2.5714962482452393,0.021200060844421387,568.3353271484375 -1769682042,917139456,2.5912203788757324,0.024257302284240723,568.3250122070312 -1769682042,966272000,2.617124080657959,0.027497172355651855,568.3096313476562 -1769682042,968481280,2.6299169063568115,0.028715968132019043,568.3012084960938 -1769682043,11511040,2.655245065689087,0.030772805213928223,568.2831420898438 -1769682043,67840768,2.681384801864624,0.03201770782470703,568.2633056640625 -1769682043,70118656,2.6943676471710205,0.03277850151062012,568.2528686523438 -1769682043,111958016,2.7202506065368652,0.034311532974243164,568.2311401367188 -1769682043,148183040,2.7463486194610596,0.03529226779937744,568.2086181640625 -1769682043,195165440,2.7657434940338135,0.03591787815093994,568.1913452148438 -1769682043,215124480,2.7850289344787598,0.036327362060546875,568.1736450195312 -1769682043,248748288,2.810544729232788,0.036850929260253906,568.1494750976562 -1769682043,278433792,2.8294389247894287,0.03711342811584473,568.130859375 -1769682043,313307136,2.846691846847534,0.03813636302947998,568.1110229492188 -1769682043,361468672,2.868544578552246,0.034267306327819824,568.0743408203125 -1769682043,372197120,2.8868932723999023,0.02955341339111328,568.039306640625 -1769682043,401984000,2.906811237335205,0.024353504180908203,567.9990844726562 -1769682043,445390336,2.9331274032592773,0.018687844276428223,567.94091796875 -1769682043,483368448,2.9528613090515137,0.015070319175720215,567.8953247070312 -1769682043,499819008,2.965916633605957,0.012682676315307617,567.8643188476562 -1769682043,551989248,2.9972639083862305,0.009011268615722656,567.7858276367188 -1769682043,564772864,3.00848388671875,0.007616996765136719,567.75439453125 -1769682043,611680512,3.029468297958374,0.006034731864929199,567.69189453125 -1769682043,657885696,3.0526559352874756,0.004914999008178711,567.6300048828125 -1769682043,675071744,3.0711963176727295,0.004257321357727051,567.5841064453125 -1769682043,712078848,3.086829900741577,0.007685542106628418,567.5426025390625 -1769682043,747796736,3.107546806335449,0.015810847282409668,567.5018310546875 -1769682043,768950784,3.11784291267395,0.019959449768066406,567.4865112304688 -1769682043,811926016,3.1379878520965576,0.02837967872619629,567.46337890625 -1769682043,849540608,3.1577584743499756,0.03563892841339111,567.4473266601562 -1769682043,879020288,3.1724205017089844,0.04027247428894043,567.4384765625 -1769682043,913063424,3.186965227127075,0.044182538986206055,567.4313354492188 -1769682043,949061632,3.206042766571045,0.04839324951171875,567.4234619140625 -1769682043,966035712,3.2153513431549072,0.050161004066467285,567.419921875 -1769682044,12407296,3.2339730262756348,0.053163886070251465,567.4127197265625 -1769682044,50103296,3.2522966861724854,0.055362582206726074,567.4046020507812 -1769682044,67810560,3.2613744735717773,0.05619454383850098,567.400146484375 -1769682044,102300160,3.279111623764038,0.05755198001861572,567.3895874023438 -1769682044,145571328,3.296623468399048,0.05846524238586426,567.3770751953125 -1769682044,180396544,3.3096354007720947,0.05890297889709473,567.3662719726562 -1769682044,212736256,3.321204900741577,0.060240864753723145,567.3544311523438 -1769682044,247711232,3.3331029415130615,0.05831122398376465,567.3389892578125 -1769682044,295187712,3.346223831176758,0.05327796936035156,567.325927734375 -1769682044,315016704,3.360208749771118,0.04832637310028076,567.3103637695312 -1769682044,370644992,3.378556966781616,0.042992472648620605,567.2869873046875 -1769682044,380610816,3.3920412063598633,0.03977036476135254,567.2678833007812 -1769682044,400387328,3.4010367393493652,0.03779792785644531,567.2545166015625 -1769682044,465364736,3.4233741760253906,0.03470015525817871,567.2191772460938 -1769682044,476030464,3.4366633892059326,0.033376216888427734,567.197021484375 -1769682044,512783616,3.450204372406006,0.032190918922424316,567.1739501953125 -1769682044,547010560,3.4681215286254883,0.03120732307434082,567.1428833007812 -1769682044,578514688,3.481471300125122,0.030863404273986816,567.119384765625 -1769682044,601770240,3.49027681350708,0.03051912784576416,567.1038208007812 -1769682044,651642112,3.511965274810791,0.030910253524780273,567.06494140625 -1769682044,680984320,3.5248661041259766,0.03119349479675293,567.0415649414062 -1769682044,712105728,3.5376298427581787,0.03158605098724365,567.0180053710938 -1769682044,757519872,3.5545053482055664,0.03217923641204834,566.9862670898438 -1769682044,770516736,3.5628750324249268,0.03226888179779053,566.9700927734375 -1769682044,811846144,3.5791854858398438,0.03335368633270264,566.937744140625 -1769682044,846281728,3.595226764678955,0.03429865837097168,566.9052734375 -1769682044,866573568,3.603182554244995,0.034646034240722656,566.8890380859375 -1769682044,911918080,3.6190192699432373,0.035561561584472656,566.8563232421875 -1769682044,951529984,3.6346333026885986,0.03628361225128174,566.8233032226562 -1769682044,980705024,3.646233320236206,0.03670632839202881,566.7982177734375 -1769682045,12041984,3.657719373703003,0.03707993030548096,566.7728271484375 -1769682045,50991360,3.6733124256134033,0.03698611259460449,566.7385864257812 -1769682045,79975680,3.6851449012756348,0.03544604778289795,566.71337890625 -1769682045,112021760,3.696821689605713,0.03339362144470215,566.6884155273438 -1769682045,164908032,3.7084431648254395,0.03129231929779053,566.6635131835938 -1769682045,176037888,3.7236363887786865,0.028737783432006836,566.6305541992188 -1769682045,212458752,3.7349205017089844,0.0270920991897583,566.6058959960938 -1769682045,261744640,3.7498161792755127,0.02533853054046631,566.572998046875 -1769682045,284670976,3.761073589324951,0.024005532264709473,566.5481567382812 -1769682045,300549632,3.7686429023742676,0.022936701774597168,566.53125 -1769682045,345761280,3.787191867828369,0.021947026252746582,566.4882202148438 -1769682045,378803200,3.798164129257202,0.021484851837158203,566.461669921875 -1769682045,417686016,3.8089916706085205,0.021206259727478027,566.4346313476562 -1769682045,457991680,3.8230628967285156,0.02108287811279297,566.3978881835938 -1769682045,480091648,3.833554267883301,0.022078275680541992,566.3700561523438 -1769682045,513604096,3.843986988067627,0.023878931999206543,566.3373413085938 -1769682045,557847040,3.8557395935058594,0.02397751808166504,566.2887573242188 -1769682045,570942976,3.861461877822876,0.024606943130493164,566.2672729492188 -1769682045,613651712,3.8726251125335693,0.027421951293945312,566.2293701171875 -1769682045,646283264,3.883631706237793,0.02976059913635254,566.1966552734375 -1769682045,682118400,3.891744613647461,0.03130507469177246,566.1742553710938 -1769682045,711978240,3.8997344970703125,0.03261971473693848,566.1530151367188 -1769682045,752786944,3.910036087036133,0.03405261039733887,566.125732421875 -1769682045,778814976,3.9179770946502686,0.03449201583862305,566.1055297851562 -1769682045,854370816,3.92648983001709,0.033423423767089844,566.0828247070312 -1769682045,869930496,3.937844753265381,0.03046107292175293,566.0473022460938 -1769682045,878065920,3.9461348056793213,0.02802753448486328,566.0177001953125 -1769682045,898816256,3.951589345932007,0.02613067626953125,565.9968872070312 -1769682045,945864192,3.964977979660034,0.023003578186035156,565.9420166015625 -1769682045,976008960,3.9702885150909424,0.021611452102661133,565.9191284179688 -1769682046,12620544,3.9807443618774414,0.019765377044677734,565.8724365234375 -1769682046,61007872,3.99104642868042,0.02033388614654541,565.8256225585938 -1769682046,68631808,3.996232509613037,0.020983099937438965,565.805419921875 -1769682046,113640192,4.0064263343811035,0.023018956184387207,565.7713012695312 -1769682046,149580800,4.016508102416992,0.024843573570251465,565.743408203125 -1769682046,179179264,4.023982048034668,0.02593207359313965,565.7258911132812 -1769682046,212154112,4.031404495239258,0.02689385414123535,565.7105102539062 -1769682046,258001920,4.037348747253418,0.027190566062927246,565.6937255859375 -1769682046,267260928,4.040812015533447,0.025765299797058105,565.68359375 -1769682046,314063104,4.047585964202881,0.025990009307861328,565.6588134765625 -1769682046,346455808,4.054066181182861,0.026410341262817383,565.6300048828125 -1769682046,380577024,4.058816432952881,0.026594877243041992,565.6063842773438 -1769682046,412298496,4.0636467933654785,0.026669979095458984,565.5813598632812 -1769682046,451208704,4.069852828979492,0.02662825584411621,565.5459594726562 -1769682046,479071744,4.074426651000977,0.026500463485717773,565.518310546875 -1769682046,515865088,4.078993797302246,0.026346206665039062,565.4900512695312 -1769682046,557315840,4.085013389587402,0.026101112365722656,565.4517822265625 -1769682046,578951936,4.089424133300781,0.025868535041809082,565.4229125976562 -1769682046,612138496,4.093221664428711,0.026149511337280273,565.3943481445312 -1769682046,660419840,4.097960472106934,0.026001930236816406,565.3558959960938 -1769682046,669570816,4.100430488586426,0.02552175521850586,565.336669921875 -1769682046,732354048,4.105408191680908,0.025967001914978027,565.2994384765625 -1769682046,745286144,4.109155654907227,0.026145219802856445,565.2724609375 -1769682046,783028224,4.114088535308838,0.0263596773147583,565.237548828125 -1769682046,814584832,4.117780685424805,0.026470661163330078,565.2122192382812 -1769682046,848018688,4.1229400634765625,0.026105761528015137,565.1791381835938 -1769682046,878808576,4.126623153686523,0.025595903396606445,565.154296875 -1769682046,914306816,4.130241870880127,0.02513587474822998,565.1292114257812 -1769682046,956212736,4.134918212890625,0.024702072143554688,565.0953979492188 -1769682046,980557824,4.138339042663574,0.024663686752319336,565.0689697265625 -1769682047,12516864,4.141712665557861,0.02467811107635498,565.0410766601562 -1769682047,63593728,4.146069526672363,0.024861812591552734,565.0014038085938 -1769682047,70677760,4.148210048675537,0.024527311325073242,564.98046875 -1769682047,112284160,4.1524457931518555,0.025234460830688477,564.9365234375 -1769682047,148902144,4.156565189361572,0.02543199062347412,564.8903198242188 -1769682047,180317696,4.159597873687744,0.02555394172668457,564.854736328125 -1769682047,213522688,4.1625847816467285,0.025530219078063965,564.8189086914062 -1769682047,246730496,4.166325092315674,0.025347590446472168,564.7713012695312 -1769682047,278658304,4.168543815612793,0.025312066078186035,564.737060546875 -1769682047,316735232,4.170607566833496,0.024740219116210938,564.7044067382812 -1769682047,355026944,4.173379421234131,0.023559927940368652,564.6630859375 -1769682047,378764800,4.175529956817627,0.023039817810058594,564.6336059570312 -1769682047,412215040,4.1776580810546875,0.022657275199890137,564.6051635742188 -1769682047,461144576,4.180296897888184,0.022256016731262207,564.5685424804688 -1769682047,468588544,4.181539058685303,0.02190089225769043,564.5506591796875 -1769682047,514174976,4.184012413024902,0.021915912628173828,564.5155029296875 -1769682047,547620352,4.1864848136901855,0.02167665958404541,564.4810180664062 -1769682047,580640000,4.188299179077148,0.021495580673217773,564.4556884765625 -1769682047,612830464,4.19020414352417,0.021311044692993164,564.4307861328125 -1769682047,650044928,4.192318916320801,0.021210312843322754,564.3986206054688 -1769682047,679170816,4.193150520324707,0.021851301193237305,564.3756103515625 -1769682047,715373568,4.194004058837891,0.02196979522705078,564.35302734375 -1769682047,753117952,4.195098876953125,0.021847963333129883,564.323486328125 -1769682047,779933696,4.1959099769592285,0.021718263626098633,564.3019409179688 -1769682047,812268544,4.19690465927124,0.021599769592285156,564.281005859375 -1769682047,853391616,4.198173522949219,0.021713972091674805,564.2545166015625 -1769682047,878942720,4.199093818664551,0.021889686584472656,564.2356567382812 -1769682047,913470208,4.200050354003906,0.02198314666748047,564.2172241210938 -1769682047,946193664,4.201620578765869,0.02165675163269043,564.1929321289062 -1769682047,982782976,4.202847480773926,0.021148204803466797,564.1744384765625 -1769682048,14572032,4.204078674316406,0.0205538272857666,564.1558837890625 -1769682048,50237952,4.205708026885986,0.01972055435180664,564.1315307617188 -1769682048,78789120,4.206752300262451,0.01916027069091797,564.11376953125 -1769682048,114801152,4.207761764526367,0.01862049102783203,564.0965576171875 -1769682048,157180672,4.20902681350708,0.018013715744018555,564.0745239257812 -1769682048,181497600,4.209922790527344,0.01761794090270996,564.05859375 -1769682048,212483072,4.210794925689697,0.017326831817626953,564.0430908203125 -1769682048,262789120,4.211825370788574,0.017038345336914062,564.02294921875 -1769682048,272144640,4.212526321411133,0.016884326934814453,564.0082397460938 -1769682048,312760320,4.2127685546875,0.01685643196105957,563.9939575195312 -1769682048,346990592,4.2119879722595215,0.01775527000427246,563.9765014648438 -1769682048,380958208,4.211404800415039,0.017842769622802734,563.9642333984375 -1769682048,413112320,4.210732460021973,0.017771244049072266,563.952392578125 -1769682048,446789376,4.209704399108887,0.017471790313720703,563.9374389648438 -1769682048,479081728,4.209051132202148,0.017323017120361328,563.9266357421875 -1769682048,514873856,4.208368301391602,0.017329931259155273,563.9161376953125 -1769682048,551580160,4.207359790802002,0.0174102783203125,563.9027099609375 -1769682048,579194368,4.2066121101379395,0.017459630966186523,563.892822265625 -1769682048,612219136,4.205761909484863,0.017543315887451172,563.8829956054688 -1769682048,665549056,4.204461097717285,0.0176241397857666,563.8701171875 -1769682048,674948352,4.2034993171691895,0.01765918731689453,563.8605346679688 -1769682048,713172736,4.202261447906494,0.017366647720336914,563.8506469726562 -1769682048,747332608,4.200480937957764,0.016733884811401367,563.8372192382812 -1769682048,779828224,4.199080467224121,0.016196012496948242,563.8270874023438 -1769682048,815375104,4.197627067565918,0.015674829483032227,563.8170776367188 -1769682048,857703424,4.195523738861084,0.015038728713989258,563.8041381835938 -1769682048,879006208,4.193978309631348,0.014568805694580078,563.7947387695312 -1769682048,918449664,4.192525863647461,0.014478206634521484,563.7861938476562 -1769682048,957292800,4.190433502197266,0.014816761016845703,563.7765502929688 -1769682048,966370304,4.189335346221924,0.014992952346801758,563.7722778320312 -1769682049,12512256,4.187084674835205,0.015546560287475586,563.7645263671875 -1769682049,57135872,4.18485164642334,0.01592540740966797,563.7572631835938 -1769682049,70739456,4.183720111846924,0.015976428985595703,563.7537231445312 -1769682049,112535808,4.181390285491943,0.016228914260864258,563.7464599609375 -1769682049,148153088,4.179024696350098,0.016368865966796875,563.7391357421875 -1769682049,183330560,4.1772379875183105,0.016422510147094727,563.7335815429688 -1769682049,213285376,4.175423622131348,0.01645207405090332,563.7279663085938 -1769682049,248441344,4.173005104064941,0.016460418701171875,563.7205810546875 -1769682049,278966528,4.171380043029785,0.016465067863464355,563.7149047851562 -1769682049,315721472,4.169729709625244,0.01647162437438965,563.7091674804688 -1769682049,354636032,4.16762638092041,0.016436219215393066,563.7013549804688 -1769682049,366982144,4.166538715362549,0.01619899272918701,563.6973266601562 -1769682049,412634880,4.164391040802002,0.015594840049743652,563.6885986328125 -1769682049,467223040,4.162379264831543,0.014871478080749512,563.6793823242188 -1769682049,477637120,4.160983085632324,0.014238357543945312,563.6724243164062 -1769682049,513163520,4.159653186798096,0.013615608215332031,563.6653442382812 -1769682049,547455488,4.158037185668945,0.012789249420166016,563.6559448242188 -1769682049,582628608,4.1570658683776855,0.012456655502319336,563.6486206054688 -1769682049,612826624,4.156185626983643,0.012521624565124512,563.6412353515625 -1769682049,650750720,4.1551361083984375,0.01272284984588623,563.6312255859375 -1769682049,665786880,4.154613971710205,0.012830972671508789,563.6261596679688 -1769682049,716996608,4.153698921203613,0.01325845718383789,563.6160278320312 -1769682049,758616320,4.152861595153809,0.01373910903930664,563.6058349609375 -1769682049,770572032,4.152435302734375,0.013906598091125488,563.6006469726562 -1769682049,812935168,4.1518378257751465,0.014425039291381836,563.5902099609375 -1769682049,858780672,4.1513190269470215,0.01477968692779541,563.5795288085938 -1769682049,869361664,4.15109395980835,0.01485741138458252,563.5741577148438 -1769682049,913240832,4.150834560394287,0.015190958976745605,563.5631713867188 -1769682049,948748800,4.150712490081787,0.015375375747680664,563.5520629882812 -1769682049,981979904,4.15069055557251,0.015471100807189941,563.5435791015625 -1769682050,13075200,4.150779724121094,0.015617609024047852,563.5352172851562 -1769682050,47935488,4.150992393493652,0.01577615737915039,563.5241088867188 -1769682050,80387328,4.151206016540527,0.015880227088928223,563.5156860351562 -1769682050,117346304,4.15147066116333,0.015935063362121582,563.5071411132812 -1769682050,151248128,4.152073860168457,0.015792012214660645,563.4954223632812 -1769682050,167585792,4.15242862701416,0.0156552791595459,563.4892578125 -1769682050,212498944,4.153222560882568,0.015407443046569824,563.4765625 -1769682050,261270528,4.154099464416504,0.015123844146728516,563.4635009765625 -1769682050,282713344,4.15478515625,0.014914274215698242,563.4534912109375 -1769682050,298893056,4.15524959564209,0.014702796936035156,563.44677734375 -1769682050,346640896,4.1564202308654785,0.014592409133911133,563.4298095703125 -1769682050,385464064,4.157111644744873,0.014584541320800781,563.4195556640625 -1769682050,412561408,4.157834053039551,0.014628410339355469,563.409423828125 -1769682050,449086464,4.158836841583252,0.01469874382019043,563.3958129882812 -1769682050,479600128,4.159584045410156,0.014835119247436523,563.3855590820312 -1769682050,513479424,4.160299777984619,0.014932632446289062,563.375244140625 -1769682050,565041664,4.161308288574219,0.015012860298156738,563.3615112304688 -1769682050,574185984,4.16207218170166,0.01502680778503418,563.35107421875 -1769682050,600536320,4.16259241104126,0.014889836311340332,563.3441162109375 -1769682050,655124224,4.1639299392700195,0.015088558197021484,563.3263549804688 -1769682050,664968704,4.164468765258789,0.015084505081176758,563.3192138671875 -1769682050,703808512,4.165510177612305,0.015182971954345703,563.3046875 -1769682050,746115840,4.16650915145874,0.015073776245117188,563.2900390625 -1769682050,813399552,4.167248725891113,0.015023231506347656,563.27880859375 -1769682050,815405312,4.167989730834961,0.014940738677978516,563.267578125 -1769682050,856118016,4.168946743011475,0.014818906784057617,563.25244140625 -1769682050,867082752,4.169411659240723,0.01467442512512207,563.244873046875 -1769682050,912577280,4.170374870300293,0.014640331268310547,563.2297973632812 -1769682050,960900608,4.171321392059326,0.014576911926269531,563.2147827148438 -1769682050,971985408,4.171795845031738,0.014383316040039062,563.207275390625 -1769682051,13146368,4.172763347625732,0.01448202133178711,563.1923828125 -1769682051,49617664,4.173783779144287,0.014446258544921875,563.1775512695312 -1769682051,82192128,4.174562454223633,0.01460886001586914,563.1665649414062 -1769682051,113383936,4.175354480743408,0.014806270599365234,563.1558837890625 -1769682051,149676544,4.1763997077941895,0.015088081359863281,563.1415405273438 -1769682051,179318784,4.177175521850586,0.015308618545532227,563.1306762695312 -1769682051,218904064,4.177992820739746,0.015498876571655273,563.11962890625 -1769682051,258593536,4.1790690422058105,0.015660524368286133,563.1043090820312 -1769682051,271832832,4.179605007171631,0.015588998794555664,563.096435546875 -1769682051,313824000,4.180692672729492,0.01584482192993164,563.080322265625 -1769682051,366234624,4.181752681732178,0.01587367057800293,563.063720703125 -1769682051,375255552,4.182466506958008,0.015907764434814453,563.0509643554688 -1769682051,412683008,4.183189392089844,0.0157926082611084,563.0381469726562 -1769682051,446617088,4.184149265289307,0.015573263168334961,563.0208740234375 -1769682051,482458624,4.184597015380859,0.015416622161865234,563.01220703125 -1769682051,514071040,4.185489654541016,0.015306711196899414,562.994873046875 -1769682051,548770048,4.18634033203125,0.015180349349975586,562.9773559570312 -1769682051,579417856,4.186956405639648,0.015113115310668945,562.964111328125 -1769682051,613974528,4.18763542175293,0.01496267318725586,562.9507446289062 -1769682051,655878656,4.188584327697754,0.014614582061767578,562.932861328125 -1769682051,667120384,4.18869686126709,0.014642000198364258,562.9239501953125 -1769682051,713379584,4.188459396362305,0.015819311141967773,562.9066772460938 -1769682051,764219648,4.188289642333984,0.016541481018066406,562.8892822265625 -1769682051,774435328,4.188170433044434,0.016990184783935547,562.8763427734375 -1769682051,813387264,4.188140869140625,0.017351627349853516,562.86328125 -1769682051,846701056,4.188111305236816,0.0177304744720459,562.845947265625 -1769682051,896316160,4.188131809234619,0.017952442169189453,562.8330688476562 -1769682051,904815104,4.188231468200684,0.01814889907836914,562.8201904296875 -1769682051,949968384,4.188362121582031,0.01833629608154297,562.8030395507812 -1769682051,980195072,4.188355445861816,0.01842784881591797,562.7901611328125 -1769682052,17475584,4.188534736633301,0.018584012985229492,562.7769775390625 -1769682052,57369088,4.188856601715088,0.018726825714111328,562.7589111328125 -1769682052,68577792,4.189055442810059,0.018685579299926758,562.7496337890625 -1769682052,113992960,4.189376354217529,0.018932104110717773,562.7305908203125 -1769682052,167117824,4.189579963684082,0.01871180534362793,562.71533203125 -1769682052,176087552,4.1900715827941895,0.018419742584228516,562.69384765625 -1769682052,213473024,4.190450191497803,0.018166542053222656,562.6771240234375 -1769682052,246986240,4.191046714782715,0.017746925354003906,562.6542358398438 -1769682052,267534848,4.191413402557373,0.01740264892578125,562.6426391601562 -1769682052,313297152,4.192339897155762,0.0168914794921875,562.6189575195312 -1769682052,356490240,4.192314147949219,0.017270565032958984,562.5955810546875 -1769682052,379903488,4.191965579986572,0.01786327362060547,562.5791015625 -1769682052,413816064,4.191655158996582,0.018204927444458008,562.5629272460938 -1769682052,450856960,4.191390037536621,0.01855921745300293,562.5419311523438 -1769682052,479402752,4.191270351409912,0.01876211166381836,562.5263671875 -1769682052,512912384,4.19123649597168,0.01893019676208496,562.5108032226562 -1769682052,543763456,4.191231727600098,0.019197463989257812,562.4951782226562 -1769682052,581809664,4.191267013549805,0.019458532333374023,562.4732055664062 -1769682052,613082112,4.1913323402404785,0.01953744888305664,562.4559326171875 -1769682052,647926784,4.191321849822998,0.019685745239257812,562.4320678710938 -1769682052,681369088,4.191032409667969,0.02028679847717285,562.4136962890625 -1769682052,707258112,4.19072151184082,0.02081298828125,562.3948364257812 -1769682052,746780416,4.190391540527344,0.0213470458984375,562.3692016601562 -1769682052,779888128,4.190052509307861,0.021711349487304688,562.3497314453125 -1769682052,816970240,4.189701080322266,0.02176356315612793,562.3304443359375 -1769682052,863544320,4.189236164093018,0.021643638610839844,562.3050537109375 -1769682052,870492160,4.188998699188232,0.02132248878479004,562.29248046875 -1769682052,912952576,4.188547134399414,0.021346330642700195,562.2677001953125 -1769682052,962562560,4.188141822814941,0.021132230758666992,562.2433471679688 -1769682052,969624832,4.187953472137451,0.020817279815673828,562.2313232421875 -1769682053,12921856,4.187603950500488,0.020841598510742188,562.2071533203125 -1769682053,47228928,4.187267303466797,0.020681142807006836,562.1831665039062 -1769682053,84679168,4.187021255493164,0.020591020584106445,562.1652221679688 -1769682053,113415168,4.186787128448486,0.020448684692382812,562.1474609375 -1769682053,152318720,4.186506271362305,0.020376205444335938,562.1241455078125 -1769682053,179801088,4.186172962188721,0.020419836044311523,562.1072387695312 -1769682053,215281408,4.1858625411987305,0.02004694938659668,562.0906982421875 -1769682053,254822144,4.185458660125732,0.019495725631713867,562.069091796875 -1769682053,280374784,4.1851606369018555,0.019094228744506836,562.053466796875 -1769682053,313722624,4.184797286987305,0.018759489059448242,562.038330078125 -1769682053,367775232,4.184133529663086,0.018945932388305664,562.0242309570312 -1769682053,375652096,4.183226585388184,0.019479990005493164,562.0067138671875 -1769682053,398673920,4.182774066925049,0.019611835479736328,561.9984130859375 -1769682053,446735872,4.181668758392334,0.020303010940551758,561.9780883789062 -1769682053,470117376,4.181244373321533,0.02037811279296875,561.9701538085938 -1769682053,513214208,4.180416584014893,0.02077794075012207,561.954345703125 -1769682053,548423936,4.179623603820801,0.020945072174072266,561.9389038085938 -1769682053,579841024,4.179043292999268,0.02098679542541504,561.9278564453125 -1769682053,613508864,4.178481578826904,0.02096247673034668,561.917236328125 -1769682053,656248576,4.177671432495117,0.020970821380615234,561.904052734375 -1769682053,681604608,4.177046775817871,0.020906448364257812,561.8948364257812 -1769682053,746566656,4.176432132720947,0.020708084106445312,561.8862915039062 -1769682053,757186048,4.175629615783691,0.020441293716430664,561.8759155273438 -1769682053,790216960,4.17507266998291,0.020168066024780273,561.8688354492188 -1769682053,802708992,4.174530982971191,0.019892454147338867,561.8622436523438 -1769682053,854195712,4.173650741577148,0.019692659378051758,561.854248046875 -1769682053,870630400,4.173181533813477,0.01936650276184082,561.8505859375 -1769682053,913496832,4.172264575958252,0.018922090530395508,561.8434448242188 -1769682053,957946624,4.171338081359863,0.01841425895690918,561.8363647460938 -1769682053,980729344,4.1706342697143555,0.01807570457458496,561.8312377929688 -1769682054,13307392,4.16990852355957,0.017746925354003906,561.8262329101562 -1769682054,65911296,4.169192790985107,0.017419099807739258,561.821533203125 -1769682054,77360896,4.168177604675293,0.017003774642944336,561.8157958984375 -1769682054,98236672,4.16767692565918,0.016727924346923828,561.8134155273438 -1769682054,148131840,4.166458606719971,0.016228437423706055,561.8092041015625 -1769682054,172758272,4.16598653793335,0.016015291213989258,561.808349609375 -1769682054,213833216,4.164936065673828,0.01566171646118164,561.807861328125 -1769682054,247373824,4.163911819458008,0.01543569564819336,561.8088989257812 -1769682054,279609344,4.163131237030029,0.015288352966308594,561.8106079101562 -1769682054,301277696,4.162541389465332,0.015280008316040039,561.8121337890625 -1769682054,354496000,4.1609787940979,0.015273094177246094,561.8172607421875 -1769682054,382098176,4.160072326660156,0.015168905258178711,561.8209838867188 -1769682054,413325568,4.159130573272705,0.015027284622192383,561.8251342773438 -1769682054,473005312,4.157844543457031,0.014801740646362305,561.8312377929688 -1769682054,476545792,4.156888961791992,0.014641046524047852,561.8363037109375 -1769682054,512791552,4.155839920043945,0.014481782913208008,561.8416748046875 -1769682054,547693312,4.154429912567139,0.014247655868530273,561.8495483398438 -1769682054,577133056,4.1533684730529785,0.013967037200927734,561.8560180664062 -1769682054,614980096,4.152307510375977,0.013628005981445312,561.8632202148438 -1769682054,651858688,4.151018142700195,0.013065576553344727,561.8741455078125 -1769682054,696475136,4.150005340576172,0.012659549713134766,561.8836669921875 -1769682054,717174016,4.148970603942871,0.012359380722045898,561.8944702148438 -1769682054,755551232,4.147538661956787,0.011941194534301758,561.9107666015625 -1769682054,768438272,4.146852970123291,0.01182866096496582,561.9196166992188 -1769682054,812902400,4.145491600036621,0.011077165603637695,561.9385375976562 -1769682054,860368896,4.144148349761963,0.010504722595214844,561.958740234375 -1769682054,881249024,4.143162727355957,0.010173797607421875,561.9743041992188 -1769682054,914954496,4.142194747924805,0.00995635986328125,561.9900512695312 -1769682054,947552256,4.140897750854492,0.009759902954101562,562.010986328125 -1769682054,980881920,4.1399455070495605,0.009663820266723633,562.0266723632812 -1769682055,13556992,4.139039516448975,0.009574174880981445,562.0423583984375 -1769682055,66318080,4.137889385223389,0.009326934814453125,562.0635375976562 -1769682055,74805504,4.137066841125488,0.00902104377746582,562.0801391601562 -1769682055,115724288,4.13626766204834,0.008708000183105469,562.0977172851562 -1769682055,155936512,4.135237216949463,0.008201122283935547,562.1231689453125 -1769682055,167533312,4.1347336769104,0.008147716522216797,562.1367797851562 -1769682055,212900096,4.133748531341553,0.0075037479400634766,562.1660766601562 -1769682055,264670208,4.132837295532227,0.007154226303100586,562.1973876953125 -1769682055,274976768,4.132336616516113,0.007002353668212891,562.2220458984375 -1769682055,315524096,4.131967544555664,0.007044434547424316,562.247314453125 -1769682055,349193984,4.1315412521362305,0.007302403450012207,562.281494140625 -1769682055,385501440,4.131252288818359,0.007490992546081543,562.3072509765625 -1769682055,413230592,4.130997180938721,0.007667183876037598,562.3331298828125 -1769682055,457533952,4.130800724029541,0.0076596736907958984,562.3675537109375 -1769682055,479934720,4.1307291984558105,0.0074073076248168945,562.3931274414062 -1769682055,515001088,4.130681037902832,0.007068037986755371,562.4188232421875 -1769682055,554034176,4.130651950836182,0.006532073020935059,562.4537963867188 -1769682055,579654912,4.130748271942139,0.006037473678588867,562.4810180664062 -1769682055,613309440,4.131231307983398,0.005080103874206543,562.5089721679688 -1769682055,664353024,4.132042407989502,0.004150271415710449,562.5484008789062 -1769682055,674896128,4.1326727867126465,0.003638744354248047,562.579833984375 -1769682055,714321152,4.133341312408447,0.003205418586730957,562.61279296875 -1769682055,749692928,4.134259223937988,0.002779364585876465,562.6587524414062 -1769682055,779669760,4.134964942932129,0.002512812614440918,562.694580078125 -1769682055,802892544,4.135447025299072,0.0028362274169921875,562.7188720703125 -1769682055,848489984,4.13677978515625,0.001838088035583496,562.7809448242188 -1769682055,880450048,4.137588024139404,0.0015027523040771484,562.8189697265625 -1769682055,913732608,4.138416290283203,0.001179337501525879,562.8572387695312 -1769682055,964580864,4.139636039733887,0.0007370710372924805,562.9088134765625 -1769682055,972111616,4.140576362609863,0.0005621910095214844,562.9481201171875 -1769682056,14317824,4.1415181159973145,0.00042879581451416016,562.9879760742188 -1769682056,46597632,4.1427531242370605,0.0002409219741821289,563.042236328125 -1769682056,67171328,4.143361568450928,0.0003682374954223633,563.0700073242188 -1769682056,113809920,4.144571781158447,-8.26120376586914e-05,563.126708984375 -1769682056,154315264,4.1457438468933105,-0.00026679039001464844,563.1849365234375 -1769682056,179687936,4.14660120010376,-0.00037682056427001953,563.2294921875 -1769682056,200707072,4.147165298461914,-2.7298927307128906e-05,563.259521484375 -1769682056,250380800,4.148653984069824,-0.0005561113357543945,563.3356323242188 -1769682056,279937792,4.150027275085449,-0.0009884834289550781,563.38134765625 -1769682056,313201664,4.151525497436523,-0.0012011528015136719,563.4270629882812 -1769682056,358365952,4.153567314147949,-0.0011914968490600586,563.488525390625 -1769682056,372567040,4.154560565948486,-0.0006167888641357422,563.5194702148438 -1769682056,414071808,4.156496524810791,-0.001040339469909668,563.5823974609375 -1769682056,452221440,4.158383846282959,-0.0010044574737548828,563.6466674804688 -1769682056,473571072,4.159811019897461,-0.001091599464416504,563.6958618164062 -1769682056,514221568,4.161227226257324,-0.00133514404296875,563.745849609375 -1769682056,546858752,4.163002014160156,-0.0017812252044677734,563.8136596679688 -1769682056,581662720,4.164300441741943,-0.002150297164916992,563.865234375 -1769682056,599966976,4.16518497467041,-0.0017762184143066406,563.89990234375 -1769682056,648674048,4.167646408081055,-0.0030400753021240234,563.9876098632812 -1769682056,679799808,4.169057846069336,-0.0032674074172973633,564.0406494140625 -1769682056,715134464,4.170395851135254,-0.003458738327026367,564.0940551757812 -1769682056,758697472,4.1717071533203125,-0.0034922361373901367,564.1474609375 -1769682056,773699584,4.173270225524902,-0.003676772117614746,564.2188110351562 -1769682056,814786816,4.174384593963623,-0.00375211238861084,564.2723388671875 -1769682056,848944384,4.175787925720215,-0.0038421154022216797,564.3438720703125 -1769682056,869116672,4.176473140716553,-0.0035408735275268555,564.3797607421875 -1769682056,914283264,4.1777472496032715,-0.004140615463256836,564.451904296875 -1769682056,949842432,4.178915023803711,-0.004355907440185547,564.5245971679688 -1769682056,979694848,4.179811477661133,-0.004558563232421875,564.5795288085938 -1769682057,1165056,4.18040657043457,-0.003996729850769043,564.6162719726562 -1769682057,49928448,4.181728363037109,-0.004617094993591309,564.708984375 -1769682057,82654720,4.18246603012085,-0.00461578369140625,564.7650146484375 -1769682057,113686272,4.18310546875,-0.004612565040588379,564.8214111328125 -1769682057,156605696,4.183743953704834,-0.004439115524291992,564.8780517578125 -1769682057,173906944,4.18451452255249,-0.00440216064453125,564.9537353515625 -1769682057,213960960,4.185051918029785,-0.004263520240783691,565.0104370117188 -1769682057,248739072,4.185696601867676,-0.004122138023376465,565.0857543945312 -1769682057,269765376,4.186061859130859,-0.0034852027893066406,565.1231079101562 -1769682057,313939712,4.1871562004089355,-0.003938198089599609,565.1970825195312 -1769682057,344190464,4.187981128692627,-0.003662705421447754,565.251953125 -1769682057,379965952,4.1890363693237305,-0.0034188032150268555,565.3243408203125 -1769682057,399985408,4.1895318031311035,-0.0027004480361938477,565.3602294921875 -1769682057,449126656,4.190718650817871,-0.00287473201751709,565.4490356445312 -1769682057,479861504,4.191400527954102,-0.0027276277542114258,565.5018920898438 -1769682057,513154048,4.192052841186523,-0.0026150941848754883,565.5546875 -1769682057,551585024,4.192923069000244,-0.0026415586471557617,565.625 -1769682057,580937728,4.193653583526611,-0.002751946449279785,565.6777954101562 -1769682057,613256192,4.194465637207031,-0.002876877784729004,565.7306518554688 -1769682057,659779072,4.195511817932129,-0.0029932260513305664,565.8013916015625 -1769682057,668171520,4.196019172668457,-0.002568840980529785,565.8367919921875 -1769682057,715226624,4.196986675262451,-0.002979278564453125,565.9073486328125 -1769682057,749886976,4.197903633117676,-0.002787947654724121,565.97705078125 -1769682057,782616320,4.198573112487793,-0.002594590187072754,566.028564453125 -1769682057,813457920,4.199201583862305,-0.0024088621139526367,566.0790405273438 -1769682057,852817408,4.199928283691406,-0.0019685029983520508,566.1450805664062 -1769682057,879958016,4.200441360473633,-0.0016756057739257812,566.1937255859375 -1769682057,916292096,4.20092248916626,-0.0014309883117675781,566.2418212890625 -1769682057,954301440,4.201496124267578,-0.001283407211303711,566.3056640625 -1769682057,967324160,4.201781272888184,-0.0009976625442504883,566.3378295898438 -1769682058,14029824,4.202343940734863,-0.0013282299041748047,566.4028930664062 -1769682058,62226432,4.202853202819824,-0.0012935400009155273,566.4693603515625 -1769682058,69837056,4.203096389770508,-0.0006999969482421875,566.5028686523438 -1769682058,113513472,4.203560829162598,-0.0010524988174438477,566.5701904296875 -1769682058,148193024,4.203979969024658,-0.0007914304733276367,566.6371459960938 -1769682058,180116224,4.204273700714111,-0.000504612922668457,566.6866455078125 -1769682058,214280960,4.204503059387207,-0.00014388561248779297,566.7351684570312 -1769682058,248427520,4.204927444458008,9.250640869140625e-05,566.7977294921875 -1769682058,280199424,4.20536470413208,0.0002645254135131836,566.8428955078125 -1769682058,314978304,4.205765247344971,0.0004137754440307617,566.8868408203125 -1769682058,354050048,4.206273078918457,0.0005890130996704102,566.9435424804688 -1769682058,381347840,4.206638336181641,0.0006119012832641602,566.9849243164062 -1769682058,413302784,4.206976890563965,0.0006396770477294922,567.0258178710938 -1769682058,460816640,4.207563877105713,0.00037789344787597656,567.0805053710938 -1769682058,469719040,4.207903861999512,0.0007015466690063477,567.1082763671875 -1769682058,513359360,4.208507537841797,1.3232231140136719e-05,567.1655883789062 -1769682058,552913152,4.209056854248047,-4.887580871582031e-06,567.2251586914062 -1769682058,584314880,4.209444999694824,6.520748138427734e-05,567.2708740234375 -1769682058,613788160,4.209793567657471,0.00010991096496582031,567.3171997070312 -1769682058,651547136,4.210165023803711,0.00013780593872070312,567.3795776367188 -1769682058,679862784,4.210339069366455,0.00029730796813964844,567.4267578125 -1769682058,718589952,4.210482120513916,0.0006514787673950195,567.4741821289062 -1769682058,757982976,4.210622787475586,0.0012350082397460938,567.53759765625 -1769682058,781096704,4.210718154907227,0.0017032623291015625,567.5847778320312 -1769682058,814370304,4.210782527923584,0.002251744270324707,567.6312866210938 -1769682058,856766720,4.210797309875488,0.0027489662170410156,567.6768188476562 -1769682058,873972992,4.210745811462402,0.0033911466598510742,567.7359008789062 -1769682058,913719808,4.21064567565918,0.003691434860229492,567.7789306640625 -1769682058,948434432,4.2104058265686035,0.004110574722290039,567.83447265625 -1769682058,980267008,4.210208892822266,0.004469037055969238,567.8746337890625 -1769682059,1182208,4.210064888000488,0.005096316337585449,567.9006958007812 -1769682059,47191296,4.2094268798828125,0.005057692527770996,567.962646484375 -1769682059,80137472,4.208998680114746,0.005090117454528809,567.9974975585938 -1769682059,113349120,4.208715438842773,0.005139470100402832,568.0308227539062 -1769682059,153651200,4.208502769470215,0.005257606506347656,568.0731201171875 -1769682059,181076992,4.2083234786987305,0.005250811576843262,568.1033935546875 -1769682059,213810432,4.208101749420166,0.005251765251159668,568.1327514648438 -1769682059,248177408,4.207828998565674,0.005377531051635742,568.1705322265625 -1769682059,269803264,4.207777976989746,0.005721926689147949,568.1890258789062 -1769682059,313592320,4.207664489746094,0.005702614784240723,568.2247924804688 -1769682059,347969024,4.207369327545166,0.0062558650970458984,568.2596435546875 -1769682059,381296896,4.207152366638184,0.006799459457397461,568.2853393554688 -1769682059,399421184,4.206992149353027,0.007396817207336426,568.3023071289062 -1769682059,450341632,4.2065324783325195,0.008048653602600098,568.3436279296875 -1769682059,480048384,4.206157207489014,0.008765339851379395,568.36767578125 -1769682059,513385984,4.205756664276123,0.00953972339630127,568.3911743164062 -1769682059,561232384,4.20522928237915,0.010531306266784668,568.4213256835938 -1769682059,572342272,4.2049713134765625,0.011277556419372559,568.4359130859375 -1769682059,599644928,4.204568862915039,0.011881709098815918,568.4569091796875 -1769682059,660341760,4.203891754150391,0.012647867202758789,568.4898071289062 -1769682059,667473920,4.203570365905762,0.013164520263671875,568.502197265625 -1769682059,713912576,4.202822208404541,0.013479351997375488,568.5255737304688 -1769682059,748224000,4.202054023742676,0.013638496398925781,568.5471801757812 -1769682059,783379200,4.201481342315674,0.013662576675415039,568.562255859375 -1769682059,813771264,4.200859546661377,0.013745427131652832,568.5765380859375 -1769682059,848695808,4.1999430656433105,0.013553977012634277,568.5939331054688 -1769682059,880334336,4.19926643371582,0.013282418251037598,568.605712890625 -1769682059,917319168,4.198610305786133,0.01302647590637207,568.6166381835938 -1769682059,950429184,4.198025703430176,0.012764811515808105,568.6301879882812 -1769682059,981544448,4.197602272033691,0.012653946876525879,568.6396484375 -1769682060,14040832,4.197175979614258,0.012509822845458984,568.6485595703125 -1769682060,64281088,4.196596622467041,0.012405753135681152,568.6596069335938 -1769682060,72653568,4.196215629577637,0.012417793273925781,568.6674194335938 -1769682060,114437632,4.195827007293701,0.01245129108428955,568.6747436523438 -1769682060,147695872,4.195148468017578,0.012819647789001465,568.6841430664062 -1769682060,186797056,4.194638252258301,0.013246417045593262,568.691162109375 -1769682060,214180864,4.194119930267334,0.013713836669921875,568.697998046875 -1769682060,249932032,4.1934099197387695,0.014309525489807129,568.706787109375 -1769682060,280314112,4.1928300857543945,0.014875650405883789,568.713134765625 -1769682060,319189248,4.192249774932861,0.015432953834533691,568.7190551757812 -1769682060,347176704,4.191666126251221,0.016012072563171387,568.7246704101562 -1769682060,380893952,4.19087553024292,0.01668417453765869,568.7315063476562 -1769682060,413378816,4.19028377532959,0.017139673233032227,568.7361450195312 -1769682060,464007936,4.189517498016357,0.017650485038757324,568.7415161132812 -1769682060,472012288,4.188866138458252,0.018063902854919434,568.744873046875 -1769682060,514445568,4.188173770904541,0.018196940422058105,568.74755859375 -1769682060,547838464,4.187272548675537,0.01819002628326416,568.7501831054688 -1769682060,586208000,4.186614990234375,0.018154621124267578,568.7515258789062 -1769682060,614739968,4.185913562774658,0.01809549331665039,568.7522583007812 -1769682060,651792896,4.1849684715271,0.017760872840881348,568.7523193359375 -1769682060,680190976,4.184286117553711,0.017442941665649414,568.7518920898438 -1769682060,716379904,4.183622360229492,0.017134785652160645,568.7510986328125 -1769682060,761746944,4.182849407196045,0.016791820526123047,568.7498779296875 -1769682060,767018496,4.182487487792969,0.01661670207977295,568.7492065429688 -1769682060,814868736,4.181773662567139,0.016389966011047363,568.747802734375 -1769682060,858628864,4.181092739105225,0.016232848167419434,568.7461547851562 -1769682060,867433216,4.180763244628906,0.016170263290405273,568.7453002929688 -1769682060,916541696,4.179967880249023,0.01613438129425049,568.7432250976562 -1769682060,949941248,4.179082870483398,0.016359806060791016,568.7407836914062 -1769682060,979578368,4.178654670715332,0.016544699668884277,568.7394409179688 -1769682061,13642240,4.177828788757324,0.016983509063720703,568.7367553710938 -1769682061,51209216,4.177051067352295,0.01743948459625244,568.7337646484375 -1769682061,80934912,4.17645788192749,0.017773866653442383,568.7313232421875 -1769682061,115453696,4.175912380218506,0.01811063289642334,568.7286987304688 -1769682061,156457728,4.175219535827637,0.01847219467163086,568.7250366210938 -1769682061,180419584,4.174743175506592,0.018735527992248535,568.7221069335938 -1769682061,214588416,4.174288272857666,0.018935799598693848,568.7190551757812 -1769682061,262387456,4.173717975616455,0.0191420316696167,568.7147216796875 -1769682061,270138624,4.1734161376953125,0.01920294761657715,568.7125244140625 -1769682061,313791232,4.17280387878418,0.01928400993347168,568.7078857421875 -1769682061,348814336,4.1722564697265625,0.01916372776031494,568.7030639648438 -1769682061,383746560,4.171880722045898,0.019031643867492676,568.6994018554688 -1769682061,414536448,4.171517372131348,0.01886296272277832,568.6956176757812 -1769682061,447649792,4.171041011810303,0.018625974655151367,568.6904296875 -1769682061,480537856,4.1707024574279785,0.018431782722473145,568.6864013671875 -1769682061,515348992,4.170391082763672,0.018262267112731934,568.682373046875 -1769682061,555273728,4.169923305511475,0.01806652545928955,568.6768798828125 -1769682061,581720832,4.169499397277832,0.017877578735351562,568.6727294921875 -1769682061,613607424,4.169107913970947,0.017802953720092773,568.6685180664062 -1769682061,665144320,4.168590068817139,0.017802119255065918,568.6627807617188 -1769682061,672868608,4.16820764541626,0.017858505249023438,568.658203125 -1769682061,717009408,4.167524814605713,0.017828822135925293,568.6533813476562 -1769682061,764410880,4.166530132293701,0.017900943756103516,568.6463623046875 -1769682061,784433664,4.165811538696289,0.018085241317749023,568.6406860351562 -1769682061,802458368,4.1651225090026855,0.018287062644958496,568.6348266601562 -1769682061,848143872,4.164240837097168,0.018526196479797363,568.62646484375 -1769682061,880794624,4.163623332977295,0.01865208148956299,568.6201171875 -1769682061,915338752,4.163033485412598,0.018715500831604004,568.613525390625 -1769682061,950948352,4.16231107711792,0.01875889301300049,568.604736328125 -1769682061,980390400,4.161780834197998,0.018799543380737305,568.5979614257812 -1769682062,14970368,4.161313533782959,0.018811345100402832,568.5911865234375 -1769682062,47149824,4.160863399505615,0.018778085708618164,568.5844116210938 -1769682062,82233600,4.160271167755127,0.018831372261047363,568.5753784179688 -1769682062,113977344,4.159863471984863,0.018748998641967773,568.5687255859375 -1769682062,147067904,4.159337997436523,0.01858961582183838,568.56005859375 -1769682062,169875200,4.15908670425415,0.018470048904418945,568.5558471679688 -1769682062,213924864,4.158655643463135,0.018407583236694336,568.5476684570312 -1769682062,260404224,4.1582932472229,0.018283843994140625,568.539794921875 -1769682062,269936640,4.158161163330078,0.018204450607299805,568.5360107421875 -1769682062,305787904,4.157916069030762,0.018263578414916992,568.5285034179688 -1769682062,349896448,4.157738208770752,0.018300890922546387,568.52099609375 -1769682062,380531200,4.157233238220215,0.018282055854797363,568.5153198242188 -1769682062,419505920,4.156682014465332,0.018299341201782227,568.5094604492188 -1769682062,457651712,4.156045436859131,0.018387675285339355,568.5015258789062 -1769682062,480967424,4.155597686767578,0.01841115951538086,568.4955444335938 -1769682062,513658112,4.155177116394043,0.018462061882019043,568.489501953125 -1769682062,564667648,4.154603481292725,0.01846134662628174,568.4814453125 -1769682062,575426560,4.153718948364258,0.018233418464660645,568.47509765625 -1769682062,614250752,4.152880668640137,0.01813828945159912,568.4686889648438 -1769682062,650865920,4.151790618896484,0.018070340156555176,568.4599609375 -1769682062,687969024,4.1509904861450195,0.01796090602874756,568.4534301757812 -1769682062,714141184,4.1502251625061035,0.01789546012878418,568.4469604492188 -1769682062,751724800,4.149318695068359,0.01767861843109131,568.438720703125 -1769682062,780698624,4.148670196533203,0.01745307445526123,568.4326782226562 -1769682062,816321280,4.148065090179443,0.017200469970703125,568.4268798828125 -1769682062,854191872,4.147304534912109,0.016939997673034668,568.4194946289062 -1769682062,880635392,4.146759986877441,0.01677572727203369,568.4142456054688 -1769682062,913986048,4.146247863769531,0.016582250595092773,568.4092407226562 -1769682062,959348992,4.145628929138184,0.016451478004455566,568.40283203125 -1769682062,969540096,4.145341396331787,0.016367316246032715,568.3997802734375 -1769682063,13849088,4.144805908203125,0.016354680061340332,568.3939819335938 -1769682063,53877504,4.144311904907227,0.016275882720947266,568.3886108398438 -1769682063,82809600,4.14396858215332,0.016290664672851562,568.384765625 -1769682063,114776576,4.143648624420166,0.016299962997436523,568.3810424804688 -1769682063,149914624,4.1433515548706055,0.01629185676574707,568.376220703125 -1769682063,180378880,4.143153190612793,0.01642298698425293,568.3729248046875 -1769682063,216374528,4.143003463745117,0.01656818389892578,568.3697509765625 -1769682063,253140992,4.142021656036377,0.01662743091583252,568.36572265625 -1769682063,282906880,4.141222953796387,0.0167618989944458,568.3628540039062 -1769682063,314044160,4.140470504760742,0.016869068145751953,568.3602294921875 -1769682063,358467840,4.139730453491211,0.01698589324951172,568.357666015625 -1769682063,367727872,4.13901424407959,0.01709270477294922,568.355224609375 -1769682063,414195712,4.138187408447266,0.017107248306274414,568.351806640625 -1769682063,447902720,4.1374616622924805,0.016916751861572266,568.3479614257812 -1769682063,480674304,4.136939525604248,0.016770005226135254,568.3449096679688 -1769682063,501182464,4.1365461349487305,0.016623973846435547,568.3427734375 -1769682063,544245504,4.135778903961182,0.016431570053100586,568.3383178710938 -1769682063,580770304,4.135085105895996,0.01622188091278076,568.3338012695312 -1769682063,598607616,4.134748935699463,0.01608562469482422,568.3316040039062 -1769682063,643909376,4.13413667678833,0.015932798385620117,568.3273315429688 -1769682063,681155328,4.133667945861816,0.015641450881958008,568.3233642578125 -1769682063,699520256,4.133459568023682,0.015415072441101074,568.3215942382812 -1769682063,748111360,4.132964611053467,0.015082120895385742,568.3175048828125 -1769682063,777096704,4.132808208465576,0.014929652214050293,568.3161010742188 -1769682063,814356736,4.132556915283203,0.014709115028381348,568.3132934570312 -1769682063,847813376,4.1323981285095215,0.014644384384155273,568.310791015625 -1769682063,880473856,4.132285118103027,0.014656782150268555,568.3090209960938 -1769682063,914877952,4.13219690322876,0.014683127403259277,568.307373046875 -1769682063,949054208,4.132116794586182,0.014777541160583496,568.3052978515625 -1769682063,980675584,4.132068634033203,0.014805793762207031,568.3038330078125 -1769682064,13985792,4.132037162780762,0.014852404594421387,568.3024291992188 -1769682064,61853696,4.132004737854004,0.014983773231506348,568.300537109375 -1769682064,71576064,4.131988525390625,0.015020608901977539,568.2994995117188 -1769682064,114404608,4.132039546966553,0.015154838562011719,568.2975463867188 -1769682064,159447808,4.132091999053955,0.015330791473388672,568.296142578125 -1769682064,169240064,4.132080554962158,0.015454530715942383,568.2948608398438 -1769682064,215631360,4.131962299346924,0.015653133392333984,568.2932739257812 -1769682064,247736576,4.131853103637695,0.015763401985168457,568.2918701171875 -1769682064,280741120,4.131793022155762,0.01583731174468994,568.291015625 -1769682064,314532608,4.1317138671875,0.015857577323913574,568.2903442382812 -1769682064,352566016,4.131709098815918,0.015781283378601074,568.28955078125 -1769682064,380857344,4.131716728210449,0.015607714653015137,568.288818359375 -1769682064,415113984,4.131699562072754,0.015416860580444336,568.2881469726562 -1769682064,453730816,4.131688117980957,0.015195012092590332,568.2872924804688 -1769682064,467225600,4.131798267364502,0.015072941780090332,568.2869262695312 -1769682064,514315776,4.132203102111816,0.014885783195495605,568.2861938476562 -1769682064,548129280,4.132607460021973,0.014659643173217773,568.2858276367188 -1769682064,569302016,4.132811546325684,0.01455998420715332,568.2858276367188 -1769682064,614464512,4.1331939697265625,0.014369368553161621,568.2860717773438 -1769682064,651727104,4.133577346801758,0.014174103736877441,568.2867431640625 -1769682064,680829440,4.133859157562256,0.013998031616210938,568.28759765625 -1769682064,702491904,4.134036540985107,0.013916373252868652,568.2883911132812 -1769682064,747862016,4.134456157684326,0.013664960861206055,568.291015625 -1769682064,781231872,4.1347527503967285,0.013514518737792969,568.29296875 -1769682064,814491136,4.13503360748291,0.01346290111541748,568.2952270507812 -1769682064,857095168,4.135305404663086,0.013471603393554688,568.2978515625 -1769682064,873168896,4.135654449462891,0.013447999954223633,568.3019409179688 -1769682064,914005504,4.135895252227783,0.013395190238952637,568.305419921875 -1769682064,949130752,4.136204719543457,0.013364076614379883,568.3106689453125 -1769682064,970479872,4.136356353759766,0.013358712196350098,568.3136596679688 -1769682065,14709760,4.136651992797852,0.013189911842346191,568.3200073242188 -1769682065,47994112,4.1369428634643555,0.01310122013092041,568.3271484375 -1769682065,80567552,4.137172698974609,0.012938141822814941,568.3331298828125 -1769682065,115559936,4.137399196624756,0.012810945510864258,568.3396606445312 -1769682065,154182656,4.137982368469238,0.012611865997314453,568.349365234375 -1769682065,181062656,4.138625144958496,0.012468218803405762,568.357421875 -1769682065,214059008,4.139266490936279,0.012279868125915527,568.3660278320312 -1769682065,262322176,4.140128135681152,0.012107133865356445,568.3783569335938 -1769682065,274235136,4.140777587890625,0.011954903602600098,568.38818359375 -1769682065,314696448,4.141427516937256,0.011804699897766113,568.3985595703125 -1769682065,348035584,4.142282009124756,0.011590003967285156,568.4129638671875 -1769682065,369675264,4.142704010009766,0.011546134948730469,568.42041015625 -1769682065,414943232,4.143571853637695,0.011250138282775879,568.4359130859375 -1769682065,448075520,4.1445136070251465,0.01102137565612793,568.4520874023438 -1769682065,480837888,4.145419597625732,0.010835409164428711,568.4646606445312 -1769682065,514375424,4.146342754364014,0.010710597038269043,568.4777221679688 -1769682065,550452736,4.147549629211426,0.010544419288635254,568.4957885742188 -1769682065,580829184,4.148440361022949,0.01041865348815918,568.5098266601562 -1769682065,614770176,4.149351596832275,0.010288357734680176,568.5242309570312 -1769682065,659575552,4.150253772735596,0.01024007797241211,568.5390014648438 -1769682065,668365056,4.151134014129639,0.010169029235839844,568.55419921875 -1769682065,714225408,4.152326583862305,0.009917378425598145,568.5751342773438 -1769682065,749758464,4.153506755828857,0.00969386100769043,568.5970458984375 -1769682065,770484224,4.154090404510498,0.009720444679260254,568.6083984375 -1769682065,815541248,4.155261993408203,0.00931549072265625,568.6319580078125 -1769682065,852698368,4.1564130783081055,0.00908970832824707,568.6568603515625 -1769682065,881190656,4.1572675704956055,0.008929610252380371,568.6763916015625 -1769682065,910875392,4.158118724822998,0.008785009384155273,568.6964721679688 -1769682065,943861760,4.1589555740356445,0.00870668888092041,568.7171630859375 -1769682065,967109376,4.159796237945557,0.008692502975463867,568.7382202148438 -1769682066,14290176,4.160904884338379,0.008457064628601074,568.7669067382812 -1769682066,63024384,4.161952495574951,0.008324742317199707,568.7959594726562 -1769682066,73069568,4.162705421447754,0.008243560791015625,568.8180541992188 -1769682066,114075648,4.163453102111816,0.008115291595458984,568.8403930664062 -1769682066,154531584,4.164548397064209,0.007990360260009766,568.863037109375 -1769682066,168929280,4.165599822998047,0.008008956909179688,568.8859252929688 -1769682066,214477824,4.166983604431152,0.007618904113769531,568.9171752929688 -1769682066,248013056,4.168336868286133,0.0074253082275390625,568.94921875 -1769682066,286177792,4.169305801391602,0.007330060005187988,568.9738159179688 -1769682066,314553856,4.170207500457764,0.007181286811828613,568.9987182617188 -1769682066,345135872,4.171095371246338,0.007147073745727539,569.0242919921875 -1769682066,381076224,4.172212600708008,0.006920456886291504,569.0589599609375 -1769682066,413126656,4.172723293304443,0.007094740867614746,569.0765380859375 -1769682066,454018560,4.174212455749512,0.006597042083740234,569.1217041015625 -1769682066,483487232,4.175103664398193,0.006420731544494629,569.149658203125 -1769682066,514403072,4.175966262817383,0.006279587745666504,569.17822265625 -1769682066,567284992,4.177079200744629,0.0060585737228393555,569.21728515625 -1769682066,569068800,4.177634239196777,0.006146550178527832,569.2372436523438 -1769682066,617111296,4.178612232208252,0.005785822868347168,569.2777709960938 -1769682066,649472768,4.179520606994629,0.00565648078918457,569.3191528320312 -1769682066,680935168,4.180186748504639,0.005626797676086426,569.3504638671875 -1769682066,701111808,4.180624008178711,0.005956172943115234,569.3713989257812 -1769682066,746557696,4.181352138519287,0.0056591033935546875,569.4134521484375 -1769682066,780993792,4.182016372680664,0.005591392517089844,569.455322265625 -1769682066,816033280,4.1824259757995605,0.005566596984863281,569.48681640625 -1769682066,850039552,4.1828083992004395,0.005495786666870117,569.5183715820312 -1769682066,868927488,4.183155059814453,0.005594372749328613,569.5501708984375 -1769682066,901311488,4.183426380157471,0.005646705627441406,569.5823974609375 -1769682066,947947776,4.183791160583496,0.004996538162231445,569.6370849609375 -1769682066,973438976,4.18389892578125,0.005329012870788574,569.659423828125 -1769682067,15433728,4.184055805206299,0.004715085029602051,569.7047119140625 -1769682067,49593088,4.1841278076171875,0.004497408866882324,569.7509155273438 -1769682067,80812288,4.184147834777832,0.004317760467529297,569.7863159179688 -1769682067,103344896,4.184306621551514,0.004679560661315918,569.8101806640625 -1769682067,152287488,4.184629917144775,0.0039664506912231445,569.8707275390625 -1769682067,181079808,4.184789657592773,0.0038776397705078125,569.907470703125 -1769682067,200367616,4.184875965118408,0.004205226898193359,569.9320678710938 -1769682067,261174016,4.185062408447266,0.003710150718688965,569.993896484375 -1769682067,274970880,4.185141563415527,0.004171013832092285,570.0186157226562 -1769682067,314279680,4.185269832611084,0.0036391019821166992,570.0684204101562 -1769682067,349071104,4.185365200042725,0.0035556554794311523,570.1184692382812 -1769682067,370141696,4.185408592224121,0.0038357973098754883,570.1436157226562 -1769682067,414462720,4.18565559387207,0.00345456600189209,570.1944580078125 -1769682067,449681664,4.185939311981201,0.003344893455505371,570.2457885742188 -1769682067,468385280,4.186080455780029,0.0036334991455078125,570.271728515625 -1769682067,515214080,4.186349868774414,0.0032873153686523438,570.3236083984375 -1769682067,545065728,4.18654727935791,0.003332972526550293,570.36279296875 -1769682067,566954240,4.186720371246338,0.003449678421020508,570.402099609375 -1769682067,617158400,4.186954498291016,0.003087639808654785,570.455078125 -1769682067,655393024,4.187159538269043,0.0029598474502563477,570.508544921875 -1769682067,681432832,4.1873064041137695,0.002829313278198242,570.549072265625 -1769682067,714423296,4.187454700469971,0.0027266740798950195,570.5900268554688 -1769682067,762486016,4.187633037567139,0.0025103092193603516,570.6455078125 -1769682067,771517952,4.1877217292785645,0.0029349327087402344,570.673583984375 -1769682067,815333376,4.187908172607422,0.0021780729293823242,570.7304077148438 -1769682067,849368832,4.188084125518799,0.001964569091796875,570.7882690429688 -1769682067,882511872,4.188170433044434,0.002110004425048828,570.8174438476562 -1769682067,905104896,4.188345909118652,0.0017406940460205078,570.8763427734375 -1769682067,948936192,4.1885223388671875,0.0016552209854125977,570.9356079101562 -1769682067,981090816,4.1886491775512695,0.0015538930892944336,570.9802856445312 -1769682068,16572160,4.188767433166504,0.0014982223510742188,571.025146484375 -1769682068,56020480,4.188936233520508,0.0013984441757202148,571.085205078125 -1769682068,81352448,4.189277172088623,0.0012912750244140625,571.13037109375 -1769682068,99205120,4.189506530761719,0.001654505729675293,571.1607055664062 -1769682068,158244096,4.189956188201904,0.001015305519104004,571.2219848632812 -1769682068,171246080,4.190290927886963,0.0014356374740600586,571.2684326171875 -1769682068,214585600,4.190738677978516,0.0005146265029907227,571.3314819335938 -1769682068,250013952,4.19117546081543,0.0002638101577758789,571.3956909179688 -1769682068,279236096,4.1913909912109375,0.0005067586898803711,571.4282836914062 -1769682068,316584192,4.191810131072998,3.063678741455078e-05,571.4942016601562 -1769682068,365579264,4.192214488983154,-9.1552734375e-05,571.5607299804688 -1769682068,372844288,4.192646026611328,-0.00013935565948486328,571.6110229492188 -1769682068,419213056,4.193073272705078,-0.0001933574676513672,571.6614990234375 -1769682068,451103488,4.193629741668701,-0.00026917457580566406,571.7290649414062 -1769682068,467048192,4.193868160247803,-2.6464462280273438e-05,571.7630004882812 -1769682068,514458880,4.1943254470825195,-0.0003911256790161133,571.8309936523438 -1769682068,566394880,4.194711685180664,-0.0005159378051757812,571.8995361328125 -1769682068,580505344,4.194967746734619,-0.0006258487701416016,571.951416015625 -1769682068,599015424,4.195128440856934,-0.0001493692398071289,571.9862670898438 -1769682068,648369664,4.195492267608643,-0.0009198188781738281,572.07421875 -1769682068,681583616,4.195628643035889,-0.0007140636444091797,572.1097412109375 -1769682068,714601216,4.195856094360352,-0.0010925531387329102,572.1813354492188 -1769682068,749221888,4.196023464202881,-0.0012055635452270508,572.25341796875 -1769682068,781149696,4.196142196655273,-0.0013386011123657227,572.307861328125 -1769682068,819035136,4.196176052093506,-0.0014598369598388672,572.3627319335938 -1769682068,852977664,4.196213245391846,-0.0015822649002075195,572.436279296875 -1769682068,881375744,4.1962432861328125,-0.001653909683227539,572.4917602539062 -1769682068,914645248,4.196188926696777,-0.001707911491394043,572.5474243164062 -1769682068,957542656,4.196115493774414,-0.0017496347427368164,572.6033325195312 -1769682068,970825984,4.196033954620361,-0.001146554946899414,572.6593627929688 -1769682069,15070464,4.195810794830322,-0.0020525455474853516,572.7346801757812 -1769682069,50324736,4.1957807540893555,-0.0022096633911132812,572.810791015625 -1769682069,82860032,4.195736885070801,-0.0018056631088256836,572.8489379882812 -1769682069,114750208,4.195598602294922,-0.0023761987686157227,572.9259643554688 -1769682069,150793728,4.1953840255737305,-0.0024346113204956055,573.0031127929688 -1769682069,167028992,4.195268630981445,-0.002051234245300293,573.0418090820312 -1769682069,216375040,4.1949849128723145,-0.0023958683013916016,573.1189575195312 -1769682069,247660288,4.194744110107422,-0.002285003662109375,573.1766967773438 -1769682069,281521408,4.194352626800537,-0.0023561716079711914,573.2536010742188 -1769682069,314412032,4.1940202713012695,-0.0023349523544311523,573.3112182617188 -1769682069,355877120,4.19380521774292,-0.0023130178451538086,573.3690185546875 -1769682069,370053376,4.193586349487305,-0.0017361640930175781,573.4269409179688 -1769682069,414650112,4.193247318267822,-0.0024051666259765625,573.5043334960938 -1769682069,449050368,4.1929144859313965,-0.002514362335205078,573.582275390625 -1769682069,482533888,4.192675590515137,-0.002665996551513672,573.6411743164062 -1769682069,515686144,4.192417144775391,-0.0027942657470703125,573.7005615234375 -1769682069,550145024,4.192047119140625,-0.0029261112213134766,573.780517578125 -1769682069,581084672,4.191760540008545,-0.0030101537704467773,573.8408813476562 -1769682069,617913088,4.191457271575928,-0.003057122230529785,573.9015502929688 -1769682069,658400256,4.1910400390625,-0.0032044649124145508,573.982666015625 -1769682069,667300352,4.190828323364258,-0.0029098987579345703,574.0234985351562 -1769682069,714787840,4.190386772155762,-0.0034737586975097656,574.1055908203125 -1769682069,758777856,4.190051078796387,-0.003596186637878418,574.1676025390625 -1769682069,768638976,4.189711093902588,-0.0032657384872436523,574.2300415039062 -1769682069,814742272,4.189250469207764,-0.003800511360168457,574.3136596679688 -1769682069,850177792,4.188776969909668,-0.0038089752197265625,574.3974609375 -1769682069,881589248,4.188419818878174,-0.0037267208099365234,574.460205078125 -1769682069,906855424,4.188045024871826,-0.003708958625793457,574.522705078125 -1769682069,949740544,4.187558650970459,-0.003701925277709961,574.6055908203125 -1769682069,981500416,4.187239646911621,-0.003750920295715332,574.667724609375 -1769682070,15254272,4.187047958374023,-0.003756880760192871,574.72998046875 -1769682070,48009984,4.186857223510742,-0.0036220550537109375,574.7923583984375 -1769682070,82887168,4.1865997314453125,-0.0038870573043823242,574.8758544921875 -1769682070,114863872,4.1863908767700195,-0.003953456878662109,574.9387817382812 -1769682070,149761280,4.186101913452148,-0.004079103469848633,575.0231323242188 -1769682070,172778240,4.1859564781188965,-0.0032945871353149414,575.0654907226562 -1769682070,200310528,4.1857171058654785,-0.0036411285400390625,575.12939453125 -1769682070,245834240,4.185397624969482,-0.0042917728424072266,575.2153930664062 -1769682070,266622976,4.1851487159729,-0.004059314727783203,575.2801513671875 -1769682070,301539328,4.184978008270264,-0.003730177879333496,575.3450317382812 -1769682070,349915392,4.184820652008057,-0.004361271858215332,575.453369140625 -1769682070,368837632,4.184757232666016,-0.0038661956787109375,575.4967041015625 -1769682070,399160576,4.184656620025635,-0.0037037134170532227,575.5615234375 -1769682070,466514176,4.184463024139404,-0.004410743713378906,575.6695556640625 -1769682070,468486912,4.1843791007995605,-0.004099726676940918,575.7129516601562 -1769682070,514979840,4.184192657470703,-0.004683494567871094,575.800048828125 -1769682070,555985408,4.184049129486084,-0.004824995994567871,575.8660888671875 -1769682070,569101568,4.183895587921143,-0.004232883453369141,575.9326171875 -1769682070,615422976,4.183703899383545,-0.0051392316818237305,576.0220947265625 -1769682070,649104128,4.183513164520264,-0.005257368087768555,576.1122436523438 -1769682070,683645952,4.183371067047119,-0.0053789615631103516,576.1802368164062 -1769682070,715425280,4.1832275390625,-0.005512714385986328,576.2485961914062 -1769682070,746943232,4.183083534240723,-0.0055353641510009766,576.3172607421875 -1769682070,766430208,4.182943344116211,-0.0052640438079833984,576.38623046875 -1769682070,818612736,4.182753562927246,-0.005775570869445801,576.4784545898438 -1769682070,850759424,4.182562351226807,-0.005871891975402832,576.5709228515625 -1769682070,870025472,4.182465076446533,-0.005307674407958984,576.6172485351562 -1769682070,899553280,4.182323932647705,-0.005287051200866699,576.6868286132812 -1769682070,960936448,4.182122230529785,-0.006136775016784668,576.8032836914062 -1769682070,967992832,4.182132244110107,-0.0055582523345947266,576.8501586914062 -1769682071,16378880,4.182232856750488,-0.006201028823852539,576.9442138671875 -1769682071,49905408,4.1823320388793945,-0.006240367889404297,577.0386352539062 -1769682071,79135488,4.182379722595215,-0.005836367607116699,577.0858764648438 -1769682071,115966720,4.182489395141602,-0.006289243698120117,577.180419921875 -1769682071,151068160,4.182600021362305,-0.006238579750061035,577.27490234375 -1769682071,181753088,4.182682037353516,-0.006202220916748047,577.3456420898438 -1769682071,216521728,4.182771682739258,-0.006114959716796875,577.4161376953125 -1769682071,252391424,4.182864189147949,-0.005888938903808594,577.486328125 -1769682071,281998080,4.1831841468811035,-0.005881547927856445,577.5796508789062 -1769682071,303087360,4.183516979217529,-0.0057572126388549805,577.6493530273438 -1769682071,360517376,4.183956623077393,-0.005669713020324707,577.741943359375 -1769682071,371122432,4.184177875518799,-0.004775404930114746,577.7881469726562 -1769682071,414597632,4.1846160888671875,-0.005556702613830566,577.8805541992188 -1769682071,449271552,4.185047149658203,-0.005543351173400879,577.97265625 -1769682071,478933248,4.185261249542236,-0.005035519599914551,578.0186767578125 -1769682071,515336448,4.185685634613037,-0.005462646484375,578.1103515625 -1769682071,550995712,4.186096668243408,-0.00542902946472168,578.201904296875 -1769682071,566112000,4.18629789352417,-0.00513458251953125,578.2476196289062 -1769682071,620880640,4.1866912841796875,-0.005531668663024902,578.3391723632812 -1769682071,653779712,4.187067985534668,-0.00555872917175293,578.4310913085938 -1769682071,668657920,4.18725061416626,-0.005071282386779785,578.4771118164062 -1769682071,715506944,4.187608242034912,-0.005420804023742676,578.5687866210938 -1769682071,759819008,4.187948226928711,-0.005269408226013184,578.6597290039062 -1769682071,769222144,4.188111782073975,-0.0045588016510009766,578.7048950195312 -1769682071,800335872,4.188345432281494,-0.004474997520446777,578.772216796875 -1769682071,842871808,4.188640117645264,-0.0050814151763916016,578.861572265625 -1769682071,877930240,4.188851356506348,-0.00478816032409668,578.9285278320312 -1769682071,899504896,4.189055442810059,-0.004502773284912109,578.99560546875 -1769682071,949795072,4.1896538734436035,-0.005077719688415527,579.1077880859375 -1769682071,967629824,4.189963340759277,-0.004609465599060059,579.1527099609375 -1769682072,10460672,4.1904168128967285,-0.00430905818939209,579.2200927734375 -1769682072,54783488,4.191205978393555,-0.004940629005432129,579.3319091796875 -1769682072,66489344,4.191522121429443,-0.004664301872253418,579.3765869140625 -1769682072,114806016,4.192187309265137,-0.0051174163818359375,579.4661865234375 -1769682072,157072128,4.1926727294921875,-0.005160093307495117,579.5337524414062 -1769682072,170668288,4.193148612976074,-0.004317045211791992,579.6016235351562 -1769682072,216721408,4.193789482116699,-0.005225419998168945,579.692138671875 -1769682072,249006336,4.194643974304199,-0.005170106887817383,579.7826538085938 -1769682072,283408640,4.195481777191162,-0.005042433738708496,579.8505249023438 -1769682072,299251200,4.196060657501221,-0.004392862319946289,579.8958129882812 -1769682072,345141760,4.197205066680908,-0.005012989044189453,579.9862670898438 -1769682072,367441664,4.198060512542725,-0.00462949275970459,580.05419921875 -1769682072,416032000,4.199195384979248,-0.005214333534240723,580.1448974609375 -1769682072,450740224,4.200336456298828,-0.0053255558013916016,580.236083984375 -1769682072,468844288,4.200899600982666,-0.004909992218017578,580.28173828125 -1769682072,515966720,4.202045917510986,-0.005597352981567383,580.3737182617188 -1769682072,552508416,4.203188419342041,-0.005832672119140625,580.4663696289062 -1769682072,565940992,4.2037529945373535,-0.005614638328552246,580.51318359375 -1769682072,614816000,4.204898834228516,-0.0062819719314575195,580.6076049804688 -1769682072,655382784,4.205740928649902,-0.006369948387145996,580.67919921875 -1769682072,670737920,4.206578254699707,-0.005569815635681152,580.751220703125 -1769682072,700968960,4.207402229309082,-0.005922555923461914,580.8235473632812 -1769682072,747522816,4.208494663238525,-0.006695389747619629,580.9202270507812 -1769682072,781414144,4.209237575531006,-0.0065767765045166016,580.9931640625 -1769682072,798556416,4.209969520568848,-0.006365418434143066,581.0664672851562 -1769682072,847474688,4.210899829864502,-0.007187008857727051,581.1648559570312 -1769682072,866779136,4.2114763259887695,-0.00671076774597168,581.2389526367188 -1769682072,912120064,4.212096214294434,-0.006321072578430176,581.3131103515625 -1769682072,953753600,4.2134318351745605,-0.006819605827331543,581.4364624023438 -1769682072,981623296,4.214207172393799,-0.006730437278747559,581.510009765625 -1769682072,999549696,4.2146711349487305,-0.005976438522338867,581.5588989257812 -1769682073,66892800,4.215674877166748,-0.0068721771240234375,581.6812133789062 -1769682073,70413312,4.216065883636475,-0.006504654884338379,581.7302856445312 -1769682073,115046144,4.216668605804443,-0.007178187370300293,581.8291625976562 -1769682073,146255616,4.217054843902588,-0.007035613059997559,581.9039916992188 -1769682073,181789952,4.2175703048706055,-0.007472991943359375,582.004638671875 -1769682073,201197312,4.217803001403809,-0.006695151329040527,582.0552368164062 -1769682073,251465728,4.218221187591553,-0.007699489593505859,582.1826171875 -1769682073,266733568,4.218364715576172,-0.007288575172424316,582.23388671875 -1769682073,315121920,4.218571186065674,-0.007876038551330566,582.3368530273438 -1769682073,346483456,4.218470573425293,-0.007947444915771484,582.4144287109375 -1769682073,366639616,4.218329429626465,-0.007524609565734863,582.4920654296875 -1769682073,415031552,4.21807861328125,-0.007832050323486328,582.5950317382812 -1769682073,465183744,4.217496395111084,-0.007716178894042969,582.6973876953125 -1769682073,479224320,4.2171173095703125,-0.00731503963470459,582.748291015625 -1769682073,498164736,4.216344356536865,-0.006863236427307129,582.8245239257812 -1769682073,543885056,4.2152228355407715,-0.007625222206115723,582.92578125 -1769682073,581686784,4.213772773742676,-0.007708191871643066,583.0272827148438 -1769682073,620846592,4.212557315826416,-0.007752537727355957,583.1035766601562 -1769682073,648460288,4.211234092712402,-0.007669806480407715,583.1802368164062 -1769682073,668643840,4.2096757888793945,-0.007716178894042969,583.2572021484375 -1769682073,698392576,4.20802116394043,-0.007761478424072266,583.335693359375 -1769682073,763804160,4.2051191329956055,-0.00869452953338623,583.4684448242188 -1769682073,771027200,4.203922271728516,-0.007645130157470703,583.5218505859375 -1769682073,799203328,4.201949119567871,-0.007941722869873047,583.6017456054688 -1769682073,841850368,4.199221611022949,-0.00850832462310791,583.7076416015625 -1769682073,877791488,4.197037696838379,-0.00799560546875,583.7860717773438 -1769682073,899057664,4.194931507110596,-0.00739288330078125,583.86376953125 -1769682073,952027904,4.191201686859131,-0.007869839668273926,583.9915771484375 -1769682073,966100992,4.189603805541992,-0.00740206241607666,584.042236328125 -1769682074,12899840,4.187165260314941,-0.007055163383483887,584.1179809570312 -1769682074,48603136,4.183715343475342,-0.007681608200073242,584.2186279296875 -1769682074,67603200,4.180952072143555,-0.007050752639770508,584.2938232421875 -1769682074,98534656,4.178104400634766,-0.006636142730712891,584.3685302734375 -1769682074,165488128,4.173147201538086,-0.007066488265991211,584.49169921875 -1769682074,174172672,4.170074462890625,-0.006924152374267578,584.5647583007812 -1769682074,199211008,4.167909145355225,-0.006181955337524414,584.6132202148438 -1769682074,244058624,4.163429260253906,-0.006745815277099609,584.709716796875 -1769682074,278135296,4.159875392913818,-0.006691455841064453,584.7821044921875 -1769682074,299054848,4.156299591064453,-0.006867527961730957,584.8533935546875 -1769682074,345435648,4.151305198669434,-0.008075952529907227,584.9468383789062 -1769682074,365844224,4.147459506988525,-0.008180499076843262,585.015869140625 -1769682074,412423680,4.143434524536133,-0.00822305679321289,585.0841064453125 -1769682074,447955456,4.137831687927246,-0.009315133094787598,585.174072265625 -1769682074,466330368,4.133478164672852,-0.009390592575073242,585.2411499023438 -1769682074,498725376,4.128988265991211,-0.009403347969055176,585.3082275390625 -1769682074,556762368,4.122771263122559,-0.010358691215515137,585.39794921875 -1769682074,573445632,4.116201400756836,-0.010545730590820312,585.4877319335938 -1769682074,599120640,4.112854957580566,-0.00996100902557373,585.5325317382812 -1769682074,645220352,4.106037139892578,-0.010564684867858887,585.6219482421875 -1769682074,677621504,4.100883960723877,-0.010276079177856445,585.6886596679688 -1769682074,699107072,4.095534324645996,-0.009868144989013672,585.7550048828125 -1769682074,748446976,4.088310241699219,-0.010175466537475586,585.8427734375 -1769682074,765392384,4.082660675048828,-0.009865283966064453,585.9081420898438 -1769682074,814113792,4.076900482177734,-0.009393930435180664,585.972900390625 -1769682074,852877312,4.069037437438965,-0.009728789329528809,586.058349609375 -1769682074,869879552,4.062946319580078,-0.009050965309143066,586.1219482421875 -1769682074,898738176,4.05682373046875,-0.008828043937683105,586.1849365234375 -1769682074,957598720,4.0484747886657715,-0.008957505226135254,586.2683715820312 -1769682074,969064704,4.042116165161133,-0.008414983749389648,586.3303833007812 -1769682074,999699712,4.035589694976807,-0.008048176765441895,586.3920288085938 -1769682075,42727936,4.026700973510742,-0.008327364921569824,586.4734497070312 -1769682075,65705984,4.019878387451172,-0.007816433906555176,586.5338134765625 -1769682075,105495296,4.0105509757995605,-0.007796168327331543,586.6134643554688 -1769682075,143508480,4.003475189208984,-0.007550358772277832,586.67236328125 -1769682075,168238592,3.9962711334228516,-0.0070656538009643555,586.7308349609375 -1769682075,198727168,3.9890353679656982,-0.006759285926818848,586.7886962890625 -1769682075,260673536,3.979132652282715,-0.006937742233276367,586.865478515625 -1769682075,269021952,3.971513509750366,-0.0067250728607177734,586.9229125976562 -1769682075,298668288,3.9637067317962646,-0.006561398506164551,586.9804077148438 -1769682075,344341760,3.953214168548584,-0.006924867630004883,587.056884765625 -1769682075,369783040,3.9451732635498047,-0.0064307451248168945,587.1142578125 -1769682075,401612800,3.9370944499969482,-0.006275534629821777,587.17138671875 -1769682075,447039488,3.9262218475341797,-0.0068024396896362305,587.247314453125 -1769682075,465972224,3.9177982807159424,-0.006543278694152832,587.3042602539062 -1769682075,502754304,3.9093360900878906,-0.006148219108581543,587.361328125 -1769682075,547833344,3.8977386951446533,-0.006767988204956055,587.4376831054688 -1769682075,567052288,3.8890280723571777,-0.006535053253173828,587.494873046875 -1769682075,598856192,3.8801143169403076,-0.0061719417572021484,587.5516357421875 -1769682075,648934912,3.868189573287964,-0.00639498233795166,587.62646484375 -1769682075,667184896,3.859071731567383,-0.0058928728103637695,587.6817626953125 -1769682075,698534400,3.8499093055725098,-0.005638480186462402,587.7362060546875 -1769682075,742691584,3.837531089782715,-0.005956411361694336,587.8079833984375 -1769682075,768362240,3.828037977218628,-0.005570173263549805,587.8613891601562 -1769682075,799247104,3.818523406982422,-0.0053424835205078125,587.9144287109375 -1769682075,844755712,3.8056764602661133,-0.00573575496673584,587.98486328125 -1769682075,866050048,3.795849084854126,-0.005421042442321777,588.0374755859375 -1769682075,901052416,3.7858331203460693,-0.005037426948547363,588.0899047851562 -1769682075,942098688,3.772491931915283,-0.005578517913818359,588.1593017578125 -1769682075,967003136,3.7622334957122803,-0.005406022071838379,588.2112426757812 -1769682075,999022080,3.751743793487549,-0.0052525997161865234,588.2635498046875 -1769682076,62257664,3.7374918460845947,-0.005680203437805176,588.333740234375 -1769682076,69206016,3.726581573486328,-0.005238652229309082,588.3865356445312 -1769682076,98892288,3.71557354927063,-0.005063652992248535,588.4393920898438 -1769682076,145333504,3.700779914855957,-0.005177974700927734,588.5090942382812 -1769682076,173582336,3.6858983039855957,-0.00484919548034668,588.577392578125 -1769682076,198850816,3.6783087253570557,-0.004267692565917969,588.6109008789062 -1769682076,243947264,3.662936210632324,-0.004408597946166992,588.6766967773438 -1769682076,266127104,3.651284694671631,-0.00403594970703125,588.7252807617188 -1769682076,301276928,3.639477252960205,-0.0036622285842895508,588.7734375 -1769682076,345529088,3.6234519481658936,-0.003915190696716309,588.8370361328125 -1769682076,368822016,3.611250638961792,-0.003407597541809082,588.8843994140625 -1769682076,398687744,3.598926067352295,-0.0031266212463378906,588.9310913085938 -1769682076,447529728,3.582329750061035,-0.0032311677932739258,588.9925537109375 -1769682076,466496256,3.5698013305664062,-0.0029299259185791016,589.0382690429688 -1769682076,499601920,3.5570433139801025,-0.0026096105575561523,589.0836181640625 -1769682076,544204800,3.53993821144104,-0.0028535127639770508,589.1436157226562 -1769682076,573030400,3.5269885063171387,-0.0022454261779785156,589.188232421875 -1769682076,599908864,3.51387882232666,-0.0022220611572265625,589.232421875 -1769682076,644513024,3.496248483657837,-0.0021823644638061523,589.2903442382812 -1769682076,666193664,3.4829189777374268,-0.0017189979553222656,589.332763671875 -1769682076,701225984,3.469552516937256,-0.0011949539184570312,589.3739013671875 -1769682076,747330304,3.4514286518096924,-0.0011930465698242188,589.427001953125 -1769682076,766080256,3.4378066062927246,-0.0010006427764892578,589.466064453125 -1769682076,799465728,3.42394757270813,-0.0008064508438110352,589.5049438476562 -1769682076,857316864,3.405374050140381,-0.0011661052703857422,589.5567626953125 -1769682076,870541056,3.391258716583252,-0.0008579492568969727,589.595947265625 -1769682076,898984704,3.377142906188965,-0.0008771419525146484,589.6351928710938 -1769682076,946434304,3.358144998550415,-0.0010868310928344727,589.6875 -1769682076,968635904,3.3438243865966797,-0.0007789134979248047,589.726318359375 -1769682077,27904,3.3293814659118652,-0.0005127191543579102,589.7644653320312 -1769682077,47987968,3.3099286556243896,-0.0006040334701538086,589.814453125 -1769682077,66199808,3.2952938079833984,-0.0004382133483886719,589.8513793945312 -1769682077,104909568,3.275602340698242,-0.0006515979766845703,589.900390625 -1769682077,145499648,3.2606725692749023,-0.0005383491516113281,589.9373779296875 -1769682077,166623744,3.2455835342407227,-0.0005205869674682617,589.9743041992188 -1769682077,198927616,3.2304532527923584,-0.0002894401550292969,590.0113525390625 -1769682077,249500672,3.2101030349731445,-0.0003802776336669922,590.0604858398438 -1769682077,265816064,3.194671869277954,-6.61611557006836e-05,590.0967407226562 -1769682077,300425216,3.1791915893554688,0.00024247169494628906,590.132568359375 -1769682077,342724864,3.1583657264709473,8.749961853027344e-05,590.1796264648438 -1769682077,369484544,3.1426985263824463,0.00035858154296875,590.2145385742188 -1769682077,399605760,3.1269125938415527,0.0003528594970703125,590.24951171875 -1769682077,443421440,3.105788469314575,0.00011873245239257812,590.296142578125 -1769682077,465841408,3.089869737625122,0.0003142356872558594,590.3311157226562 -1769682077,501730560,3.073869228363037,0.0006177425384521484,590.3658447265625 -1769682077,548642560,3.052337169647217,0.0005269050598144531,590.4114990234375 -1769682077,565800448,3.0359840393066406,0.0008976459503173828,590.4450073242188 -1769682077,599364096,3.0195798873901367,0.0012630224227905273,590.4776611328125 -1769682077,654803200,2.997558832168579,0.0012549161911010742,590.5201416015625 -1769682077,672459008,2.9809820652008057,0.0016093254089355469,590.5514526367188 -1769682077,698854144,2.964381217956543,0.0014842748641967773,590.5828247070312 -1769682077,747120128,2.942112922668457,0.001217961311340332,590.625 -1769682077,771056384,2.9253954887390137,0.0013726353645324707,590.6571044921875 -1769682077,799675904,2.908473253250122,0.0013495683670043945,590.6895141601562 -1769682077,843685376,2.885756492614746,0.0011844038963317871,590.7327880859375 -1769682077,866616320,2.8685944080352783,0.001368880271911621,590.7649536132812 -1769682077,901520896,2.851433277130127,0.001608431339263916,590.7966918945312 -1769682077,944873216,2.828479290008545,0.001515209674835205,590.8380737304688 -1769682077,967207936,2.811250686645508,0.0015491843223571777,590.8687133789062 -1769682077,999149824,2.7938265800476074,0.0015645623207092285,590.8995971679688 -1769682078,57702656,2.770555019378662,0.001164078712463379,590.9412841796875 -1769682078,75052032,2.747084617614746,0.0009219050407409668,590.9840087890625 -1769682078,101091072,2.735304117202759,0.0011570453643798828,591.0055541992188 -1769682078,143450368,2.711620330810547,0.0008941888809204102,591.0489501953125 -1769682078,169424896,2.6937339305877686,0.001168966293334961,591.0812377929688 -1769682078,199733504,2.6759402751922607,0.001351773738861084,591.113037109375 -1769682078,244115968,2.652113676071167,0.0013980269432067871,591.1541748046875 -1769682078,266550528,2.634300947189331,0.0017309784889221191,591.18408203125 -1769682078,301199616,2.6161577701568604,0.0020498037338256836,591.2131958007812 -1769682078,345520128,2.591951370239258,0.0019249916076660156,591.2511596679688 -1769682078,366061568,2.573807716369629,0.0019366741180419922,591.2794189453125 -1769682078,400481792,2.555602788925171,0.0018674731254577637,591.3082275390625 -1769682078,457517824,2.5312647819519043,0.0013788342475891113,591.347900390625 -1769682078,475522304,2.506880283355713,0.0011649131774902344,591.3888549804688 -1769682078,499165696,2.494589328765869,0.00130385160446167,591.4097290039062 -1769682078,544359168,2.470067262649536,0.001069486141204834,591.45166015625 -1769682078,572763392,2.451509952545166,0.001365065574645996,591.4829711914062 -1769682078,600336384,2.432663917541504,0.0014480352401733398,591.5137329101562 -1769682078,650249216,2.407529830932617,0.0014781355857849121,591.5540771484375 -1769682078,666296832,2.38869047164917,0.0017490386962890625,591.5835571289062 -1769682078,705250816,2.36344838142395,0.0017737746238708496,591.6221313476562 -1769682078,745967616,2.344533920288086,0.0017898082733154297,591.6507568359375 -1769682078,769036288,2.3255958557128906,0.0016932487487792969,591.6795654296875 -1769682078,799285248,2.30655837059021,0.0014348626136779785,591.709228515625 -1769682078,843120128,2.2811262607574463,0.0008445382118225098,591.7506103515625 -1769682078,866555392,2.2620935440063477,0.00063323974609375,591.7828979492188 -1769682078,899917056,2.243002414703369,0.0005003213882446289,591.8159790039062 -1769682078,943532288,2.2174227237701416,0.0002630949020385742,591.8606567382812 -1769682078,968904448,2.1982226371765137,0.0004406571388244629,591.8939819335938 -1769682078,999407616,2.1789088249206543,0.0005714893341064453,591.9266967773438 -1769682079,44838912,2.1531412601470947,0.0007125735282897949,591.9691162109375 -1769682079,66569216,2.133791446685791,0.0010474920272827148,591.9996948242188 -1769682079,104676096,2.10789155960083,0.0012598037719726562,592.0392456054688 -1769682079,145717504,2.0883920192718506,0.0012917518615722656,592.0682983398438 -1769682079,166095360,2.0687739849090576,0.0012053251266479492,592.0973510742188 -1769682079,200240896,2.049302101135254,0.001022934913635254,592.1272583007812 -1769682079,256679936,2.0234181880950928,0.0004200935363769531,592.1690673828125 -1769682079,276887552,1.997336745262146,2.5391578674316406e-05,592.2129516601562 -1769682079,299166976,1.9842828512191772,2.8371810913085938e-05,592.235595703125 -1769682079,344809728,1.9582207202911377,-0.00026857852935791016,592.2813720703125 -1769682079,371389440,1.9385483264923096,-2.962350845336914e-05,592.315673828125 -1769682079,399197440,1.9188884496688843,7.50422477722168e-05,592.349365234375 -1769682079,444941568,1.892671823501587,0.00024318695068359375,592.3928833007812 -1769682079,466256384,1.8729960918426514,0.0005960464477539062,592.42431640625 -1769682079,501239552,1.8532066345214844,0.0009570717811584473,592.4546508789062 -1769682079,545191424,1.8267825841903687,0.0011410117149353027,592.49365234375 -1769682079,566128384,1.8070611953735352,0.0013917088508605957,592.5220947265625 -1769682079,599267584,1.7873258590698242,0.001500546932220459,592.5501708984375 -1769682079,647830272,1.7611498832702637,0.0010425448417663574,592.588134765625 -1769682079,668014592,1.741471529006958,0.000593721866607666,592.6180419921875 -1769682079,700271360,1.7215913534164429,5.245208740234375e-05,592.6498413085938 -1769682079,741437440,1.695224642753601,-0.0008902549743652344,592.6954956054688 -1769682079,773125888,1.6755683422088623,-0.001216113567352295,592.731689453125 -1769682079,799643648,1.6558912992477417,-0.0016397833824157715,592.7689819335938 -1769682079,847722240,1.6297696828842163,-0.0020233988761901855,592.8194580078125 -1769682079,866426368,1.6101940870285034,-0.0018866658210754395,592.8570556640625 -1769682079,902607360,1.5839922428131104,-0.001711428165435791,592.9055786132812 -1769682079,944298240,1.5643203258514404,-0.0014390349388122559,592.9406127929688 -1769682079,966833920,1.5447907447814941,-0.0010887384414672852,592.9744262695312 -1769682079,999010048,1.5252881050109863,-0.0007354915142059326,593.0072021484375 -1769682080,48476416,1.4992746114730835,-0.0004596114158630371,593.0493774414062 -1769682080,68208128,1.4796994924545288,-0.00013813376426696777,593.0801391601562 -1769682080,99308544,1.4600245952606201,6.768107414245605e-05,593.1104736328125 -1769682080,145345280,1.4338608980178833,0.00020971894264221191,593.150390625 -1769682080,170112000,1.4143909215927124,0.00040602684020996094,593.1802368164062 -1769682080,200375040,1.394817590713501,0.00026223063468933105,593.2101440429688 -1769682080,247193088,1.3686723709106445,-0.0004240870475769043,593.25146484375 -1769682080,265980416,1.3490740060806274,-0.0010549426078796387,593.2843017578125 -1769682080,304724480,1.323011875152588,-0.0021929144859313965,593.3317260742188 -1769682080,347127808,1.3035321235656738,-0.002901136875152588,593.3698120117188 -1769682080,368714496,1.284227967262268,-0.0034177303314208984,593.4096069335938 -1769682080,399017216,1.2648298740386963,-0.0037469565868377686,593.4503784179688 -1769682080,449048064,1.239260196685791,-0.004049181938171387,593.5051879882812 -1769682080,466889728,1.220069169998169,-0.0039028525352478027,593.545654296875 -1769682080,499586560,1.2008570432662964,-0.0036132633686065674,593.5847778320312 -1769682080,541713664,1.1752135753631592,-0.0032916367053985596,593.634765625 -1769682080,571107840,1.1560606956481934,-0.002805769443511963,593.6705322265625 -1769682080,599867392,1.1369574069976807,-0.002345860004425049,593.705078125 -1769682080,648229632,1.1115604639053345,-0.0019066035747528076,593.7493286132812 -1769682080,666833920,1.0925883054733276,-0.0015231668949127197,593.7815551757812 -1769682080,704327936,1.0671459436416626,-0.001134335994720459,593.823486328125 -1769682080,744271104,1.0481703281402588,-0.0008683204650878906,593.8543701171875 -1769682080,766461440,1.029191493988037,-0.0006545186042785645,593.8849487304688 -1769682080,799199744,1.0102519989013672,-0.00041687488555908203,593.915283203125 -1769682080,850404352,0.9850910305976868,-0.00024521350860595703,593.9553833007812 -1769682080,866630400,0.966398298740387,-0.00013127923011779785,593.985107421875 -1769682080,899343872,0.9476224780082703,-8.255243301391602e-06,594.0147094726562 -1769682080,947525888,0.9232548475265503,-0.00028640031814575195,594.0540161132812 -1769682080,969284096,0.9051414132118225,-0.0006743669509887695,594.0842895507812 -1769682081,18048256,0.880479633808136,-0.001440674066543579,594.1265869140625 -1769682081,43672832,0.8559046983718872,-0.0021407604217529297,594.171630859375 -1769682081,68006400,0.8436317443847656,-0.0024844706058502197,594.195068359375 -1769682081,100709632,0.82558274269104,-0.002933979034423828,594.2312622070312 -1769682081,146224384,0.8017092943191528,-0.00343891978263855,594.280517578125 -1769682081,166243072,0.7842144966125488,-0.00356099009513855,594.3176879882812 -1769682081,212734720,0.7664812207221985,-0.0035378187894821167,594.3544921875 -1769682081,246182144,0.7434143424034119,-0.0034394264221191406,594.4022827148438 -1769682081,267719424,0.7258698344230652,-0.003162100911140442,594.4369506835938 -1769682081,299233792,0.7083708047866821,-0.0027969926595687866,594.4705200195312 -1769682081,359303680,0.685350239276886,-0.0023061931133270264,594.513427734375 -1769682081,367841280,0.6686122417449951,-0.0018102973699569702,594.5441284179688 -1769682081,400422144,0.6516522765159607,-0.0012771934270858765,594.5736083984375 -1769682081,443119360,0.6294525861740112,-0.0006031394004821777,594.611083984375 -1769682081,467625984,0.613219678401947,-2.0951032638549805e-05,594.6377563476562 -1769682081,500161536,0.5970613360404968,0.0005404055118560791,594.663330078125 -1769682081,544897280,0.5760552883148193,0.0012618601322174072,594.6956176757812 -1769682081,566088192,0.5605496168136597,0.0018070191144943237,594.718505859375 -1769682081,610213376,0.5450475811958313,0.0023380815982818604,594.7404174804688 -1769682081,647767808,0.5243770480155945,0.002983078360557556,594.7678833007812 -1769682081,666550016,0.5088746547698975,0.003436446189880371,594.7874145507812 -1769682081,700019712,0.49337315559387207,0.003894522786140442,594.8057250976562 -1769682081,756771840,0.47394269704818726,0.004456192255020142,594.8287963867188 -1769682081,770513408,0.4621501863002777,0.0048857927322387695,594.8449096679688 -1769682081,801997824,0.45221227407455444,0.0051904767751693726,594.860107421875 -1769682081,846141696,0.43576693534851074,0.0055833905935287476,594.8789672851562 -1769682081,878963712,0.4202668070793152,0.005906000733375549,594.8925170898438 -1769682081,899416832,0.40600425004959106,0.0062892138957977295,594.9053344726562 -1769682081,946738688,0.3853442072868347,0.006692469120025635,594.9215087890625 -1769682081,966739712,0.3717249035835266,0.006970919668674469,594.9327392578125 -1769682082,13280512,0.3587343394756317,0.007301591336727142,594.9431762695312 -1769682082,48775424,0.34057632088661194,0.007609367370605469,594.9559936523438 -1769682082,68647168,0.32699865102767944,0.007843121886253357,594.9649658203125 -1769682082,100448000,0.3140687346458435,0.008091777563095093,594.9732666015625 -1769682082,159311360,0.2959785759449005,0.008372589945793152,594.9834594726562 -1769682082,170823936,0.2817043662071228,0.008591748774051666,594.9906616210938 -1769682082,200621568,0.2693038880825043,0.008776649832725525,594.9972534179688 -1769682082,243671296,0.24863706529140472,0.00910796970129013,595.00537109375 -1769682082,278266880,0.23506715893745422,0.009312920272350311,595.0108642578125 -1769682082,301583616,0.22400572896003723,0.009492412209510803,595.0158081054688 -1769682082,343454720,0.21113230288028717,0.009676314890384674,595.0215454101562 -1769682082,366455040,0.2016228884458542,0.00980159267783165,595.0252075195312 -1769682082,410631424,0.19211407005786896,0.009974218904972076,595.0285034179688 -1769682082,448695296,0.1794353872537613,0.010126959532499313,595.0321655273438 -1769682082,469931776,0.16992421448230743,0.01025613397359848,595.0346069335938 -1769682082,499282432,0.16041310131549835,0.010413475334644318,595.0368041992188 -1769682082,556253696,0.14773161709308624,0.010538484901189804,595.039306640625 -1769682082,572815104,0.13504646718502045,0.010673053562641144,595.0413818359375 -1769682082,600840960,0.12870414555072784,0.010747265070676804,595.0421752929688 -1769682082,646148608,0.1160198226571083,0.010897040367126465,595.043701171875 -1769682082,681526528,0.10650379210710526,0.010980073362588882,595.0444946289062 -1769682082,699470592,0.09698845446109772,0.011085037142038345,595.0451049804688 -1769682082,743712256,0.08431248366832733,0.011204002425074577,595.0455932617188 -1769682082,766361856,0.07480286061763763,0.011233502998948097,595.0457763671875 -1769682082,811415808,0.06529336422681808,0.01129429042339325,595.0457763671875 -1769682082,846758656,0.052614111453294754,0.01142625417560339,595.0455322265625 -1769682082,868135936,0.043102484196424484,0.011495397426187992,595.0452270507812 -1769682082,899344640,0.0,-0.0,595.0459594726562 -1769682082,959241216,0.0,-0.0,595.0459594726562 -1769682082,967655424,0.0,-0.0,595.0459594726562 -1769682083,653568,0.0,-0.0,595.0459594726562 -1769682083,44847616,0.0,-0.0,595.0459594726562 -1769682083,66499328,0.0,-0.0,595.0459594726562 -1769682083,100040192,0.0,-0.0,595.0459594726562 -1769682083,144382208,0.0,-0.0,595.0459594726562 -1769682083,166351616,0.0,-0.0,595.0459594726562 -1769682083,210019328,0.0,-0.0,595.0459594726562 -1769682083,252273408,0.0,-0.0,595.0459594726562 -1769682083,268891392,0.0,-0.0,595.0459594726562 -1769682083,299468800,0.0,-0.0,595.0459594726562 -1769682083,355685120,0.0,-0.0,595.0459594726562 -1769682083,370723840,0.0,-0.0,595.0459594726562 -1769682083,400806656,0.0,-0.0,595.0459594726562 -1769682083,444600320,0.0,-0.0,595.0459594726562 -1769682083,484027648,0.0,-0.0,595.0459594726562 -1769682083,499753216,0.0,-0.0,595.0459594726562 -1769682083,552578048,0.0,-0.0,595.0459594726562 -1769682083,567736832,0.0,-0.0,595.0459594726562 -1769682083,609743360,0.0,-0.0,595.0459594726562 -1769682083,650066944,0.0,-0.0,595.0459594726562 -1769682083,669276672,0.0,-0.0,595.0459594726562 -1769682083,699639552,0.0,-0.0,595.0459594726562 -1769682083,748513024,0.0,-0.0,595.0459594726562 -1769682083,766773248,0.0,-0.0,595.0459594726562 -1769682083,799625728,0.0,-0.0,595.0459594726562 -1769682083,845560064,0.0,-0.0,595.0459594726562 -1769682083,873488384,0.0,-0.0,595.0459594726562 -1769682083,900744192,0.0,-0.0,595.0459594726562 -1769682083,944880640,0.0,-0.0,595.0459594726562 -1769682083,966494976,0.0,-0.0,595.0459594726562 -1769682084,1017088,0.0,-0.0,595.0459594726562 -1769682084,53259008,0.0,-0.0,595.0460205078125 -1769682084,69108736,0.0,-0.0,595.0460205078125 -1769682084,99521024,0.0,-0.0,595.0460205078125 -1769682084,146659584,0.0,-0.0,595.0460205078125 -1769682084,166736128,0.0,-0.0,595.0460205078125 -1769682084,199493632,0.0,-0.0,595.0460205078125 -1769682084,244625152,0.0,-0.0,595.0460205078125 -1769682084,268357632,0.0,-0.0,595.0460205078125 -1769682084,301943808,0.0,-0.0,595.0460205078125 -1769682084,343927808,0.0,-0.0,595.0460205078125 -1769682084,376743168,0.0,-0.0,595.0460205078125 -1769682084,400738816,0.0,-0.0,595.0460205078125 -1769682084,444682240,0.0,-0.0,595.0460205078125 -1769682084,466789376,0.0,-0.0,595.0460205078125 -1769682084,515276544,0.0,-0.0,595.0460205078125 -1769682084,550225408,0.0,-0.0,595.0460205078125 -1769682084,568155648,0.0,-0.0,595.0460205078125 -1769682084,599814144,0.0,-0.0,595.0460205078125 -1769682084,657167616,0.0,-0.0,595.0460205078125 -1769682084,670425344,0.0,-0.0,595.0460205078125 -1769682084,701838848,0.0,-0.0,595.0460205078125 -1769682084,744483840,0.0,-0.0,595.0460205078125 -1769682084,777924352,0.0,-0.0,595.0460205078125 -1769682084,799596544,0.0,-0.0,595.0460205078125 -1769682084,849946624,0.0,-0.0,595.0460205078125 -1769682084,868508672,0.0,-0.0,595.0460205078125 -1769682084,910160896,0.0,-0.0,595.0460205078125 -1769682084,949344768,0.0,-0.0,595.0460205078125 -1769682084,967320320,0.0,-0.0,595.0460205078125 -1769682084,999742208,0.0,-0.0,595.0460205078125 -1769682085,56089856,0.0,-0.0,595.0460205078125 -1769682085,69967360,0.0,-0.0,595.0460205078125 -1769682085,101258496,0.0,-0.0,595.0460205078125 -1769682085,144666624,0.0,-0.0,595.0460205078125 -1769682085,178153216,0.0,-0.0,595.0460205078125 -1769682085,200668416,0.0,-0.0,595.0460205078125 -1769682085,242048000,0.0,-0.0,595.0460205078125 -1769682085,267771136,0.0,-0.0,595.0460205078125 -1769682085,308499712,0.0,-0.0,595.0460205078125 -1769682085,344192000,0.0,-0.0,595.0460205078125 -1769682085,367932672,0.0,-0.0,595.0460205078125 -1769682085,399806976,0.0,-0.0,595.0460205078125 -1769682085,456473600,0.0,-0.0,595.0460205078125 -1769682085,469579008,0.0,-0.0,595.0460205078125 -1769682085,500752896,0.0,-0.0,595.0460205078125 -1769682085,543247360,0.0,-0.0,595.0460205078125 -1769682085,578151168,0.0,-0.0,595.0460205078125 -1769682085,600925184,0.0,-0.0,595.0460205078125 -1769682085,653026048,0.0,-0.0,595.0460205078125 -1769682085,667531264,0.0,-0.0,595.0460205078125 -1769682085,715071488,0.0,-0.0,595.0460205078125 -1769682085,752646912,0.0,-0.0,595.0460205078125 -1769682085,767166464,0.0,-0.0,595.0460205078125 -1769682085,800109568,0.0,-0.0,595.0460205078125 -1769682085,853917952,0.0,-0.0,595.0460205078125 -1769682085,867773184,0.0,-0.0,595.0460205078125 -1769682085,901641472,0.0,-0.0,595.0460205078125 -1769682085,945278720,0.0,-0.0,595.0460205078125 -1769682085,977356800,0.0,-0.0,595.0460205078125 -1769682086,3714304,0.0,-0.0,595.0460205078125 -1769682086,45648128,0.0,-0.0,595.0460205078125 -1769682086,66493696,0.0,-0.0,595.0460205078125 -1769682086,113440512,0.0,-0.0,595.0460205078125 -1769682086,149990912,0.0,-0.0,595.0460205078125 -1769682086,168994816,0.0,-0.0,595.0460205078125 -1769682086,199829248,0.0,-0.0,595.0460205078125 -1769682086,263319040,0.0,-0.0,595.0460205078125 -1769682086,270981120,0.0,-0.0,595.0460205078125 -1769682086,300742400,0.0,-0.0,595.0460205078125 -1769682086,344598272,0.0,-0.0,595.0460205078125 -1769682086,367198208,0.0,-0.0,595.0460205078125 -1769682086,406346240,0.0,-0.0,595.0460205078125 -1769682086,452542976,0.0,-0.0,595.0460205078125 -1769682086,468201984,0.0,-0.0,595.0460205078125 -1769682086,499777792,0.0,-0.0,595.0460205078125 -1769682086,559496448,0.0,-0.0,595.0460205078125 -1769682086,575485440,0.0,-0.0,595.0460205078125 -1769682086,600046592,0.0,-0.0,595.0460205078125 -1769682086,642333184,0.0,-0.0,595.0460205078125 -1769682086,670466304,0.0,-0.0,595.0460205078125 -1769682086,701947136,0.0,-0.0,595.0460205078125 -1769682086,746746880,0.0,-0.0,595.0460205078125 -1769682086,766935296,0.0,-0.0,595.0460205078125 -1769682086,800072960,0.0,-0.0,595.0460205078125 -1769682086,847519232,0.0,-0.0,595.0460205078125 -1769682086,866787840,0.0,-0.0,595.0460205078125 -1769682086,900205312,0.0,-0.0,595.0460205078125 -1769682086,962212352,0.0,-0.0,595.0460205078125 -1769682086,968286464,0.0,-0.0,595.0460205078125 -1769682087,1990656,0.0,-0.0,595.0460205078125 -1769682087,45661440,0.0,-0.0,595.0460205078125 -1769682087,70301952,0.0,-0.0,595.0460205078125 -1769682087,101434624,0.0,-0.0,595.0460205078125 -1769682087,144342784,0.0,-0.0,595.0460205078125 -1769682087,167131904,0.0,-0.0,595.0460205078125 -1769682087,200808704,0.0,-0.0,595.0460205078125 -1769682087,242951168,0.0,-0.0,595.0460205078125 -1769682087,267593984,0.0,-0.0,595.0460205078125 -1769682087,300301568,0.0,-0.0,595.0460205078125 -1769682087,349877760,0.0,-0.0,595.0460205078125 -1769682087,369783808,0.0,-0.0,595.0460205078125 -1769682087,400265472,0.0,-0.0,595.0460205078125 -1769682087,460486144,0.0,-0.0,595.0460205078125 -1769682087,466914048,0.0,-0.0,595.0460205078125 -1769682087,501124096,0.0,-0.0,595.0460205078125 -1769682087,542052864,0.0,-0.0,595.0460205078125 -1769682087,566753024,0.0,-0.0,595.0460205078125 -1769682087,600514560,0.0,-0.0,595.0460205078125 -1769682087,646750720,0.0,-0.0,595.0460205078125 -1769682087,666792704,0.0,-0.0,595.0460205078125 -1769682087,711515392,0.0,-0.0,595.0460205078125 -1769682087,747710976,0.0,-0.0,595.0460205078125 -1769682087,768873728,0.0,-0.0,595.0460205078125 -1769682087,799913472,0.0,-0.0,595.0460205078125 -1769682087,861070848,0.0,-0.0,595.0460205078125 -1769682087,868840704,0.0,-0.0,595.0460205078125 -1769682087,901200896,0.0,-0.0,595.0460205078125 -1769682087,942525184,0.0,-0.0,595.0460205078125 -1769682087,966996736,0.0,-0.0,595.0460205078125 -1769682088,758528,0.0,-0.0,595.0460205078125 -1769682088,57256448,0.0,-0.0,595.0460205078125 -1769682088,66032640,0.0,-0.0,595.0460205078125 -1769682088,115894016,0.0,-0.0,595.0460205078125 -1769682088,143513344,0.0,-0.0,595.0460205078125 -1769682088,167181568,0.0,-0.0,595.0460205078125 -1769682088,199896064,0.0,-0.0,595.0460205078125 -1769682088,253044480,0.0,-0.0,595.0460205078125 -1769682088,266701312,0.0,-0.0,595.0460205078125 -1769682088,300723200,0.0,-0.0,595.0460205078125 -1769682088,345487104,0.0,-0.0,595.0460205078125 -1769682088,380301312,0.0,-0.0,595.0460205078125 -1769682088,400850688,0.0,-0.0,595.0460205078125 -1769682088,444826880,0.0,-0.0,595.0460205078125 -1769682088,466938368,0.0,-0.0,595.0460205078125 -1769682088,510375168,0.0,-0.0,595.0460205078125 -1769682088,550420480,0.0,-0.0,595.0460205078125 -1769682088,570011392,0.0,-0.0,595.0460205078125 -1769682088,600254720,0.0,-0.0,595.0460205078125 -1769682088,655870208,0.0,-0.0,595.0460205078125 -1769682088,670202624,0.0,-0.0,595.0460205078125 -1769682088,701188608,0.0,-0.0,595.0460205078125 -1769682088,744651520,0.0,-0.0,595.0460205078125 -1769682088,777669120,0.0,-0.0,595.0460205078125 -1769682088,800749568,0.0,-0.0,595.0460205078125 -1769682088,846280704,0.0,-0.0,595.0460205078125 -1769682088,867312896,0.0,-0.0,595.0460205078125 -1769682088,914400256,0.0,-0.0,595.0460205078125 -1769682088,946911232,0.0,-0.0,595.0460205078125 -1769682088,968318208,0.0,-0.0,595.0460205078125 -1769682089,359424,0.0,-0.0,595.0460205078125 -1769682089,59989248,0.0,-0.0,595.0460205078125 -1769682089,71097856,0.0,-0.0,595.0460205078125 -1769682089,101735424,0.0,-0.0,595.0460205078125 -1769682089,142663424,0.0,-0.0,595.0460205078125 -1769682089,168030720,0.0,-0.0,595.0460205078125 -1769682089,201004288,0.0,-0.0,595.0460205078125 -1769682089,244797184,0.0,-0.0,595.0460205078125 -1769682089,267593216,0.0,-0.0,595.0460205078125 -1769682089,299961088,0.0,-0.0,595.0460205078125 -1769682089,359496704,0.0,-0.0,595.0460205078125 -1769682089,372410880,0.0,-0.0,595.0460205078125 -1769682089,400912640,0.0,-0.0,595.0460205078125 -1769682089,443479552,0.0,-0.0,595.0460205078125 -1769682089,468326144,0.0,-0.0,595.0460205078125 -1769682089,502152448,0.0,-0.0,595.0460205078125 -1769682089,544260864,0.0,-0.0,595.0460205078125 -1769682089,577681920,0.0,-0.0,595.0460205078125 -1769682089,601679872,0.0,-0.0,595.0460205078125 -1769682089,646577152,0.0,-0.0,595.0460205078125 -1769682089,667211520,0.0,-0.0,595.0460205078125 -1769682089,712577792,0.0,-0.0,595.0460205078125 -1769682089,748062464,0.0,-0.0,595.0460205078125 -1769682089,767920384,0.0,-0.0,595.0460205078125 -1769682089,800861696,0.0,-0.0,595.0460205078125 -1769682089,858436864,0.0,-0.0,595.0460205078125 -1769682089,868858112,0.0,-0.0,595.0460205078125 -1769682089,901336320,0.0,-0.0,595.0460205078125 -1769682089,944389376,0.0,-0.0,595.0460205078125 -1769682089,967881472,0.0,-0.0,595.0460205078125 -1769682090,257280,0.0,-0.0,595.0460205078125 -1769682090,42771968,0.0,-0.0,595.0460205078125 -1769682090,67807744,0.0,-0.0,595.0460205078125 -1769682090,110488832,0.0,-0.0,595.0460205078125 -1769682090,148538368,0.0,-0.0,595.0460205078125 -1769682090,168489216,0.0,-0.0,595.0460205078125 -1769682090,200728064,0.0,-0.0,595.0460205078125 -1769682090,261348096,0.0,-0.0,595.0460205078125 -1769682090,270057472,0.0,-0.0,595.0460205078125 -1769682090,302282496,0.0,-0.0,595.0460205078125 -1769682090,345687808,0.0,-0.0,595.0460205078125 -1769682090,366953472,0.0,-0.0,595.0460205078125 -1769682090,402300160,0.0,-0.0,595.0460205078125 -1769682090,448028416,0.0,-0.0,595.0460205078125 -1769682090,468740352,0.0,-0.0,595.0460205078125 -1769682090,500964352,0.0,-0.0,595.0460205078125 -1769682090,549586688,0.0,-0.0,595.0460205078125 -1769682090,567851520,0.0,-0.0,595.0460205078125 -1769682090,601137920,0.0,-0.0,595.0460205078125 -1769682090,655128832,0.0,-0.0,595.0460205078125 -1769682090,667663104,0.0,-0.0,595.0460205078125 -1769682090,700353024,0.0,-0.0,595.0460205078125 -1769682090,746530816,0.0,-0.0,595.0460205078125 -1769682090,779245568,0.0,-0.0,595.0460205078125 -1769682090,801247744,0.0,-0.0,595.0460205078125 -1769682090,845111552,0.0,-0.0,595.0460205078125 -1769682090,867724032,0.0,-0.0,595.0460205078125 -1769682090,912970240,0.0,-0.0,595.0460205078125 -1769682090,949839616,0.0,-0.0,595.0460205078125 -1769682090,969208320,0.0,-0.0,595.0460205078125 -1769682091,702976,0.0,-0.0,595.0460205078125 -1769682091,59461376,0.0,-0.0,595.0460205078125 -1769682091,70676736,0.0,-0.0,595.0460205078125 -1769682091,102295040,0.0,-0.0,595.0460205078125 -1769682091,146952448,0.0,-0.0,595.0460205078125 -1769682091,178936064,0.0,-0.0,595.0460205078125 -1769682091,200229888,0.0,-0.0,595.0460205078125 -1769682091,247408640,0.0,-0.0,595.0460205078125 -1769682091,267329536,0.0,-0.0,595.0460205078125 -1769682091,315355136,0.0,-0.0,595.0460205078125 -1769682091,348527872,0.0,-0.0,595.0460205078125 -1769682091,367772416,0.0,-0.0,595.0460205078125 -1769682091,402522112,0.0,-0.0,595.0460205078125 -1769682091,463196672,0.0,-0.0,595.0460205078125 -1769682091,471121408,0.0,-0.0,595.0460205078125 -1769682091,501043712,0.0,-0.0,595.0460205078125 -1769682091,542918400,0.0,-0.0,595.0460205078125 -1769682091,567469824,0.0,-0.0,595.0460205078125 -1769682091,601739008,0.0,-0.0,595.0460205078125 -1769682091,644812032,0.0,-0.0,595.0460205078125 -1769682091,668060416,0.0,-0.0,595.0460205078125 -1769682091,700255232,0.0,-0.0,595.0460205078125 -1769682091,747239936,0.0,-0.0,595.0460205078125 -1769682091,767849728,0.0,-0.0,595.0460205078125 -1769682091,800330240,0.0,-0.0,595.0460205078125 -1769682091,842411520,0.0,-0.0,595.0460205078125 -1769682091,872898048,0.0,-0.0,595.0460205078125 -1769682091,902231808,0.0,-0.0,595.0460205078125 -1769682091,946402560,0.0,-0.0,595.0460205078125 -1769682091,967419392,0.0,-0.0,595.0460205078125 -1769682092,2174208,0.0,-0.0,595.0460205078125 -1769682092,48662784,0.0,-0.0,595.0460205078125 -1769682092,69630976,0.0,-0.0,595.0460205078125 -1769682092,100746240,0.0,-0.0,595.0460205078125 -1769682092,149553152,0.0,-0.0,595.0460205078125 -1769682092,168215552,0.0,-0.0,595.0460205078125 -1769682092,201261568,0.0,-0.0,595.0460205078125 -1769682092,244874752,0.0,-0.0,595.0460205078125 -1769682092,269065216,0.0,-0.0,595.0460205078125 -1769682092,301879808,0.0,-0.0,595.0460205078125 -1769682092,345524224,0.0,-0.0,595.0460205078125 -1769682092,379899136,0.0,-0.0,595.0460205078125 -1769682092,400440576,0.0,-0.0,595.0460205078125 -1769682092,445587968,0.0,-0.0,595.0460205078125 -1769682092,467280384,0.0,-0.0,595.0460205078125 -1769682092,512416768,0.0,-0.0,595.0460205078125 -1769682092,549800448,0.0,-0.0,595.0460205078125 -1769682092,568284928,0.0,-0.0,595.0460205078125 -1769682092,600460544,0.0,-0.0,595.0460205078125 -1769682092,654857984,0.0,-0.0,595.0460205078125 -1769682092,667777536,0.0,-0.0,595.0460205078125 -1769682092,701326080,0.0,-0.0,595.0460205078125 -1769682092,747479808,0.0,-0.0,595.0460205078125 -1769682092,784129024,0.0,-0.0,595.0460205078125 -1769682092,800947456,0.0,-0.0,595.0460205078125 -1769682092,846666496,0.0,-0.0,595.0460205078125 -1769682092,867120384,0.0,-0.0,595.0460205078125 -1769682092,900412672,0.0,-0.0,595.0460205078125 -1769682092,950244096,0.0,-0.0,595.0460205078125 -1769682092,968660736,0.0,-0.0,595.0460205078125 -1769682093,1161472,0.0,-0.0,595.0460205078125 -1769682093,45659136,0.0,-0.0,595.0460205078125 -1769682093,68429056,0.0,-0.0,595.0460205078125 -1769682093,101346304,0.0,-0.0,595.0460205078125 -1769682093,146858240,0.0,-0.0,595.0460205078125 -1769682093,170796032,0.0,-0.0,595.0460205078125 -1769682093,201356544,0.0,-0.0,595.0460205078125 -1769682093,244364800,0.0,-0.0,595.0460205078125 -1769682093,281857792,0.0,-0.0,595.0460205078125 -1769682093,301108736,0.0,-0.0,595.0460205078125 -1769682093,346138880,0.0,-0.0,595.0460205078125 -1769682093,367251200,0.0,-0.0,595.0460205078125 -1769682093,415964672,0.0,-0.0,595.0460205078125 -1769682093,448157952,0.0,-0.0,595.0460205078125 -1769682093,467810560,0.0,-0.0,595.0460205078125 -1769682093,502105856,0.0,-0.0,595.0460205078125 -1769682093,553842432,0.0,-0.0,595.0460205078125 -1769682093,568423424,0.0,-0.0,595.0460205078125 -1769682093,601573632,0.0,-0.0,595.0460205078125 -1769682093,649358080,0.0,-0.0,595.0460205078125 -1769682093,678871040,0.0,-0.0,595.0460205078125 -1769682093,701318912,0.0,-0.0,595.0460205078125 -1769682093,748847360,0.0,-0.0,595.0460205078125 -1769682093,767556864,0.0,-0.0,595.0460205078125 -1769682093,812131072,0.0,-0.0,595.0460205078125 -1769682093,847674624,0.0,-0.0,595.0460205078125 -1769682093,868602880,0.0,-0.0,595.0460205078125 -1769682093,901357312,0.0,-0.0,595.0460205078125 -1769682093,962885120,0.0,-0.0,595.0460205078125 -1769682093,972430848,0.0,-0.0,595.0460205078125 -1769682094,1585152,0.0,-0.0,595.0460205078125 -1769682094,47435776,0.0,-0.0,595.0460205078125 -1769682094,67964160,0.0,-0.0,595.0460205078125 -1769682094,103548416,0.0,-0.0,595.0460205078125 -1769682094,147037696,0.0,-0.0,595.0460205078125 -1769682094,167775744,0.0,-0.0,595.0460205078125 -1769682094,201607680,0.0,-0.0,595.0460205078125 -1769682094,251003904,0.0,-0.0,595.0460205078125 -1769682094,268652544,0.0,-0.0,595.0460205078125 -1769682094,301113344,0.0,-0.0,595.0460205078125 -1769682094,349791488,0.0,-0.0,595.0460205078125 -1769682094,375056384,0.0,-0.0,595.0460205078125 -1769682094,402107392,0.0,-0.0,595.0460205078125 -1769682094,444923136,0.0,-0.0,595.0460205078125 -1769682094,467968256,0.0,-0.0,595.0460205078125 -1769682094,502096896,0.0,-0.0,595.0460205078125 -1769682094,547809536,0.0,-0.0,595.0460205078125 -1769682094,568917504,0.0,-0.0,595.0460205078125 -1769682094,600631296,0.0,-0.0,595.0460205078125 -1769682094,646519552,0.0,-0.0,595.0460205078125 -1769682094,667739648,0.0,-0.0,595.0460205078125 -1769682094,703357952,0.0,-0.0,595.0460205078125 -1769682094,744399360,0.0,-0.0,595.0460205078125 -1769682094,770948608,0.0,-0.0,595.0460205078125 -1769682094,802944256,0.0,-0.0,595.0460205078125 -1769682094,845568000,0.0,-0.0,595.0460205078125 -1769682094,883061248,0.0,-0.0,595.0460205078125 -1769682094,901376768,0.0,-0.0,595.0460205078125 -1769682094,944872704,0.0,-0.0,595.0460205078125 -1769682094,967782144,0.0,-0.0,595.0460205078125 -1769682095,11738624,0.0,-0.0,595.0460205078125 -1769682095,48809728,0.0,-0.0,595.0460205078125 -1769682095,69614592,0.0,-0.0,595.0460205078125 -1769682095,100644352,0.0,-0.0,595.0460205078125 -1769682095,157391104,0.0,-0.0,595.0460205078125 -1769682095,173179136,0.0,-0.0,595.0460205078125 -1769682095,201956864,0.0,-0.0,595.0460205078125 -1769682095,246407680,0.0,-0.0,595.0460205078125 -1769682095,278473728,0.0,-0.0,595.0460205078125 -1769682095,301786880,0.0,-0.0,595.0460205078125 -1769682095,349749504,0.0,-0.0,595.0460205078125 -1769682095,367815168,0.0,-0.0,595.0460205078125 -1769682095,414122240,0.0,-0.0,595.0460205078125 -1769682095,449124864,0.0,-0.0,595.0460205078125 -1769682095,469576960,0.0,-0.0,595.0460205078125 -1769682095,500763648,0.0,-0.0,595.0460205078125 -1769682095,561742592,0.0,-0.0,595.0460205078125 -1769682095,570810624,0.0,-0.0,595.0460205078125 -1769682095,602256128,0.0,-0.0,595.0460205078125 -1769682095,642893824,0.0,-0.0,595.0460205078125 -1769682095,667728640,0.0,-0.0,595.0460205078125 -1769682095,705484032,0.0,-0.0,595.0460205078125 -1769682095,745607936,0.0,-0.0,595.0460205078125 -1769682095,767791872,0.0,-0.0,595.0460205078125 -1769682095,801393152,0.0,-0.0,595.0460205078125 -1769682095,849348864,0.0,-0.0,595.0460205078125 -1769682095,869302528,0.0,-0.0,595.0460205078125 -1769682095,900881408,0.0,-0.0,595.0460205078125 -1769682095,943066368,0.0,-0.0,595.0460205078125 -1769682095,969249792,0.0,-0.0,595.0460205078125 -1769682096,2141952,0.0,-0.0,595.0460205078125 -1769682096,45041408,0.0,-0.0,595.0460205078125 -1769682096,68201984,0.0,-0.0,595.0460205078125 -1769682096,105097728,0.0,-0.0,595.0460205078125 -1769682096,144802304,0.0,-0.0,595.0460205078125 -1769682096,168890112,0.0,-0.0,595.0460205078125 -1769682096,200909312,0.0,-0.0,595.0460205078125 -1769682096,247878912,0.0,-0.0,595.0460205078125 -1769682096,267697408,0.0,-0.0,595.0460205078125 -1769682096,301723136,0.0,-0.0,595.0460205078125 -1769682096,346430464,0.0,-0.0,595.0460205078125 -1769682096,368822528,0.0,-0.0,595.0460205078125 -1769682096,400844800,0.0,-0.0,595.0460205078125 -1769682096,448357120,0.0,-0.0,595.0460205078125 -1769682096,482990336,0.0,-0.0,595.0460205078125 -1769682096,501094912,0.0,-0.0,595.0460205078125 -1769682096,551904000,0.0,-0.0,595.0460205078125 -1769682096,567766784,0.0,-0.0,595.0460205078125 -1769682096,611592960,0.0,-0.0,595.0460205078125 -1769682096,649420288,0.0,-0.0,595.0460205078125 -1769682096,668521216,0.0,-0.0,595.0460205078125 -1769682096,701349632,0.0,-0.0,595.0460205078125 -1769682096,755279360,0.0,-0.0,595.0460205078125 -1769682096,769503488,0.0,-0.0,595.0460205078125 -1769682096,804146944,0.0,-0.0,595.0460205078125 -1769682096,846772224,0.0,-0.0,595.0460205078125 -1769682096,884144896,0.0,-0.0,595.0460205078125 -1769682096,901284352,0.0,-0.0,595.0460205078125 -1769682096,946731008,0.0,-0.0,595.0460205078125 -1769682096,968095744,0.0,-0.0,595.0460205078125 -1769682097,3885056,0.0,-0.0,595.0460205078125 -1769682097,49071872,0.0,-0.0,595.0460205078125 -1769682097,69111296,0.0,-0.0,595.0460205078125 -1769682097,101014016,0.0,-0.0,595.0460205078125 -1769682097,160533248,0.0,-0.0,595.0460205078125 -1769682097,170844928,0.0,-0.0,595.0460205078125 -1769682097,204320512,0.0,-0.0,595.0460205078125 -1769682097,242968832,0.0,-0.0,595.0460205078125 -1769682097,268383744,0.0,-0.0,595.0460205078125 -1769682097,352696576,0.0,-0.0,595.0460205078125 -1769682097,376715008,0.0,-0.0,595.0460205078125 -1769682097,403256832,0.0049320789985358715,0.002631816081702709,595.0457153320312 -1769682097,407344640,0.008216639049351215,0.0036606278736144304,595.0449829101562 -1769682097,445301248,0.020822471007704735,0.0057698399759829044,595.0416259765625 -1769682097,468347904,0.027033133432269096,0.006564016919583082,595.0399169921875 -1769682097,500918016,0.036981917917728424,0.0076746586710214615,595.0369873046875 -1769682097,550244864,0.0516270287334919,0.008916933089494705,595.0328369140625 -1769682097,568303872,0.062894307076931,0.009678525850176811,595.0294799804688 -1769682097,600920320,0.07452550530433655,0.010344527661800385,595.0262451171875 -1769682097,644671488,0.09059477597475052,0.010990619659423828,595.021728515625 -1769682097,669554432,0.1029520109295845,0.01132669672369957,595.0183715820312 -1769682097,701483776,0.11540769040584564,0.011550016701221466,595.0150756835938 -1769682097,754420480,0.13272912800312042,0.011684630066156387,595.010498046875 -1769682097,770087680,0.14578783512115479,0.011737365275621414,595.0070190429688 -1769682097,802273024,0.15920542180538177,0.01171024888753891,595.0036010742188 -1769682097,846266624,0.17718958854675293,0.011606939136981964,594.9989624023438 -1769682097,868522752,0.1909317672252655,0.011469483375549316,594.9954833984375 -1769682097,912895232,0.20489896833896637,0.011343549937009811,594.9920654296875 -1769682097,951317504,0.2244510054588318,0.011120446026325226,594.987548828125 -1769682097,970429184,0.24007059633731842,0.010999634861946106,594.9841918945312 -1769682098,1095936,0.2557103633880615,0.010856874287128448,594.9807739257812 -1769682098,62896128,0.27806758880615234,0.010717004537582397,594.9761352539062 -1769682098,70066432,0.2954789102077484,0.010609932243824005,594.9727172851562 -1769682098,102552064,0.3128618896007538,0.010485470294952393,594.9691772460938 -1769682098,144433664,0.3371620774269104,0.01036575436592102,594.9645385742188 -1769682098,168598528,0.356563001871109,0.010275378823280334,594.9610595703125 -1769682098,204949760,0.38289400935173035,0.010221593081951141,594.9562377929688 -1769682098,244752128,0.4032175540924072,0.010161414742469788,594.9525756835938 -1769682098,268771584,0.4246063530445099,0.010140478610992432,594.9488525390625 -1769682098,301198848,0.4466049373149872,0.010103955864906311,594.9449462890625 -1769682098,357329920,0.47627389430999756,0.010067105293273926,594.9395751953125 -1769682098,372897024,0.5058357119560242,0.010088860988616943,594.93408203125 -1769682098,401200384,0.5208737850189209,0.01007068157196045,594.9312133789062 -1769682098,446879744,0.5520234107971191,0.010115101933479309,594.9254150390625 -1769682098,472500224,0.5762444138526917,0.010112643241882324,594.9208374023438 -1769682098,502857728,0.6005131006240845,0.010153144598007202,594.916015625 -1769682098,546362112,0.6336164474487305,0.010229811072349548,594.9093627929688 -1769682098,568072704,0.658031165599823,0.010280370712280273,594.904052734375 -1769682098,604231168,0.6902313828468323,0.010375261306762695,594.8967895507812 -1769682098,651403008,0.7147569060325623,0.010434076189994812,594.8909912109375 -1769682098,668508416,0.7367784976959229,0.010482192039489746,594.8851318359375 -1769682098,702321664,0.7581244111061096,0.010566860437393188,594.8792724609375 -1769682098,748941056,0.7876003980636597,0.01067332923412323,594.871337890625 -1769682098,768552960,0.8112553954124451,0.010687261819839478,594.864990234375 -1769682098,801513216,0.8350254893302917,0.010577648878097534,594.8579711914062 -1769682098,850055680,0.8671908974647522,0.010465681552886963,594.8477172851562 -1769682098,882299648,0.8999540209770203,0.010342597961425781,594.8366088867188 -1769682098,902184704,0.9162105321884155,0.010274529457092285,594.830810546875 -1769682098,945991424,0.9493237137794495,0.0102195143699646,594.81884765625 -1769682098,968878336,0.9739096760749817,0.010106950998306274,594.8095703125 -1769682099,8193792,1.0059418678283691,0.010089516639709473,594.796875 -1769682099,49642752,1.0299853086471558,0.010055631399154663,594.7872314453125 -1769682099,68685568,1.0522366762161255,0.010035157203674316,594.7774658203125 -1769682099,101197056,1.0742249488830566,0.009999275207519531,594.7677001953125 -1769682099,157958400,1.1026889085769653,0.0100058913230896,594.7549438476562 -1769682099,170703104,1.1258100271224976,0.009961962699890137,594.745361328125 -1769682099,201378816,1.1490874290466309,0.00991135835647583,594.7356567382812 -1769682099,248626944,1.1809526681900024,0.009915471076965332,594.722412109375 -1769682099,269953024,1.2050083875656128,0.009861409664154053,594.71240234375 -1769682099,301219840,1.2291439771652222,0.009818673133850098,594.7024536132812 -1769682099,345339904,1.2618718147277832,0.009771913290023804,594.6890258789062 -1769682099,369197312,1.286189079284668,0.009670495986938477,594.6790161132812 -1769682099,404776192,1.3181917667388916,0.009601175785064697,594.6658935546875 -1769682099,450561024,1.3421523571014404,0.009501487016677856,594.65625 -1769682099,468618496,1.3667255640029907,0.009386062622070312,594.6467895507812 -1769682099,502465792,1.3912369012832642,0.009241193532943726,594.6375122070312 -1769682099,557707008,1.4240283966064453,0.009145617485046387,594.6253662109375 -1769682099,575600896,1.4568352699279785,0.009037405252456665,594.6135864257812 -1769682099,601224960,1.473239779472351,0.008910059928894043,594.607666015625 -1769682099,648866304,1.5062907934188843,0.008821874856948853,594.59619140625 -1769682099,671585280,1.5311124324798584,0.008687764406204224,594.5877075195312 -1769682099,702138112,1.5558031797409058,0.008557915687561035,594.5794067382812 -1769682099,745082368,1.5887391567230225,0.008415013551712036,594.5687866210938 -1769682099,768366336,1.6134248971939087,0.008197963237762451,594.5611572265625 -1769682099,805043200,1.6463834047317505,0.007985591888427734,594.5516357421875 -1769682099,848476416,1.6712499856948853,0.007754147052764893,594.545166015625 -1769682099,868908288,1.6957670450210571,0.007528066635131836,594.5391235351562 -1769682099,968993280,1.72834050655365,0.007221579551696777,594.5320434570312 -1769682099,983702528,1.760910987854004,0.006901562213897705,594.5260009765625 -1769682099,998075392,1.7771967649459839,0.006739258766174316,594.5233154296875 -1769682100,4782592,1.8089253902435303,0.006453573703765869,594.5186157226562 -1769682100,46955264,1.8414465188980103,0.006006836891174316,594.5153198242188 -1769682100,67509248,1.8578656911849976,0.005947530269622803,594.5147094726562 -1769682100,101534976,1.8826398849487305,0.0059476494789123535,594.5151977539062 -1769682100,150740736,1.9153931140899658,0.005934417247772217,594.5177001953125 -1769682100,169951488,1.9396491050720215,0.005942940711975098,594.52099609375 -1769682100,202056960,1.9637356996536255,0.0058997273445129395,594.5252075195312 -1769682100,244722944,1.9958676099777222,0.005802333354949951,594.5322875976562 -1769682100,272396032,2.0198512077331543,0.005736708641052246,594.53857421875 -1769682100,302440960,2.0437111854553223,0.005589962005615234,594.5455932617188 -1769682100,347283712,2.075336217880249,0.005287766456604004,594.5560913085938 -1769682100,368396544,2.0988540649414062,0.005075991153717041,594.5650024414062 -1769682100,404881408,2.1302671432495117,0.004683256149291992,594.5781860351562 -1769682100,444478720,2.153592824935913,0.004431188106536865,594.5889892578125 -1769682100,470222336,2.176737070083618,0.0041542649269104,594.600830078125 -1769682100,501590016,2.1998023986816406,0.0038924217224121094,594.6134033203125 -1769682100,563923200,2.2303106784820557,0.00347977876663208,594.6316528320312 -1769682100,572196608,2.252901792526245,0.0032376646995544434,594.646240234375 -1769682100,602554624,2.27506160736084,0.0028505921363830566,594.6615600585938 -1769682100,647092992,2.304507255554199,0.0018617510795593262,594.6826782226562 -1769682100,672747776,2.32635498046875,0.0011935234069824219,594.6990356445312 -1769682100,701491712,2.347964286804199,0.00048416852951049805,594.7161254882812 -1769682100,748240128,2.376702070236206,-0.0004622936248779297,594.7396850585938 -1769682100,769275648,2.398240327835083,-0.0009290575981140137,594.7582397460938 -1769682100,803454976,2.4264748096466064,-0.001671135425567627,594.7837524414062 -1769682100,844992768,2.447673797607422,-0.0020062923431396484,594.8035278320312 -1769682100,869718528,2.4688267707824707,-0.0023395419120788574,594.8240356445312 -1769682100,901328896,2.48984432220459,-0.0026891231536865234,594.84521484375 -1769682100,960475136,2.5174996852874756,-0.0032469630241394043,594.8748168945312 -1769682100,975734016,2.544877529144287,-0.0037483572959899902,594.9060668945312 -1769682101,4734464,2.565237283706665,-0.004038810729980469,594.9306030273438 -1769682101,44635392,2.585524797439575,-0.004262089729309082,594.9561767578125 -1769682101,75662848,2.6125617027282715,-0.00465768575668335,594.9915771484375 -1769682101,101708800,2.625924587249756,-0.004593789577484131,595.0099487304688 -1769682101,145141760,2.6521520614624023,-0.005278527736663818,595.04736328125 -1769682101,168491264,2.671685218811035,-0.0058730244636535645,595.0758666992188 -1769682101,204187904,2.697542190551758,-0.0069776177406311035,595.1144409179688 -1769682101,251167744,2.716792106628418,-0.0075577497482299805,595.1438598632812 -1769682101,269159168,2.7361905574798584,-0.008315622806549072,595.1737060546875 -1769682101,356330752,2.762026071548462,-0.008848905563354492,595.2141723632812 -1769682101,370320896,2.7878310680389404,-0.009052455425262451,595.255859375 -1769682101,392156160,2.806910276412964,-0.009187638759613037,595.287841796875 -1769682101,402064128,2.8195314407348633,-0.008955061435699463,595.3095703125 -1769682101,452373504,2.85107421875,-0.009431302547454834,595.3654174804688 -1769682101,467812864,2.8636579513549805,-0.009311914443969727,595.3883056640625 -1769682101,513837056,2.8824045658111572,-0.009296298027038574,595.4232788085938 -1769682101,552439808,2.907174825668335,-0.009701311588287354,595.4711303710938 -1769682101,569771776,2.925518035888672,-0.009654223918914795,595.5077514648438 -1769682101,601629440,2.943861961364746,-0.009675145149230957,595.5450439453125 -1769682101,662898944,2.9680848121643066,-0.010103702545166016,595.5955810546875 -1769682101,671115776,2.986194610595703,-0.010150790214538574,595.63427734375 -1769682101,702269440,3.0040605068206787,-0.010223567485809326,595.673583984375 -1769682101,748636672,3.028409957885742,-0.01075124740600586,595.7279052734375 -1769682101,768269056,3.04657244682312,-0.010348916053771973,595.770751953125 -1769682101,802727680,3.064631938934326,-0.00986337661743164,595.8150634765625 -1769682101,846295040,3.088637590408325,-0.009733736515045166,595.8759765625 -1769682101,869854720,3.106538772583008,-0.009295284748077393,595.922607421875 -1769682101,903175936,3.1301681995391846,-0.009233534336090088,595.98583984375 -1769682101,949105920,3.1478614807128906,-0.00889497995376587,596.0337524414062 -1769682101,970693120,3.165479898452759,-0.008623182773590088,596.0820922851562 -1769682102,1969152,3.182934284210205,-0.008436083793640137,596.1309204101562 -1769682102,63012864,3.206088066101074,-0.008794128894805908,596.1966552734375 -1769682102,71179520,3.223187208175659,-0.008657217025756836,596.2463989257812 -1769682102,103645696,3.2400565147399902,-0.00907433032989502,596.2962036132812 -1769682102,147812352,3.262444257736206,-0.010438680648803711,596.36279296875 -1769682102,168657920,3.2790069580078125,-0.011075258255004883,596.4130249023438 -1769682102,207585280,3.3010129928588867,-0.012391984462738037,596.4804077148438 -1769682102,249701120,3.3173511028289795,-0.012859225273132324,596.5313720703125 -1769682102,268774400,3.3335394859313965,-0.013227641582489014,596.5826416015625 -1769682102,302523904,3.349606513977051,-0.013454020023345947,596.63427734375 -1769682102,358572288,3.3708293437957764,-0.014299929141998291,596.7034301757812 -1769682102,372578816,3.3865318298339844,-0.01417684555053711,596.7556762695312 -1769682102,403827712,3.4073305130004883,-0.01503676176071167,596.8256225585938 -1769682102,444911104,3.4227380752563477,-0.01498568058013916,596.8783569335938 -1769682102,474463232,3.4382011890411377,-0.01460939645767212,596.9314575195312 -1769682102,501912320,3.4537460803985596,-0.01340484619140625,596.985595703125 -1769682102,555235840,3.4743356704711914,-0.011892199516296387,597.0592651367188 -1769682102,568701184,3.4896841049194336,-0.010506749153137207,597.1152954101562 -1769682102,602677504,3.5050320625305176,-0.00860607624053955,597.1715087890625 -1769682102,649789952,3.5251667499542236,-0.006827116012573242,597.246337890625 -1769682102,671535616,3.5400679111480713,-0.0050743818283081055,597.3024291992188 -1769682102,701983744,3.5547354221343994,-0.0038105249404907227,597.3587036132812 -1769682102,750961920,3.574009895324707,-0.0031620264053344727,597.4343872070312 -1769682102,768453888,3.5883195400238037,-0.002487659454345703,597.491943359375 -1769682102,801749504,3.6023240089416504,-0.001974344253540039,597.5504150390625 -1769682102,846136576,3.620668411254883,-0.002278566360473633,597.6298828125 -1769682102,874187008,3.638786554336548,-0.0024547576904296875,597.7106323242188 -1769682102,902550528,3.647622585296631,-0.001816391944885254,597.7514038085938 -1769682102,945885952,3.6645514965057373,-0.002247333526611328,597.8329467773438 -1769682102,968980992,3.676791191101074,-0.003084897994995117,597.8923950195312 -1769682103,3712256,3.6927483081817627,-0.0055915117263793945,597.9691772460938 -1769682103,47422720,3.704408645629883,-0.00689244270324707,598.0255126953125 -1769682103,69015552,3.715794563293457,-0.007888197898864746,598.0810546875 -1769682103,102829568,3.727091073989868,-0.008797287940979004,598.1356201171875 -1769682103,147860736,3.74176025390625,-0.010411500930786133,598.2071533203125 -1769682103,168784128,3.7525274753570557,-0.010937929153442383,598.2600708007812 -1769682103,201679104,3.762913703918457,-0.011388301849365234,598.3129272460938 -1769682103,244682240,3.7768795490264893,-0.012661337852478027,598.3843994140625 -1769682103,272453888,3.7875585556030273,-0.01182699203491211,598.44091796875 -1769682103,303179008,3.798072099685669,-0.01092541217803955,598.5006713867188 -1769682103,345483008,3.8116745948791504,-0.010236620903015137,598.5852661132812 -1769682103,369423616,3.8216543197631836,-0.0089263916015625,598.6517944335938 -1769682103,403687936,3.834772825241089,-0.008031845092773438,598.7428588867188 -1769682103,447930368,3.844386100769043,-0.0067147016525268555,598.8118286132812 -1769682103,469390848,3.853752374649048,-0.005372166633605957,598.8804931640625 -1769682103,502110464,3.862870931625366,-0.004178762435913086,598.9484252929688 -1769682103,550083072,3.874800682067871,-0.00371551513671875,599.0375366210938 -1769682103,569511424,3.8834915161132812,-0.0029453039169311523,599.103271484375 -1769682103,601851904,3.892157554626465,-0.002371668815612793,599.1685180664062 -1769682103,645400576,3.9033663272857666,-0.0026110410690307617,599.2550659179688 -1769682103,672011264,3.9108662605285645,-0.001653909683227539,599.3199462890625 -1769682103,702832128,3.917973041534424,-0.0021867752075195312,599.3853149414062 -1769682103,749979904,3.927135467529297,-0.0042684078216552734,599.472412109375 -1769682103,768527360,3.933896064758301,-0.005161762237548828,599.5376586914062 -1769682103,815198720,3.9404170513153076,-0.005935311317443848,599.6026611328125 -1769682103,852962560,3.9511256217956543,-0.008099079132080078,599.7105102539062 -1769682103,868480512,3.9553067684173584,-0.007988452911376953,599.7532958984375 -1769682103,901628928,3.961439609527588,-0.008165240287780762,599.8169555664062 -1769682103,958757632,3.9694294929504395,-0.009033560752868652,599.900634765625 -1769682103,966950144,3.975208044052124,-0.009063959121704102,599.9623413085938 -1769682104,5162240,3.980961799621582,-0.008535504341125488,600.023193359375 -1769682104,46654464,3.9883315563201904,-0.009008049964904785,600.10302734375 -1769682104,69804544,3.9937896728515625,-0.008572578430175781,600.162353515625 -1769682104,102163712,3.999180555343628,-0.00833439826965332,600.2213134765625 -1769682104,147991808,4.006170272827148,-0.008785843849182129,600.2999267578125 -1769682104,168426752,4.011309623718262,-0.008516073226928711,600.3591918945312 -1769682104,216006400,4.016340732574463,-0.008229732513427734,600.4188232421875 -1769682104,249928448,4.022889137268066,-0.008677005767822266,600.4989624023438 -1769682104,270161408,4.027659893035889,-0.008242487907409668,600.5592041015625 -1769682104,301925120,4.032520294189453,-0.007786273956298828,600.6193237304688 -1769682104,360555776,4.038869857788086,-0.0080183744430542,600.6989135742188 -1769682104,376667904,4.0449652671813965,-0.008032560348510742,600.7777709960938 -1769682104,404307712,4.04794454574585,-0.007176756858825684,600.8169555664062 -1769682104,448367616,4.053806781768799,-0.007527709007263184,600.8950805664062 -1769682104,481032960,4.058073043823242,-0.007168769836425781,600.9535522460938 -1769682104,502182656,4.062269687652588,-0.006783962249755859,601.0117797851562 -1769682104,544851968,4.067636966705322,-0.00716555118560791,601.0889892578125 -1769682104,569247488,4.071478843688965,-0.006773471832275391,601.1466064453125 -1769682104,613851392,4.075328826904297,-0.006405234336853027,601.2037963867188 -1769682104,651973888,4.080390930175781,-0.0067996978759765625,601.279541015625 -1769682104,673050112,4.084068775177002,-0.0063419342041015625,601.3363037109375 -1769682104,702175232,4.08763313293457,-0.006184935569763184,601.3929443359375 -1769682104,759228416,4.092249870300293,-0.006553292274475098,601.4685668945312 -1769682104,769324288,4.0955810546875,-0.006520986557006836,601.525390625 -1769682104,804167424,4.09880256652832,-0.006063342094421387,601.5822143554688 -1769682104,847000064,4.102931976318359,-0.006557106971740723,601.65771484375 -1769682104,870349056,4.105965614318848,-0.006254792213439941,601.7144775390625 -1769682104,902342912,4.10892915725708,-0.006096601486206055,601.7713012695312 -1769682104,946942464,4.112699508666992,-0.006624102592468262,601.8471069335938 -1769682104,969561344,4.115443229675293,-0.006347537040710449,601.9041137695312 -1769682105,12832000,4.118062973022461,-0.00614321231842041,601.9611206054688 -1769682105,52893440,4.121480464935303,-0.006625056266784668,602.0369262695312 -1769682105,70082560,4.12391996383667,-0.006360888481140137,602.0935668945312 -1769682105,105355776,4.127076148986816,-0.006891965866088867,602.1690063476562 -1769682105,160634112,4.129350185394287,-0.006752371788024902,602.2255249023438 -1769682105,169379584,4.131510257720947,-0.006752371788024902,602.2822875976562 -1769682105,203916544,4.133586406707764,-0.006486415863037109,602.3396606445312 -1769682105,248472320,4.136188507080078,-0.007196903228759766,602.416748046875 -1769682105,269719552,4.138103485107422,-0.0070111751556396484,602.4750366210938 -1769682105,303150336,4.140020847320557,-0.006777048110961914,602.53369140625 -1769682105,348079360,4.142515182495117,-0.0073157548904418945,602.6119995117188 -1769682105,368669952,4.144261360168457,-0.007027029991149902,602.6708984375 -1769682105,412418816,4.145978927612305,-0.0067490339279174805,602.7297973632812 -1769682105,448598784,4.148170471191406,-0.0072672367095947266,602.8085327148438 -1769682105,470086144,4.149669647216797,-0.0069353580474853516,602.8676147460938 -1769682105,502299904,4.151121616363525,-0.0065767765045166016,602.9265747070312 -1769682105,560584704,4.152917385101318,-0.0069460272789001465,603.0046997070312 -1769682105,566907136,4.154232501983643,-0.006782174110412598,603.0628662109375 -1769682105,602236160,4.155481815338135,-0.006157040596008301,603.1205444335938 -1769682105,645720832,4.157147407531738,-0.00638502836227417,603.196533203125 -1769682105,669733888,4.158300876617432,-0.006119906902313232,603.2530517578125 -1769682105,704808192,4.1594061851501465,-0.005563199520111084,603.3090209960938 -1769682105,746145280,4.1608171463012695,-0.005885183811187744,603.3832397460938 -1769682105,769086720,4.161767482757568,-0.005500733852386475,603.4384765625 -1769682105,802238464,4.162679672241211,-0.005125939846038818,603.493408203125 -1769682105,848857600,4.1637864112854,-0.0054852962493896484,603.5663452148438 -1769682105,868945920,4.164580821990967,-0.005120038986206055,603.6206665039062 -1769682105,914379264,4.16533899307251,-0.0047553181648254395,603.6746826171875 -1769682105,946623744,4.166254043579102,-0.005093216896057129,603.7459716796875 -1769682105,971231232,4.1668925285339355,-0.004739582538604736,603.7989501953125 -1769682106,2177280,4.167471408843994,-0.0044155120849609375,603.8516235351562 -1769682106,59700736,4.1681318283081055,-0.004772663116455078,603.9212036132812 -1769682106,68552192,4.168501853942871,-0.004694938659667969,603.9730834960938 -1769682106,104032768,4.168850421905518,-0.004236817359924316,604.0247192382812 -1769682106,149748480,4.169210433959961,-0.004743516445159912,604.0934448242188 -1769682106,169342464,4.169436931610107,-0.004545331001281738,604.1449584960938 -1769682106,202404096,4.169583797454834,-0.004337608814239502,604.1966552734375 -1769682106,244774144,4.169707775115967,-0.004899859428405762,604.2657470703125 -1769682106,270096640,4.169785499572754,-0.004686832427978516,604.3177490234375 -1769682106,311314432,4.1698689460754395,-0.004431247711181641,604.3697509765625 -1769682106,347475968,4.169906139373779,-0.004825711250305176,604.4391479492188 -1769682106,369283328,4.169814109802246,-0.004512190818786621,604.4910888671875 -1769682106,402232320,4.169704914093018,-0.004176735877990723,604.5428466796875 -1769682106,448170496,4.169504642486572,-0.004535198211669922,604.6115112304688 -1769682106,468888064,4.169397354125977,-0.004226028919219971,604.6627807617188 -1769682106,502027008,4.169130802154541,-0.003908216953277588,604.7137451171875 -1769682106,549248000,4.168745994567871,-0.004254698753356934,604.781494140625 -1769682106,572547840,4.168410301208496,-0.003740847110748291,604.8319091796875 -1769682106,603419392,4.168686389923096,-0.0032554268836975098,604.8822021484375 -1769682106,644678912,4.169469356536865,-0.00045734643936157227,604.951171875 -1769682106,669359616,4.170021057128906,0.0026813149452209473,605.0043334960938 -1769682106,703251200,4.170641899108887,0.005787074565887451,605.0763549804688 -1769682106,748047104,4.171043395996094,0.00838172435760498,605.130859375 -1769682106,769116160,4.171450614929199,0.010606944561004639,605.1859741210938 -1769682106,802766848,4.171756744384766,0.012452661991119385,605.2415161132812 -1769682106,850893056,4.172121524810791,0.013475120067596436,605.3165283203125 -1769682106,868869632,4.1722822189331055,0.014549314975738525,605.3734741210938 -1769682106,903162624,4.172410488128662,0.01539069414138794,605.4307250976562 -1769682106,945928448,4.172492504119873,0.01531982421875,605.5075073242188 -1769682111,449065984,0.0,-0.0,609.9276123046875 -1769682111,469393920,0.0,-0.0,609.9276123046875 -1769682111,507856640,0.0,-0.0,609.9276123046875 -1769682111,550883328,0.0,-0.0,609.9276123046875 -1769682111,569635584,0.0,-0.0,609.9276123046875 -1769682111,602757888,0.0,-0.0,609.9276123046875 -1769682111,653416448,0.0,-0.0,609.9276123046875 -1769682111,674659840,0.0,-0.0,609.9276123046875 -1769682111,707428352,0.0,-0.0,609.9276123046875 -1769682111,749065728,0.0,-0.0,609.9276123046875 -1769682111,779393024,0.0,-0.0,609.9276123046875 -1769682111,803398400,0.0,-0.0,609.9276123046875 -1769682111,850230272,0.0,-0.0,609.9276123046875 -1769682111,869469184,0.0,-0.0,609.9276123046875 -1769682111,904924160,0.0,-0.0,609.9276123046875 -1769682111,945897728,0.0,-0.0,609.9276123046875 -1769682111,969608192,0.0,-0.0,609.9276123046875 -1769682112,2809088,0.0,-0.0,609.9276123046875 -1769682112,53695232,0.0,-0.0,609.9276123046875 -1769682112,68948224,0.0,-0.0,609.9276123046875 -1769682112,102731776,0.0,-0.0,609.9276123046875 -1769682112,148591360,0.0,-0.0,609.9276123046875 -1769682112,173492736,0.0,-0.0,609.9276123046875 -1769682112,203752960,0.0,-0.0,609.9276123046875 -1769682112,248101888,0.0,-0.0,609.9276123046875 -1769682112,269510656,0.0,-0.0,609.9276123046875 -1769682112,305878528,0.0,-0.0,609.9276123046875 -1769682112,352089856,0.0,-0.0,609.9276123046875 -1769682112,371784960,0.0,-0.0,609.9276123046875 -1769682112,404763392,0.0,-0.0,609.9276123046875 -1769682112,447222272,0.0,-0.0,609.9276123046875 -1769682112,472760064,0.0,-0.0,609.9276123046875 -1769682112,504577792,0.0,-0.0,609.9276123046875 -1769682112,562524928,0.0,-0.0,609.9276123046875 -1769682112,570624000,0.021425053477287292,0.0048261526972055435,609.92529296875 -1769682112,603703040,0.05003639683127403,0.00824767630547285,609.9141845703125 -1769682112,646364160,0.07148133218288422,0.010499061085283756,609.903076171875 -1769682112,669923840,0.09293576329946518,0.012607511132955551,609.8916625976562 -1769682112,706390528,0.12158535420894623,0.015178972855210304,609.8779907226562 -1769682112,747114752,0.14326530694961548,0.016852721571922302,609.8693237304688 -1769682112,769897984,0.1648426353931427,0.018287185579538345,609.862060546875 -1769682112,803926272,0.19422240555286407,0.019790515303611755,609.854248046875 -1769682112,863863296,0.21630825102329254,0.020627260208129883,609.8494262695312 -1769682112,870029312,0.2392732948064804,0.021214686334133148,609.8450927734375 -1769682112,904009216,0.27075839042663574,0.021630726754665375,609.8397827148438 -1769682112,949665024,0.29531702399253845,0.021677739918231964,609.8360595703125 -1769682112,980986112,0.33025839924812317,0.02148391306400299,609.8311767578125 -1769682113,5756928,0.3561897575855255,0.021173037588596344,609.8279418945312 -1769682113,47343616,0.3832135498523712,0.02073352038860321,609.8251342773438 -1769682113,70828288,0.4108126163482666,0.020229697227478027,609.8228759765625 -1769682113,103871232,0.44889259338378906,0.019443854689598083,609.8212890625 -1769682113,152328960,0.47944578528404236,0.018803566694259644,609.8212280273438 -1769682113,170334208,0.5105106830596924,0.018095962703227997,609.8223266601562 -1769682113,203311616,0.5522214770317078,0.0171356201171875,609.825927734375 -1769682113,247476992,0.5839729309082031,0.01642581820487976,609.8304443359375 -1769682113,270371584,0.6169818639755249,0.01569991558790207,609.8364868164062 -1769682113,304508672,0.6619585752487183,0.014707103371620178,609.8472290039062 -1769682113,348187136,0.6960873007774353,0.014016866683959961,609.8572387695312 -1769682113,372208384,0.7297147512435913,0.013333573937416077,609.8690795898438 -1769682113,404450048,0.7748191356658936,0.012435615062713623,609.8876342773438 -1769682113,450283776,0.8091893196105957,0.011827558279037476,609.9034423828125 -1769682113,487960064,0.8535206317901611,0.011037439107894897,609.927001953125 -1769682113,513764096,0.8840944766998291,0.010555177927017212,609.9464721679688 -1769682113,546820608,0.9231767058372498,0.009989261627197266,609.9747314453125 -1769682113,569763840,0.9419249296188354,0.009804919362068176,609.9896850585938 -1769682113,604323328,0.9775552153587341,0.009323596954345703,610.0211181640625 -1769682113,651694080,1.002842903137207,0.009065717458724976,610.0459594726562 -1769682113,671136768,1.0319310426712036,0.008803680539131165,610.071533203125 -1769682113,703904512,1.072313904762268,0.008375152945518494,610.106201171875 -1769682113,752578048,1.1025687456130981,0.0080748051404953,610.1322021484375 -1769682113,776719872,1.1429942846298218,0.007401004433631897,610.1676025390625 -1769682113,803174656,1.1733438968658447,0.006872877478599548,610.1951904296875 -1769682113,851142144,1.20396888256073,0.006389141082763672,610.2241821289062 -1769682113,870157824,1.2349035739898682,0.0059130191802978516,610.2544555664062 -1769682113,905911296,1.275935411453247,0.005257055163383484,610.2967529296875 -1769682113,952868864,1.3068403005599976,0.004999563097953796,610.3297119140625 -1769682113,971589888,1.3378669023513794,0.004851087927818298,610.3634033203125 -1769682114,3428096,1.3792940378189087,0.004641667008399963,610.4085083007812 -1769682114,50317056,1.410713791847229,0.004727691411972046,610.4423217773438 -1769682114,71926016,1.4420069456100464,0.004998624324798584,610.4755249023438 -1769682114,103549952,1.4836273193359375,0.005227208137512207,610.5184936523438 -1769682114,146616576,1.5147194862365723,0.005729883909225464,610.5494995117188 -1769682114,174196480,1.5559993982315063,0.006268620491027832,610.5892333984375 -1769682114,205190400,1.5870829820632935,0.006675034761428833,610.61767578125 -1769682114,246671616,1.618085503578186,0.007137179374694824,610.6449584960938 -1769682114,282744320,1.6486736536026,0.0076257288455963135,610.6709594726562 -1769682114,303340544,1.6890077590942383,0.008074909448623657,610.7037353515625 -1769682114,346945792,1.7192975282669067,0.00854039192199707,610.72705078125 -1769682114,370027008,1.7496012449264526,0.008965551853179932,610.749267578125 -1769682114,403770624,1.7896137237548828,0.009403526782989502,610.7772827148438 -1769682114,446867456,1.8195483684539795,0.00983467698097229,610.797119140625 -1769682114,470970880,1.8493553400039673,0.010199248790740967,610.8160400390625 -1769682114,503507456,1.8887420892715454,0.010419219732284546,610.8399658203125 -1769682114,571137024,1.9181939363479614,0.010602682828903198,610.8572998046875 -1769682114,580840704,1.9571043252944946,0.010637789964675903,610.8802490234375 -1769682114,604333568,1.9860235452651978,0.01065528392791748,610.8973999023438 -1769682114,648685312,2.014747142791748,0.010728508234024048,610.9146118164062 -1769682114,670760960,2.0437021255493164,0.01084926724433899,610.931640625 -1769682114,708379392,2.0820467472076416,0.01095321774482727,610.9537963867188 -1769682114,752989952,2.110621452331543,0.011254489421844482,610.969482421875 -1769682114,771250688,2.138838291168213,0.01162499189376831,610.9841918945312 -1769682114,804359168,2.176272392272949,0.011926740407943726,611.0018310546875 -1769682114,847866880,2.2042598724365234,0.012405365705490112,611.0140380859375 -1769682114,871052288,2.2323474884033203,0.013044595718383789,611.0256958007812 -1769682114,905084416,2.269252300262451,0.01386973261833191,611.0399169921875 -1769682114,947174912,2.2967350482940674,0.014554470777511597,611.0494384765625 -1769682114,977465856,2.3331258296966553,0.01529201865196228,611.0606689453125 -1769682115,3199488,2.360161542892456,0.01576453447341919,611.068115234375 -1769682115,46818048,2.3870184421539307,0.01613214612007141,611.074951171875 -1769682115,70818816,2.4136345386505127,0.01638185977935791,611.0814819335938 -1769682115,104999680,2.4489293098449707,0.016558945178985596,611.090087890625 -1769682115,145208576,2.4751131534576416,0.016699641942977905,611.0965576171875 -1769682115,172675072,2.501270294189453,0.016835898160934448,611.1029663085938 -1769682115,204979968,2.5357236862182617,0.0169600248336792,611.111083984375 -1769682115,252291328,2.570006847381592,0.016846299171447754,611.1181030273438 -1769682115,269665792,2.586911916732788,0.016703754663467407,611.1207885742188 -1769682115,304941056,2.620558500289917,0.016286522150039673,611.124267578125 -1769682115,363435008,2.6456005573272705,0.01603102684020996,611.1253662109375 -1769682115,371908608,2.6703786849975586,0.015817254781723022,611.1256103515625 -1769682115,404556544,2.703157901763916,0.015582293272018433,611.1243896484375 -1769682115,448133120,2.7275216579437256,0.015441209077835083,611.12255859375 -1769682115,470009856,2.7517783641815186,0.015311896800994873,611.1202392578125 -1769682115,504098304,2.7837438583374023,0.01525142788887024,611.1165161132812 -1769682115,549628160,2.807427406311035,0.015218198299407959,611.1133422851562 -1769682115,572309504,2.830930233001709,0.015243947505950928,611.1098022460938 -1769682115,605186560,2.861807346343994,0.015413731336593628,611.1045532226562 -1769682115,653767424,2.8921937942504883,0.015568375587463379,611.0985107421875 -1769682115,670268160,2.9072792530059814,0.015598893165588379,611.09521484375 -1769682115,704889600,2.9368503093719482,0.015748411417007446,611.0882568359375 -1769682115,762705152,2.9588725566864014,0.015895307064056396,611.0827026367188 -1769682115,771343104,2.980652332305908,0.016026794910430908,611.0769653320312 -1769682115,803847424,3.0091938972473145,0.01626753807067871,611.0691528320312 -1769682115,846062080,3.030308961868286,0.01633542776107788,611.063232421875 -1769682115,870034944,3.051267147064209,0.016368210315704346,611.0573120117188 -1769682115,903709952,3.079167366027832,0.0164528489112854,611.0493774414062 -1769682115,947576320,3.099843740463257,0.016754746437072754,611.0433959960938 -1769682115,969684480,3.1204490661621094,0.017122089862823486,611.037353515625 -1769682116,6615552,3.147494316101074,0.017660140991210938,611.0289916992188 -1769682116,48478208,3.1675097942352295,0.01798689365386963,611.0223388671875 -1769682116,70466560,3.1872432231903076,0.018299520015716553,611.0151977539062 -1769682116,105127424,3.213179588317871,0.018727540969848633,611.0050659179688 -1769682116,149552384,3.2325055599212646,0.01889413595199585,610.9970703125 -1769682116,171353344,3.2515716552734375,0.01900261640548706,610.9888305664062 -1769682116,204036608,3.276580333709717,0.019138336181640625,610.977783203125 -1769682116,249876736,3.2951440811157227,0.019091546535491943,610.9696044921875 -1769682116,276459264,3.319565534591675,0.01908111572265625,610.9590454101562 -1769682116,303916800,3.3376686573028564,0.018984317779541016,610.9512939453125 -1769682116,348371712,3.355445623397827,0.018862009048461914,610.9434814453125 -1769682116,370183936,3.373098611831665,0.018731892108917236,610.9357299804688 -1769682116,404537600,3.3961856365203857,0.018688499927520752,610.9253540039062 -1769682116,452494080,3.413384199142456,0.018572628498077393,610.91748046875 -1769682116,471294208,3.430208921432495,0.01846003532409668,610.9096069335938 -1769682116,503266816,3.452479600906372,0.018388330936431885,610.8992309570312 -1769682116,552809984,3.46885085105896,0.0182497501373291,610.8916625976562 -1769682116,572253952,3.4845683574676514,0.018041372299194336,610.88427734375 -1769682116,604905728,3.5053296089172363,0.01805579662322998,610.874755859375 -1769682116,646738688,3.5206573009490967,0.017988383769989014,610.867919921875 -1769682116,676145152,3.540928840637207,0.01801055669784546,610.8589477539062 -1769682116,705147904,3.5558269023895264,0.018005311489105225,610.852294921875 -1769682116,753984256,3.5704712867736816,0.017956018447875977,610.8457641601562 -1769682116,770739200,3.5849173069000244,0.01789158582687378,610.8392333984375 -1769682116,803742976,3.6039865016937256,0.017901837825775146,610.8309326171875 -1769682116,849053440,3.618004560470581,0.017851948738098145,610.8248901367188 -1769682116,871011328,3.6317298412323,0.01779782772064209,610.819091796875 -1769682116,903371008,3.649094343185425,0.01760256290435791,610.8116455078125 -1769682116,950181120,3.661691904067993,0.017311573028564453,610.806396484375 -1769682116,975261184,3.674178123474121,0.016985714435577393,610.8011474609375 -1769682117,3959808,3.6904706954956055,0.016624271869659424,610.7941284179688 -1769682117,48541440,3.7025270462036133,0.016287505626678467,610.7888793945312 -1769682117,70566656,3.7144668102264404,0.015987694263458252,610.7838745117188 -1769682117,105230592,3.7300198078155518,0.015566825866699219,610.7774047851562 -1769682117,147080448,3.741469621658325,0.015249073505401611,610.772705078125 -1769682117,173295360,3.7566590309143066,0.0149727463722229,610.7667236328125 -1769682117,204511232,3.767854928970337,0.014792859554290771,610.762451171875 -1769682117,252366080,3.778834104537964,0.014644980430603027,610.7581176757812 -1769682117,270141696,3.789649486541748,0.014568746089935303,610.7539672851562 -1769682117,304258816,3.8037729263305664,0.014567852020263672,610.7483520507812 -1769682117,347211008,3.817661762237549,0.01454848051071167,610.7427368164062 -1769682117,370066432,3.8245179653167725,0.014504432678222656,610.7399291992188 -1769682117,405319680,3.838287591934204,0.014627635478973389,610.734619140625 -1769682117,459938048,3.8484315872192383,0.014876246452331543,610.731201171875 -1769682117,470240256,3.8583383560180664,0.01517486572265625,610.7282104492188 -1769682117,503837184,3.871425151824951,0.015571296215057373,610.724609375 -1769682117,545793792,3.8810415267944336,0.015825390815734863,610.721923828125 -1769682117,584605952,3.890632390975952,0.016046762466430664,610.7194213867188 -1769682117,604612096,3.903174638748169,0.016358673572540283,610.7159423828125 -1769682117,652919808,3.9117305278778076,0.016417503356933594,610.7131958007812 -1769682117,672007680,3.919809103012085,0.016254961490631104,610.7102661132812 -1769682117,703436032,3.9304418563842773,0.015915751457214355,610.7061157226562 -1769682117,753771264,3.9382615089416504,0.01557457447052002,610.702880859375 -1769682117,770730496,3.9458906650543213,0.015239357948303223,610.69970703125 -1769682117,804495104,3.9560985565185547,0.014868617057800293,610.6953125 -1769682117,866350592,3.9635653495788574,0.01458972692489624,610.6919555664062 -1769682117,877377792,3.9733948707580566,0.014292895793914795,610.6875 -1769682117,905881344,3.9805095195770264,0.014127671718597412,610.68408203125 -1769682117,950708480,3.9883763790130615,0.014010965824127197,610.6806640625 -1769682117,973591296,3.999324083328247,0.013902425765991211,610.6765747070312 -1769682118,8182784,4.007424831390381,0.013837158679962158,610.6739501953125 -1769682118,50194688,4.015482425689697,0.013789713382720947,610.6714477539062 -1769682118,74782208,4.023419380187988,0.01377558708190918,610.6691284179688 -1769682118,103597056,4.03406286239624,0.013797104358673096,610.6661987304688 -1769682118,168907264,4.04187536239624,0.013959348201751709,610.6641845703125 -1769682118,177031680,4.051950454711914,0.014303624629974365,610.6616821289062 -1769682118,203411456,4.05948543548584,0.014501512050628662,610.6600341796875 -1769682118,246632448,4.0669755935668945,0.014685451984405518,610.6585083007812 -1769682118,273766656,4.074259281158447,0.014818012714385986,610.6572265625 -1769682118,306194688,4.083858013153076,0.015019416809082031,610.6557006835938 -1769682118,347968512,4.09087610244751,0.01511847972869873,610.6547241210938 -1769682118,370217984,4.0977373123168945,0.015160977840423584,610.6536865234375 -1769682118,405861120,4.106701850891113,0.015238046646118164,610.6522216796875 -1769682118,448521728,4.113256931304932,0.015259802341461182,610.6513061523438 -1769682118,471012352,4.119734287261963,0.015245974063873291,610.6502685546875 -1769682118,503945216,4.128117084503174,0.01525568962097168,610.6488647460938 -1769682118,552830976,4.134304046630859,0.01522129774093628,610.6478271484375 -1769682118,570908928,4.140346527099609,0.01517939567565918,610.6467895507812 -1769682118,603938304,4.148255825042725,0.015170753002166748,610.6455078125 -1769682118,639926784,4.155272960662842,0.01514136791229248,610.64453125 -1769682118,671971584,4.1605987548828125,0.015068233013153076,610.6434326171875 -1769682118,704856320,4.166319370269775,0.015014410018920898,610.6420288085938 -1769682118,749539840,4.16876745223999,0.01499241590499878,610.6410522460938 -1769682118,781201152,4.174831390380859,0.01500612497329712,610.6401977539062 -1769682118,804487424,4.183836460113525,0.01504373550415039,610.6386108398438 -1769682118,850705408,4.190345287322998,0.015064001083374023,610.6373901367188 -1769682118,870364672,4.196753025054932,0.015098810195922852,610.6359252929688 -1769682118,904421120,4.205183982849121,0.015210509300231934,610.6339721679688 -1769682118,954224640,4.213500499725342,0.015298724174499512,610.6320190429688 -1769682118,970219520,4.217624187469482,0.015323519706726074,610.6309814453125 -1769682119,5037312,4.225666522979736,0.01538914442062378,610.628662109375 -1769682119,62780416,4.231413841247559,0.015418648719787598,610.6268310546875 -1769682119,70699008,4.235772609710693,0.015434026718139648,610.6249389648438 -1769682119,104476672,4.238792419433594,0.015448510646820068,610.6227416992188 -1769682119,148323072,4.242648601531982,0.015443801879882812,610.6212768554688 -1769682119,170119680,4.247612476348877,0.01533198356628418,610.619873046875 -1769682119,203844608,4.253958702087402,0.015174150466918945,610.618408203125 -1769682119,249590784,4.258516311645508,0.015031158924102783,610.6177978515625 -1769682119,270140416,4.262829303741455,0.01496046781539917,610.6176147460938 -1769682119,306027264,4.268542766571045,0.014906108379364014,610.61767578125 -1769682119,354000640,4.272590637207031,0.014915525913238525,610.6177978515625 -1769682119,372575232,4.276436805725098,0.014921247959136963,610.6179809570312 -1769682119,404311552,4.281325340270996,0.014949262142181396,610.6179809570312 -1769682119,454426368,4.2848734855651855,0.01498103141784668,610.6177978515625 -1769682119,471689728,4.288064479827881,0.01499718427658081,610.6176147460938 -1769682119,506781184,4.292318344116211,0.015002191066741943,610.6171875 -1769682119,547053056,4.295262813568115,0.014971733093261719,610.6170654296875 -1769682119,575538688,4.299244403839111,0.014943599700927734,610.6170654296875 -1769682119,603784192,4.302140235900879,0.01488727331161499,610.6172485351562 -1769682119,648208384,4.304839134216309,0.014848530292510986,610.61767578125 -1769682119,670841344,4.307455539703369,0.014786243438720703,610.6183471679688 -1769682119,705368064,4.310708999633789,0.014740526676177979,610.6195678710938 -1769682119,753122560,4.3130412101745605,0.014738082885742188,610.62060546875 -1769682119,772725760,4.31521463394165,0.01435542106628418,610.6220703125 -1769682119,805215488,4.318002223968506,0.014263331890106201,610.6255493164062 -1769682119,851597312,4.320021152496338,0.014011204242706299,610.6290893554688 -1769682119,872386816,4.321968078613281,0.013895034790039062,610.6336059570312 -1769682119,903763456,4.324450492858887,0.013662219047546387,610.6409301757812 -1769682119,953793280,4.326163291931152,0.01360940933227539,610.64697265625 -1769682119,972156672,4.3278021812438965,0.013538718223571777,610.6535034179688 -1769682120,3976192,4.329811096191406,0.013401389122009277,610.662353515625 -1769682120,47217664,4.331236362457275,0.01340174674987793,610.6690673828125 -1769682120,72975616,4.332493305206299,0.013434231281280518,610.6759033203125 -1769682120,105982464,4.334102630615234,0.013376414775848389,610.684814453125 -1769682120,153630976,4.335206508636475,0.013463914394378662,610.6912841796875 -1769682120,171102976,4.3361616134643555,0.01354140043258667,610.6976928710938 -1769682120,204411136,4.337342739105225,0.013540565967559814,610.705810546875 -1769682120,251578112,4.3381195068359375,0.013610482215881348,610.7118530273438 -1769682120,270716160,4.338845729827881,0.013698697090148926,610.7175903320312 -1769682120,303745536,4.339682579040527,0.013710081577301025,610.7249755859375 -1769682120,358140672,4.3402485847473145,0.013814985752105713,610.7304077148438 -1769682120,372923392,4.340709686279297,0.013890743255615234,610.7356567382812 -1769682120,404453632,4.341263294219971,0.013913154602050781,610.7423706054688 -1769682120,461247744,4.341594696044922,0.014001309871673584,610.747314453125 -1769682120,468995072,4.341836452484131,0.014090240001678467,610.7520751953125 -1769682120,505381888,4.342436790466309,0.014213919639587402,610.7579345703125 -1769682120,550785024,4.342798709869385,0.01434934139251709,610.7620239257812 -1769682120,570604800,4.343120098114014,0.01446157693862915,610.7656860351562 -1769682120,604522752,4.343482971191406,0.0145987868309021,610.77001953125 -1769682120,648904704,4.3437066078186035,0.014444589614868164,610.7726440429688 -1769682120,671539456,4.343870162963867,0.014457345008850098,610.7742309570312 -1769682120,703890176,4.344062328338623,0.013889968395233154,610.7741088867188 -1769682120,749053952,4.344171524047852,0.013462662696838379,610.7713012695312 -1769682120,770960896,4.344351291656494,0.013249337673187256,610.7691040039062 -1769682120,804228864,4.344688892364502,0.01291424036026001,610.7638549804688 -1769682120,861405696,4.344878196716309,0.012607574462890625,610.7592163085938 -1769682120,870776320,4.345042705535889,0.012361645698547363,610.754150390625 -1769682120,906231040,4.345209121704102,0.012148261070251465,610.7469482421875 -1769682120,950103808,4.3452887535095215,0.011958479881286621,610.7412719726562 -1769682120,970468096,4.345302581787109,0.01180875301361084,610.7354736328125 -1769682121,4215296,4.3452982902526855,0.011787116527557373,610.727783203125 -1769682121,54019328,4.345245838165283,0.01167452335357666,610.7220458984375 -1769682121,70310912,4.345151424407959,0.011622369289398193,610.71630859375 -1769682121,105227520,4.345003128051758,0.011708498001098633,610.7086791992188 -1769682121,152615680,4.344829559326172,0.011699974536895752,610.7029418945312 -1769682121,171852032,4.344645977020264,0.011717140674591064,610.6972045898438 -1769682121,204395008,4.344372272491455,0.011841773986816406,610.6893310546875 -1769682121,262870784,4.344089031219482,0.011819005012512207,610.6834106445312 -1769682121,271092480,4.343781471252441,0.011871516704559326,610.6774291992188 -1769682121,306442496,4.343352317810059,0.01196831464767456,610.66943359375 -1769682121,350046976,4.3429436683654785,0.011929869651794434,610.6635131835938 -1769682121,370823680,4.342526912689209,0.01188957691192627,610.6576538085938 -1769682121,403846912,4.342121601104736,0.011980593204498291,610.6500854492188 -1769682121,447983616,4.341867923736572,0.011926352977752686,610.6444702148438 -1769682121,470862080,4.341593265533447,0.011911094188690186,610.638916015625 -1769682121,504558080,4.34119176864624,0.011936724185943604,610.6317138671875 -1769682121,554311680,4.340872764587402,0.01187288761138916,610.6264038085938 -1769682121,571611904,4.340477466583252,0.01185065507888794,610.62109375 -1769682121,604787968,4.339913368225098,0.011909425258636475,610.6141967773438 -1769682121,660596480,4.339452743530273,0.011867523193359375,610.6090087890625 -1769682121,673969152,4.338815212249756,0.011875808238983154,610.6022338867188 -1769682121,706566656,4.338400363922119,0.011883914470672607,610.5972290039062 -1769682121,751509248,4.337936878204346,0.01182544231414795,610.5921630859375 -1769682121,785235200,4.337437629699707,0.011783897876739502,610.5872802734375 -1769682121,805100800,4.336733818054199,0.011831820011138916,610.5808715820312 -1769682121,852737792,4.336208343505859,0.011763334274291992,610.5761108398438 -1769682121,870982656,4.335679054260254,0.011711537837982178,610.5714111328125 -1769682121,904213504,4.334961891174316,0.011730432510375977,610.5653076171875 -1769682121,949847552,4.33439826965332,0.011676609516143799,610.5609130859375 -1769682121,972494848,4.333817958831787,0.011640727519989014,610.5565185546875 -1769682122,5788928,4.333037376403809,0.01167374849319458,610.5507202148438 -1769682122,77690368,4.332407474517822,0.01163327693939209,610.5464477539062 -1769682122,90239744,4.331406116485596,0.011658906936645508,610.540771484375 -1769682122,101874176,4.33090353012085,0.01161283254623413,610.5379028320312 -1769682122,146443264,4.329484939575195,0.011676311492919922,610.53076171875 -1769682122,170959360,4.328866004943848,0.011623919010162354,610.5279541015625 -1769682122,207994112,4.327545642852783,0.011670291423797607,610.522216796875 -1769682122,249427456,4.326395034790039,0.01163262128829956,610.51806640625 -1769682122,271881984,4.325244426727295,0.011598467826843262,610.513916015625 -1769682122,303911168,4.323679447174072,0.01162111759185791,610.508544921875 -1769682122,359882240,4.322412490844727,0.011584281921386719,610.5045776367188 -1769682122,370904064,4.32125997543335,0.011580944061279297,610.500732421875 -1769682122,405242624,4.319723129272461,0.011583805084228516,610.4956665039062 -1769682122,446494720,4.318283557891846,0.011546611785888672,610.4920043945312 -1769682122,474059008,4.31632661819458,0.01154869794845581,610.4871826171875 -1769682122,506639872,4.314882278442383,0.011536777019500732,610.4837036132812 -1769682122,553025280,4.313140869140625,0.01150500774383545,610.480224609375 -1769682122,571327232,4.311396598815918,0.011500060558319092,610.4767456054688 -1769682122,605774080,4.309023380279541,0.01154249906539917,610.4722900390625 -1769682122,671156992,4.306278228759766,0.01153630018234253,610.4677734375 -1769682122,677749760,4.3041253089904785,0.011537611484527588,610.4644775390625 -1769682122,703929600,4.301926136016846,0.011518239974975586,610.4612426757812 -1769682122,760905984,4.299536228179932,0.011479377746582031,610.4581298828125 -1769682122,768828928,4.297094345092773,0.011442840099334717,610.4551391601562 -1769682122,805088768,4.293833255767822,0.011438965797424316,610.4513549804688 -1769682122,849464064,4.2913079261779785,0.011404633522033691,610.4485473632812 -1769682122,873219584,4.288527011871338,0.011381030082702637,610.44580078125 -1769682122,904285952,4.284745216369629,0.011405110359191895,610.4423217773438 -1769682122,947616000,4.281790256500244,0.011383473873138428,610.4397583007812 -1769682122,970852096,4.279038429260254,0.01136922836303711,610.4371948242188 -1769682123,13616384,4.275331974029541,0.011385023593902588,610.4338989257812 -1769682123,47930624,4.2726216316223145,0.01136404275894165,610.431396484375 -1769682123,70481408,4.26996374130249,0.011339962482452393,610.428955078125 -1769682123,104484352,4.266411781311035,0.011336266994476318,610.4258422851562 -1769682123,163540736,4.263733863830566,0.011297464370727539,610.423583984375 -1769682123,173794560,4.261184215545654,0.011236786842346191,610.42138671875 -1769682123,203773184,4.257831573486328,0.011206567287445068,610.4187622070312 -1769682123,246880768,4.2553534507751465,0.011157333850860596,610.4169921875 -1769682123,270498304,4.25300931930542,0.011100172996520996,610.4153442382812 -1769682123,308022784,4.249950885772705,0.011065542697906494,610.4132690429688 -1769682123,357470720,4.247758388519287,0.01102137565612793,610.4119262695312 -1769682123,371836672,4.245639324188232,0.010994195938110352,610.4105834960938 -1769682123,405533184,4.2429070472717285,0.011008620262145996,610.4088134765625 -1769682123,453198592,4.240977764129639,0.010999083518981934,610.407470703125 -1769682123,471587840,4.239107608795166,0.011012077331542969,610.4060668945312 -1769682123,504479232,4.236844062805176,0.01106327772140503,610.4039306640625 -1769682123,547385600,4.235191822052002,0.011060178279876709,610.4022216796875 -1769682123,573471232,4.233489036560059,0.011045873165130615,610.4004516601562 -1769682123,606029824,4.231321811676025,0.011092901229858398,610.3978881835938 -1769682123,639092736,4.229909420013428,0.011072158813476562,610.3958129882812 -1769682123,670458368,4.228549480438232,0.011057913303375244,610.3938598632812 -1769682123,709216000,4.226912498474121,0.01106250286102295,610.39111328125 -1769682123,749115136,4.225814342498779,0.011029839515686035,610.38916015625 -1769682123,772915200,4.224817276000977,0.010983467102050781,610.3873291015625 -1769682123,805281024,4.223694324493408,0.010936737060546875,610.385009765625 -1769682123,869117696,4.222935199737549,0.010905086994171143,610.3834228515625 -1769682123,876485632,4.222139358520508,0.010867118835449219,610.3814697265625 -1769682123,906094848,4.221621990203857,0.010834336280822754,610.3802490234375 -1769682123,950862080,4.221189498901367,0.010801196098327637,610.37890625 -1769682123,978625792,4.220720291137695,0.01077502965927124,610.3773193359375 -1769682124,5158400,4.220446586608887,0.010773658752441406,610.3761596679688 -1769682124,53327872,4.220246315002441,0.010755717754364014,610.3748779296875 -1769682124,71534336,4.22021484375,0.010729432106018066,610.3736572265625 -1769682124,108271616,4.220207691192627,0.010724067687988281,610.3721923828125 -1769682124,140464896,4.220253944396973,0.010694622993469238,610.3710327148438 -1769682124,170539520,4.220267295837402,0.010699868202209473,610.3698120117188 -1769682124,206667776,4.220282077789307,0.010715723037719727,610.3681640625 -1769682124,253982976,4.2202606201171875,0.010738968849182129,610.3668823242188 -1769682124,271785728,4.220269203186035,0.010776102542877197,610.365478515625 -1769682124,304285184,4.220317840576172,0.010845541954040527,610.3634033203125 -1769682124,349226752,4.220382213592529,0.010873377323150635,610.3616943359375 -1769682124,375652352,4.22050142288208,0.010939419269561768,610.3590698242188 -1769682124,406470656,4.220622539520264,0.010985791683197021,610.3569946289062 -1769682124,449265152,4.220762252807617,0.011014819145202637,610.354736328125 -1769682124,470925056,4.220931529998779,0.011022090911865234,610.3524169921875 -1769682124,510270208,4.22092342376709,0.011068642139434814,610.3490600585938 -1769682124,551641600,4.220935821533203,0.011069953441619873,610.346435546875 -1769682124,572637952,4.220953464508057,0.011063218116760254,610.3436889648438 -1769682124,604201216,4.221010684967041,0.011094212532043457,610.340087890625 -1769682124,649627648,4.221061706542969,0.011074364185333252,610.3373413085938 -1769682124,671460864,4.2211079597473145,0.011062860488891602,610.3345947265625 -1769682124,707277824,4.22117280960083,0.011071562767028809,610.3310546875 -1769682124,749093376,4.221284866333008,0.011044085025787354,610.3285522460938 -1769682124,772028672,4.221370697021484,0.011019289493560791,610.325927734375 -1769682124,805106688,4.221495151519775,0.01103442907333374,610.3226928710938 -1769682124,847351296,4.2216596603393555,0.011020779609680176,610.3203125 -1769682124,882850048,4.221826553344727,0.011013805866241455,610.31787109375 -1769682124,905320960,4.222090244293213,0.011053979396820068,610.3145751953125 -1769682124,951690240,4.222318172454834,0.011066138744354248,610.3121337890625 -1769682124,971430400,4.2225542068481445,0.011075794696807861,610.3094482421875 -1769682125,7095296,4.222872734069824,0.01115339994430542,610.3058471679688 -1769682125,56958464,4.223273277282715,0.011195957660675049,610.3018798828125 -1769682125,70328832,4.223475456237793,0.011183857917785645,610.2999267578125 -1769682125,105515776,4.223933696746826,0.01126408576965332,610.2955932617188 -1769682125,161978368,4.224245548248291,0.011254489421844482,610.2923583984375 -1769682125,173216256,4.224353790283203,0.01123344898223877,610.2889404296875 -1769682125,206706688,4.224518775939941,0.011273503303527832,610.2843627929688 -1769682125,251961344,4.224649429321289,0.011242449283599854,610.2810668945312 -1769682125,271281920,4.224809646606445,0.011220872402191162,610.2777709960938 -1769682125,304822272,4.225025653839111,0.011275112628936768,610.2734375 -1769682125,349147648,4.225217819213867,0.011253535747528076,610.2702026367188 -1769682125,371795968,4.2253499031066895,0.011240184307098389,610.2669677734375 -1769682125,404500992,4.225532531738281,0.011299729347229004,610.2626342773438 -1769682125,451548416,4.225578308105469,0.011300325393676758,610.25927734375 -1769682125,473244160,4.225535869598389,0.011282086372375488,610.2557373046875 -1769682125,504682752,4.22549295425415,0.01135629415512085,610.2509155273438 -1769682125,564382720,4.225471496582031,0.011370718479156494,610.2471313476562 -1769682125,573727488,4.225457668304443,0.011369764804840088,610.2433471679688 -1769682125,606613760,4.2254319190979,0.011454224586486816,610.2380981445312 -1769682125,653408256,4.225435733795166,0.01143944263458252,610.2340698242188 -1769682125,670836736,4.225451469421387,0.011451423168182373,610.22998046875 -1769682125,707911936,4.225495338439941,0.011533379554748535,610.224365234375 -1769682125,760012032,4.22553825378418,0.011533200740814209,610.2201538085938 -1769682125,771866368,4.225574493408203,0.011525928974151611,610.2158203125 -1769682125,804770304,4.2256550788879395,0.011620402336120605,610.2099609375 -1769682125,867180544,4.225738525390625,0.011577308177947998,610.2056274414062 -1769682125,877931520,4.225888252258301,0.011623561382293701,610.19970703125 -1769682125,906333184,4.226001739501953,0.011631131172180176,610.1952514648438 -1769682125,947410432,4.2261176109313965,0.011585056781768799,610.1908569335938 -1769682125,977666048,4.226240634918213,0.011610567569732666,610.18505859375 -1769682126,5677824,4.2263407707214355,0.011590361595153809,610.1806640625 -1769682126,54502144,4.226515769958496,0.011540412902832031,610.1764526367188 -1769682126,70796288,4.226687431335449,0.011534273624420166,610.172119140625 -1769682126,109238784,4.226715087890625,0.011574864387512207,610.16650390625 -1769682126,148190208,4.22674560546875,0.011541903018951416,610.162353515625 -1769682126,173116160,4.226785182952881,0.011518418788909912,610.1580810546875 -1769682126,204556032,4.22690486907959,0.011606097221374512,610.1524047851562 -1769682126,254712832,4.227009296417236,0.011562764644622803,610.1480712890625 -1769682126,271484672,4.227137088775635,0.011565148830413818,610.1437377929688 -1769682126,305332480,4.227347373962402,0.01167374849319458,610.1376953125 -1769682126,347401216,4.227512836456299,0.011676132678985596,610.133056640625 -1769682126,376087808,4.227725505828857,0.01181870698928833,610.12646484375 -1769682126,406199552,4.227818012237549,0.011873841285705566,610.1212158203125 -1769682126,453025024,4.227926254272461,0.011892259120941162,610.1157836914062 -1769682126,471926784,4.228041172027588,0.011907041072845459,610.1100463867188 -1769682126,507975936,4.228198051452637,0.012027621269226074,610.1021728515625 -1769682126,554297088,4.228342533111572,0.012004375457763672,610.09619140625 -1769682126,573110784,4.228432655334473,0.011976063251495361,610.0902709960938 -1769682126,606019584,4.228550910949707,0.011988818645477295,610.0823974609375 -1769682126,659956224,4.228647708892822,0.011903584003448486,610.0767822265625 -1769682126,676916224,4.228780269622803,0.011905670166015625,610.0694580078125 -1769682126,704642816,4.2288923263549805,0.011851906776428223,610.064208984375 -1769682126,750697728,4.229011058807373,0.011761903762817383,610.05908203125 -1769682126,775919872,4.229175567626953,0.011788785457611084,610.052490234375 -1769682126,807980544,4.229294776916504,0.011764287948608398,610.0476684570312 -1769682126,847779328,4.22943115234375,0.011721193790435791,610.0427856445312 -1769682126,870855936,4.229578018188477,0.011689305305480957,610.0380249023438 -1769682126,907635200,4.229791641235352,0.011717736721038818,610.0316162109375 -1769682126,944758016,4.230018615722656,0.011693120002746582,610.025390625 -1769682126,970886400,4.230125427246094,0.011626660823822021,610.022216796875 -1769682127,4469504,4.2303643226623535,0.011662960052490234,610.0159912109375 -1769682127,52867072,4.230513572692871,0.011639595031738281,610.0114135742188 -1769682127,72418560,4.230525970458984,0.011632561683654785,610.0067749023438 -1769682127,105135616,4.23061990737915,0.011722207069396973,610.0004272460938 -1769682127,148288256,4.230690002441406,0.011733293533325195,609.9956665039062 -1769682127,178897664,4.230766296386719,0.011804640293121338,609.989013671875 -1769682127,205084928,4.230830669403076,0.011834442615509033,609.98388671875 -1769682127,253799168,4.230953216552734,0.011805355548858643,609.9786987304688 -1769682127,272168192,4.231064319610596,0.011794865131378174,609.9735717773438 -1769682127,306129920,4.23124885559082,0.011816799640655518,609.9666748046875 -1769682127,354732032,4.231368064880371,0.011730551719665527,609.9616088867188 -1769682127,371826688,4.231499671936035,0.0116768479347229,609.956787109375 -1769682127,405051392,4.231678485870361,0.01166754961013794,609.9505004882812 -1769682127,453614848,4.231867790222168,0.011578917503356934,609.946044921875 -1769682127,472482048,4.232052803039551,0.011530637741088867,609.9417114257812 -1769682127,505330432,4.2323479652404785,0.011550426483154297,609.9360961914062 -1769682127,553534208,4.232571125030518,0.011508524417877197,609.9320068359375 -1769682127,580784384,4.232913970947266,0.011536836624145508,609.9266357421875 -1769682127,606852352,4.233191013336182,0.011544883251190186,609.9224853515625 -1769682127,648690176,4.233471393585205,0.011529505252838135,609.9183349609375 -1769682127,670931968,4.2337327003479,0.01152735948562622,609.9141235351562 -1769682127,708037376,4.234079360961914,0.011593997478485107,609.9083862304688 -1769682127,747702272,4.234355926513672,0.011581659317016602,609.9039306640625 -1769682127,772716800,4.234591007232666,0.011568307876586914,609.8995361328125 -1769682127,804609024,4.234905242919922,0.01165992021560669,609.8934936523438 -1769682127,866442240,4.235220432281494,0.011686921119689941,609.887451171875 -1769682127,874318080,4.2354536056518555,0.011706829071044922,609.8828125 -1769682127,905510912,4.235682487487793,0.011712312698364258,609.8780517578125 -1769682127,947940352,4.235909461975098,0.011679649353027344,609.8733520507812 -1769682127,982511872,4.236122131347656,0.011665821075439453,609.8687133789062 -1769682128,6491136,4.236308574676514,0.011686861515045166,609.8624877929688 -1769682128,49664768,4.236451625823975,0.011642515659332275,609.8579711914062 -1769682128,71262720,4.2365946769714355,0.01159590482711792,609.8535766601562 -1769682128,104953088,4.236772537231445,0.011628985404968262,609.8478393554688 -1769682128,151968512,4.236936569213867,0.01161336898803711,609.8422241210938 -1769682128,171507712,4.2370100021362305,0.011574029922485352,609.8394165039062 -1769682128,205100032,4.237163066864014,0.011661052703857422,609.833740234375 -1769682128,266868992,4.237276077270508,0.01165693998336792,609.829345703125 -1769682128,274472192,4.237407684326172,0.011740922927856445,609.8233032226562 -1769682128,307307776,4.237504959106445,0.011779963970184326,609.8185424804688 -1769682128,351441664,4.2376203536987305,0.011764705181121826,609.8136596679688 -1769682128,373152000,4.237720012664795,0.011770188808441162,609.8087768554688 -1769682128,408732416,4.237852573394775,0.011871695518493652,609.8019409179688 -1769682128,447480320,4.23795223236084,0.01185905933380127,609.7968139648438 -1769682128,471052032,4.238042831420898,0.011843204498291016,609.7916259765625 -1769682128,506998272,4.23817253112793,0.011919498443603516,609.78466796875 -1769682128,554361344,4.238276481628418,0.011872649192810059,609.779541015625 -1769682128,572343296,4.238377571105957,0.011835753917694092,609.7743530273438 -1769682128,605334272,4.238516807556152,0.011905372142791748,609.767578125 -1769682128,649842432,4.238618850708008,0.011834859848022461,609.7625122070312 -1769682128,672693504,4.238717079162598,0.011801183223724365,609.757568359375 -1769682128,708041984,4.2388434410095215,0.011822283267974854,609.7510986328125 -1769682128,749064448,4.238945007324219,0.011768937110900879,609.7463989257812 -1769682128,771305984,4.239046573638916,0.01172250509262085,609.7417602539062 -1769682128,805082368,4.2391791343688965,0.01176828145980835,609.735595703125 -1769682128,849467136,4.239263534545898,0.011723160743713379,609.7310180664062 -1769682128,871395072,4.239333152770996,0.011711657047271729,609.7265014648438 -1769682128,905787136,4.239419937133789,0.011814355850219727,609.7203369140625 -1769682128,952774144,4.239497184753418,0.011817574501037598,609.7155151367188 -1769682128,972487424,4.239564895629883,0.011818170547485352,609.7106323242188 -1769682129,8562432,4.239646911621094,0.011912286281585693,609.703857421875 -1769682129,67949568,4.239706516265869,0.011890172958374023,609.69873046875 -1769682129,77338368,4.239774227142334,0.011947154998779297,609.691650390625 -1769682129,105584384,4.2398176193237305,0.011948049068450928,609.6864013671875 -1769682129,148425472,4.239855766296387,0.01190173625946045,609.68115234375 -1769682129,172546816,4.2398834228515625,0.01186591386795044,609.6759643554688 -1769682129,208028160,4.23993444442749,0.011907696723937988,609.6692504882812 -1769682129,247833856,4.240046977996826,0.011848986148834229,609.6627197265625 -1769682129,271485952,4.240101337432861,0.011784732341766357,609.6595458984375 -1769682129,305816576,4.240199565887451,0.011809110641479492,609.6534423828125 -1769682129,372008448,4.240257740020752,0.011742889881134033,609.6489868164062 -1769682129,378192896,4.240318298339844,0.011733949184417725,609.6431884765625 -1769682129,404317184,4.240358829498291,0.011708080768585205,609.6388549804688 -1769682129,449381632,4.240391254425049,0.01165771484375,609.6347045898438 -1769682129,475749120,4.240422248840332,0.011660158634185791,609.6292724609375 -1769682129,506717696,4.240438461303711,0.011636793613433838,609.6251831054688 -1769682129,548150272,4.240448474884033,0.011587381362915039,609.6212158203125 -1769682129,571082752,4.240450382232666,0.01156681776046753,609.6172485351562 -1769682129,607238400,4.240442276000977,0.011606693267822266,609.612060546875 -1769682129,660270592,4.240431308746338,0.011569023132324219,609.6082153320312 -1769682129,671314176,4.240406513214111,0.011561691761016846,609.6043090820312 -1769682129,705854208,4.240368843078613,0.011631906032562256,609.5990600585938 -1769682129,753705984,4.240332126617432,0.011623561382293701,609.5950927734375 -1769682129,773154816,4.240288734436035,0.011599183082580566,609.591064453125 -1769682129,805311488,4.240222930908203,0.01165914535522461,609.5856323242188 -1769682129,848734976,4.240167617797852,0.011613249778747559,609.5816040039062 -1769682129,874909952,4.240145683288574,0.011598587036132812,609.5762939453125 -1769682129,905764096,4.240164279937744,0.011569797992706299,609.5724487304688 -1769682129,951904000,4.240177631378174,0.011472880840301514,609.5687866210938 -1769682129,973337600,4.2401838302612305,0.01141500473022461,609.5642700195312 -1769682130,8077824,4.240184783935547,0.011344850063323975,609.5611572265625 -1769682130,48067840,4.240179538726807,0.011264503002166748,609.5582885742188 -1769682130,72064000,4.240164756774902,0.011198997497558594,609.5556640625 -1769682130,105276672,4.240137577056885,0.011142194271087646,609.5525512695312 -1769682130,170184192,4.2401123046875,0.01109468936920166,609.5503540039062 -1769682130,179447296,4.2401933670043945,0.011071622371673584,609.5477294921875 -1769682130,205851904,4.240281105041504,0.01106196641921997,609.5457153320312 -1769682130,248087040,4.240352630615234,0.011031687259674072,609.5438232421875 -1769682130,277530624,4.24043083190918,0.011058509349822998,609.541259765625 -1769682130,306579456,4.240477085113525,0.01106405258178711,609.5392456054688 -1769682130,348708352,4.240511417388916,0.011062324047088623,609.5372924804688 -1769682130,371459584,4.240532875061035,0.01105034351348877,609.5352783203125 -1769682130,410716160,4.240545272827148,0.011077940464019775,609.5326538085938 -1769682130,450035968,4.240530967712402,0.011064350605010986,609.5307006835938 -1769682130,471884800,4.240513801574707,0.011046290397644043,609.5287475585938 -1769682130,505921536,4.2404608726501465,0.011068284511566162,609.5262451171875 -1769682130,555849216,4.240406513214111,0.011055707931518555,609.5244140625 -1769682130,572354304,4.240345001220703,0.011025428771972656,609.5225830078125 -1769682130,605367552,4.240234375,0.01102358102798462,609.520263671875 -1769682130,650950656,4.2401227951049805,0.011021077632904053,609.5185546875 -1769682130,679339520,4.239963054656982,0.011006414890289307,609.516357421875 -1769682130,704988416,4.239833354949951,0.011001944541931152,609.5147705078125 -1769682130,748699136,4.239667892456055,0.010976016521453857,609.5133056640625 -1769682130,771520000,4.239492893218994,0.010941147804260254,609.5117797851562 -1769682130,806442496,4.23922061920166,0.01094740629196167,609.5098876953125 -1769682130,848341760,4.239151477813721,0.010892331600189209,609.5084838867188 -1769682130,872001536,4.239076614379883,0.010865449905395508,609.5072021484375 -1769682130,905111552,4.238945484161377,0.010831117630004883,609.5056762695312 -1769682130,949674240,4.238778114318848,0.010805904865264893,609.5042114257812 -1769682130,972052224,4.238678455352783,0.010782241821289062,609.5036010742188 -1769682131,5875456,4.238455295562744,0.010751962661743164,609.50244140625 -1769682131,50262272,4.238275527954102,0.010740816593170166,609.501708984375 -1769682131,72559104,4.238076686859131,0.010713338851928711,609.5010375976562 -1769682131,106676736,4.237887382507324,0.010727643966674805,609.5001220703125 -1769682131,157796096,4.2378153800964355,0.010703444480895996,609.4995727539062 -1769682131,173434880,4.23773193359375,0.010679423809051514,609.4990844726562 -1769682131,209254912,4.237607955932617,0.010662615299224854,609.49853515625 -1769682135,205608448,4.224598407745361,0.010496079921722412,609.5523071289062 -1769682135,268037120,0.0,-0.0,609.5524291992188 -1769682135,277842944,0.0,-0.0,609.552490234375 -1769682135,305382144,0.0,-0.0,609.552490234375 -1769682135,352566528,0.0,-0.0,609.552490234375 -1769682135,372752896,0.0,-0.0,609.552490234375 -1769682135,406224128,0.0,-0.0,609.552490234375 -1769682135,462984448,0.0,-0.0,609.552490234375 -1769682135,468595456,0.0,-0.0,609.552490234375 -1769682135,507687424,0.0,-0.0,609.552490234375 -1769682135,554949888,0.0,-0.0,609.552490234375 -1769682135,572461824,0.0,-0.0,609.552490234375 -1769682135,605119488,0.0,-0.0,609.552490234375 -1769682135,652199936,0.0,-0.0,609.552490234375 -1769682135,672070656,0.0,-0.0,609.5525512695312 -1769682135,705380864,0.0,-0.0,609.5525512695312 -1769682135,748313088,0.0,-0.0,609.5525512695312 -1769682135,772692736,0.0,-0.0,609.5525512695312 -1769682135,807455232,0.0,-0.0,609.5525512695312 -1769682135,870539008,0.0,-0.0,609.5525512695312 -1769682135,875869696,0.0,-0.0,609.5525512695312 -1769682135,905640448,0.0,-0.0,609.5525512695312 -1769682135,949940224,0.0,-0.0,609.5525512695312 -1769682135,977299712,0.0,-0.0,609.5525512695312 -1769682136,7739136,0.0,-0.0,609.5525512695312 -1769682136,50407424,0.0,-0.0,609.5525512695312 -1769682136,72501248,0.0,-0.0,609.5525512695312 -1769682136,105592832,0.0,-0.0,609.5525512695312 -1769682136,161005824,0.0,-0.0,609.5525512695312 -1769682136,172840960,0.0,-0.0,609.5525512695312 -1769682136,205764864,0.0,-0.0,609.5525512695312 -1769682136,254204160,0.0,-0.0,609.5525512695312 -1769682136,272860416,0.0,-0.0,609.5525512695312 -1769682136,307017216,0.0,-0.0,609.5525512695312 -1769682136,351220992,0.0,-0.0,609.5525512695312 -1769682136,379367680,0.0034029525704681873,0.0032043808605521917,609.5524291992188 -1769682136,406116096,0.021643387153744698,0.004624626599252224,609.5513305664062 -1769682136,451884032,0.03976617380976677,0.005941410548985004,609.5484619140625 -1769682136,472517376,0.05778250843286514,0.007169752381742001,609.5445556640625 -1769682136,511099904,0.081634521484375,0.008639760315418243,609.5381469726562 -1769682136,544549376,0.10540352761745453,0.009884128347039223,609.531005859375 -1769682136,571830016,0.11726581305265427,0.010409368202090263,609.52734375 -1769682136,605761536,0.14104428887367249,0.011280613020062447,609.5197143554688 -1769682136,655042048,0.15911392867565155,0.011776397004723549,609.513671875 -1769682136,673604864,0.176932692527771,0.012150730937719345,609.5076904296875 -1769682136,705716224,0.20046986639499664,0.012492287904024124,609.4993896484375 -1769682136,738513408,0.21930725872516632,0.01265111193060875,609.4929809570312 -1769682136,774960128,0.24567173421382904,0.012760970741510391,609.4839477539062 -1769682136,806621952,0.2657368779182434,0.012783583253622055,609.4768676757812 -1769682136,843195904,0.2860662639141083,0.012785762548446655,609.4693603515625 -1769682136,872035840,0.307112455368042,0.012771394103765488,609.4615478515625 -1769682136,908335360,0.336223304271698,0.01275257021188736,609.4505615234375 -1769682136,955716864,0.35883045196533203,0.012726947665214539,609.4418334960938 -1769682136,973983232,0.3823032081127167,0.012706547975540161,609.4327392578125 -1769682137,5829376,0.41358131170272827,0.01269451528787613,609.4201049804688 -1769682137,59636480,0.4461400508880615,0.012710049748420715,609.4067993164062 -1769682137,67796480,0.4628530442714691,0.012715823948383331,609.3999633789062 -1769682137,106857984,0.4973461925983429,0.012763135135173798,609.3856811523438 -1769682137,151463680,0.5237857699394226,0.012782730162143707,609.3745727539062 -1769682137,180385536,0.5597022771835327,0.012861408293247223,609.3590698242188 -1769682137,207918080,0.5870012640953064,0.01291394978761673,609.34716796875 -1769682137,252221440,0.615516185760498,0.012947112321853638,609.3347778320312 -1769682137,272827136,0.6439962387084961,0.012996673583984375,609.3222045898438 -1769682137,309521152,0.6817622184753418,0.013092294335365295,609.3048706054688 -1769682137,351538432,0.7110896706581116,0.013123676180839539,609.2916259765625 -1769682137,372863488,0.739020586013794,0.013150498270988464,609.2781982421875 -1769682137,406035200,0.7761174440383911,0.013232171535491943,609.26025390625 -1769682137,450116352,0.8041372895240784,0.013224154710769653,609.2467651367188 -1769682137,473204224,0.829494297504425,0.013218924403190613,609.2333984375 -1769682137,506790656,0.8626610636711121,0.013236626982688904,609.2158813476562 -1769682137,539421440,0.8875075578689575,0.013181954622268677,609.2030029296875 -1769682137,572568320,0.9140591621398926,0.01312410831451416,609.1903076171875 -1769682137,608411904,0.9499590992927551,0.013100102543830872,609.1734008789062 -1769682137,639517952,0.9769260883331299,0.013000324368476868,609.1608276367188 -1769682137,673328896,1.012678623199463,0.012907743453979492,609.1441040039062 -1769682137,706096384,1.0403298139572144,0.012815013527870178,609.1318969726562 -1769682137,757355008,1.0678212642669678,0.012685149908065796,609.1196899414062 -1769682137,771649280,1.0936838388442993,0.012547239661216736,609.10791015625 -1769682137,806284800,1.127964735031128,0.01240028440952301,609.0928955078125 -1769682137,850561024,1.1627728939056396,0.012195184826850891,609.0786743164062 -1769682137,872391936,1.1805819272994995,0.012050047516822815,609.07177734375 -1769682137,906775296,1.215928077697754,0.011887341737747192,609.05859375 -1769682137,968537600,1.242965579032898,0.01170426607131958,609.049072265625 -1769682137,979342592,1.2786927223205566,0.011513561010360718,609.0369873046875 -1769682138,9905408,1.3054602146148682,0.011359483003616333,609.0283203125 -1769682138,57018624,1.3321542739868164,0.011160701513290405,609.0200805664062 -1769682138,72855552,1.3590024709701538,0.010974258184432983,609.0123291015625 -1769682138,112318720,1.394913673400879,0.010759711265563965,609.0026245117188 -1769682138,148767744,1.4219253063201904,0.010539472103118896,608.9959716796875 -1769682138,173798400,1.4491287469863892,0.010341852903366089,608.9896850585938 -1769682138,208324352,1.4849796295166016,0.010121196508407593,608.9822387695312 -1769682138,273410560,1.5121104717254639,0.009913921356201172,608.9772338867188 -1769682138,280322304,1.547849416732788,0.009683221578598022,608.97119140625 -1769682138,305920512,1.5746173858642578,0.009503602981567383,608.9673461914062 -1769682138,338953216,1.6014699935913086,0.009313017129898071,608.9639282226562 -1769682138,372858368,1.6285656690597534,0.009134858846664429,608.9609985351562 -1769682138,408431872,1.6647047996520996,0.00891914963722229,608.957763671875 -1769682138,454042880,1.6917058229446411,0.00875169038772583,608.9558715820312 -1769682138,472629504,1.718482255935669,0.008590012788772583,608.954345703125 -1769682138,508374016,1.7539151906967163,0.008382529020309448,608.953125 -1769682138,556000512,1.7805426120758057,0.008233636617660522,608.9528198242188 -1769682138,574534656,1.8070487976074219,0.008084684610366821,608.952880859375 -1769682138,606874880,1.8423644304275513,0.0078812837600708,608.95361328125 -1769682138,655006464,1.8774375915527344,0.007692426443099976,608.9552001953125 -1769682138,671610112,1.894858479499817,0.007604748010635376,608.956298828125 -1769682138,706140416,1.9296181201934814,0.007422596216201782,608.9589233398438 -1769682138,754795520,1.9555423259735107,0.007312506437301636,608.9614868164062 -1769682138,780365824,1.9899135828018188,0.00714448094367981,608.9652709960938 -1769682138,807257344,2.0155348777770996,0.0070393383502960205,608.9686279296875 -1769682138,841420800,2.04103946685791,0.0069501399993896484,608.9722290039062 -1769682138,872121600,2.066527843475342,0.006853461265563965,608.9762573242188 -1769682138,908076544,2.1001956462860107,0.006696850061416626,608.9821166992188 -1769682138,943376384,2.1335294246673584,0.006575465202331543,608.9884643554688 -1769682138,972597248,2.150103807449341,0.006551116704940796,608.9918823242188 -1769682139,5847808,2.183136224746704,0.006420493125915527,608.9989624023438 -1769682139,54648320,2.2077529430389404,0.0063818395137786865,609.004638671875 -1769682139,73213184,2.2321431636810303,0.006320208311080933,609.0105590820312 -1769682139,106093568,2.264314651489258,0.006180703639984131,609.018798828125 -1769682139,139015680,2.2884578704833984,0.006141602993011475,609.0253295898438 -1769682139,174761984,2.3125057220458984,0.0061099231243133545,609.0320434570312 -1769682139,207569920,2.344264030456543,0.005971848964691162,609.0414428710938 -1769682139,250985984,2.367727518081665,0.005961716175079346,609.0486450195312 -1769682139,272483840,2.391030788421631,0.005933523178100586,609.05615234375 -1769682139,306515968,2.421964168548584,0.005834907293319702,609.0664672851562 -1769682139,355929344,2.4450273513793945,0.005840301513671875,609.0743408203125 -1769682139,374208512,2.475513219833374,0.005759775638580322,609.0850830078125 -1769682139,406024448,2.4981563091278076,0.005736023187637329,609.0932006835938 -1769682139,452599040,2.5208120346069336,0.005760848522186279,609.1015014648438 -1769682139,473085184,2.5432181358337402,0.005763649940490723,609.10986328125 -1769682139,509825792,2.5726985931396484,0.005670219659805298,609.1212768554688 -1769682139,565728768,2.59452223777771,0.005718588829040527,609.1299438476562 -1769682139,576356608,2.6234512329101562,0.0056344568729400635,609.1416625976562 -1769682139,607728384,2.644927978515625,0.005623131990432739,609.150634765625 -1769682139,653055744,2.666315793991089,0.005688399076461792,609.15966796875 -1769682139,672530176,2.68752121925354,0.005688965320587158,609.168701171875 -1769682139,708207104,2.715635061264038,0.0056154727935791016,609.180908203125 -1769682139,757874688,2.743469476699829,0.005631506443023682,609.1931762695312 -1769682139,767939840,2.757197141647339,0.005674302577972412,609.1993408203125 -1769682139,806182144,2.784374952316284,0.005658984184265137,609.2116088867188 -1769682139,855123200,2.804537057876587,0.005746662616729736,609.2208251953125 -1769682139,873567488,2.82456111907959,0.005782723426818848,609.2301025390625 -1769682139,906287360,2.85101580619812,0.005730688571929932,609.242431640625 -1769682139,939867392,2.870671510696411,0.005827069282531738,609.2516479492188 -1769682139,978634240,2.8965654373168945,0.005812346935272217,609.2638549804688 -1769682140,9336576,2.9157471656799316,0.005847036838531494,609.2728881835938 -1769682140,51547136,2.934643030166626,0.005949139595031738,609.2819213867188 -1769682140,73691136,2.9595932960510254,0.005936741828918457,609.2938842773438 -1769682140,106903552,2.9779953956604004,0.005972146987915039,609.3027954101562 -1769682140,145403648,3.0023226737976074,0.0060217976570129395,609.314697265625 -1769682140,172726528,3.014371633529663,0.006126582622528076,609.3206176757812 -1769682140,206362624,3.0383217334747314,0.0060797929763793945,609.3323364257812 -1769682140,254034432,3.055816888809204,0.006168365478515625,609.3411865234375 -1769682140,273976832,3.07319712638855,0.006232321262359619,609.3499755859375 -1769682140,307271168,3.0960657596588135,0.006186068058013916,609.3617553710938 -1769682140,348600320,3.1129751205444336,0.006280422210693359,609.370361328125 -1769682140,379301376,3.1353394985198975,0.00627666711807251,609.3819580078125 -1769682140,408822784,3.151890516281128,0.0063239336013793945,609.3905029296875 -1769682140,453628928,3.168356418609619,0.006423294544219971,609.39892578125 -1769682140,474190592,3.1898539066314697,0.006435811519622803,609.4100952148438 -1769682140,508524800,3.205829620361328,0.006498098373413086,609.4182739257812 -1769682140,543921664,3.2269704341888428,0.00657343864440918,609.4290161132812 -1769682140,572410368,3.2373454570770264,0.006686866283416748,609.4342651367188 -1769682140,607988480,3.257779598236084,0.006676733493804932,609.4447631835938 -1769682140,653869824,3.2729058265686035,0.006781458854675293,609.452392578125 -1769682140,675146240,3.2929444313049316,0.006810367107391357,609.4624633789062 -1769682140,706023424,3.3077285289764404,0.006873488426208496,609.4698486328125 -1769682140,749088512,3.3224098682403564,0.006987512111663818,609.4771728515625 -1769682140,777646336,3.341752052307129,0.007032632827758789,609.486572265625 -1769682140,807423232,3.355988025665283,0.007105112075805664,609.4934692382812 -1769682140,842975488,3.3701086044311523,0.0072457194328308105,609.5001220703125 -1769682140,872444416,3.3839492797851562,0.007318675518035889,609.506591796875 -1769682140,908187648,3.4022741317749023,0.0073313117027282715,609.51513671875 -1769682140,960838144,3.4157602787017822,0.007434666156768799,609.521240234375 -1769682140,969659136,3.42919921875,0.00747758150100708,609.52734375 -1769682141,6359808,3.4468605518341064,0.007517993450164795,609.5352172851562 -1769682141,55964672,3.4643092155456543,0.007570862770080566,609.54296875 -1769682141,72953600,3.4729788303375244,0.007653474807739258,609.5467529296875 -1769682141,107995648,3.490154266357422,0.007635056972503662,609.5542602539062 -1769682141,140836096,3.5027918815612793,0.007720649242401123,609.5598754882812 -1769682141,173850880,3.515353202819824,0.007768154144287109,609.5653686523438 -1769682141,206518784,3.5318539142608643,0.007729470729827881,609.5726928710938 -1769682141,251052544,3.5440001487731934,0.007799983024597168,609.578125 -1769682141,272739328,3.55607008934021,0.007847428321838379,609.58349609375 -1769682141,310415616,3.5718793869018555,0.00784069299697876,609.590576171875 -1769682141,350068992,3.5836291313171387,0.007927298545837402,609.5957641601562 -1769682141,373762048,3.595240592956543,0.008007168769836426,609.600830078125 -1769682141,408704512,3.610583543777466,0.008029341697692871,609.6072998046875 -1769682141,456165120,3.621917247772217,0.008135020732879639,609.6119384765625 -1769682141,473619200,3.636822462081909,0.008150160312652588,609.6178588867188 -1769682141,506507520,3.6479249000549316,0.008178472518920898,609.6222534179688 -1769682141,543582464,3.6624808311462402,0.008212566375732422,609.6278686523438 -1769682141,572686336,3.6697397232055664,0.008269786834716797,609.6307983398438 -1769682141,606503680,3.683953046798706,0.008234500885009766,609.6364135742188 -1769682141,639537152,3.694488048553467,0.008280277252197266,609.6407470703125 -1769682141,683582720,3.7049460411071777,0.008301973342895508,609.6450805664062 -1769682141,709280768,3.71869158744812,0.008261620998382568,609.65087890625 -1769682141,757133568,3.7288401126861572,0.008321046829223633,609.6551513671875 -1769682141,772334336,3.7388463020324707,0.008337914943695068,609.6595458984375 -1769682141,812141568,3.7521462440490723,0.008308827877044678,609.6651611328125 -1769682141,854874112,3.7619376182556152,0.00835484266281128,609.6694946289062 -1769682141,874403328,3.771682024002075,0.008390426635742188,609.6736450195312 -1769682141,906972928,3.7845327854156494,0.008353769779205322,609.6791381835938 -1769682141,957780480,3.794004440307617,0.00841444730758667,609.6832885742188 -1769682141,989102336,3.8064491748809814,0.008388161659240723,609.6887817382812 -1769682142,7190528,3.8156726360321045,0.008415520191192627,609.69287109375 -1769682142,45395712,3.8278496265411377,0.008446097373962402,609.6982421875 -1769682142,74744832,3.8367912769317627,0.008485496044158936,609.7022094726562 -1769682142,108137216,3.845649003982544,0.008535921573638916,609.7059936523438 -1769682142,140833536,3.8543570041656494,0.008631348609924316,609.7097778320312 -1769682142,182996736,3.862997531890869,0.008705556392669678,609.7133178710938 -1769682142,206977280,3.8742828369140625,0.008747100830078125,609.7177734375 -1769682142,251559168,3.8826212882995605,0.008838951587677002,609.7208862304688 -1769682142,273825536,3.893458604812622,0.008898735046386719,609.7247924804688 -1769682142,306618368,3.9014861583709717,0.008951902389526367,609.7274780273438 -1769682142,345005568,3.911851406097412,0.00901651382446289,609.73095703125 -1769682142,373281024,3.9169421195983887,0.009071707725524902,609.7326049804688 -1769682142,408612608,3.926950454711914,0.00908505916595459,609.7359619140625 -1769682142,465291776,3.934282064437866,0.009136736392974854,609.7383422851562 -1769682142,473327872,3.9415292739868164,0.009164214134216309,609.7407836914062 -1769682142,507019776,3.9509811401367188,0.009158313274383545,609.7440185546875 -1769682142,554741760,3.9579293727874756,0.009197652339935303,609.746337890625 -1769682142,574901504,3.9670469760894775,0.009203493595123291,609.7494506835938 -1769682142,609339904,3.9737753868103027,0.009220480918884277,609.7517700195312 -1769682142,654608384,3.980320930480957,0.009266972541809082,609.7540283203125 -1769682142,672843008,3.9866461753845215,0.009302139282226562,609.7562255859375 -1769682142,708133632,3.9949777126312256,0.009311199188232422,609.7591552734375 -1769682142,753443328,4.003068447113037,0.009357154369354248,609.7617797851562 -1769682142,773238784,4.00709867477417,0.009397387504577637,609.7630615234375 -1769682142,808228864,4.0148844718933105,0.009393572807312012,609.765625 -1769682142,872641536,4.020628452301025,0.009422063827514648,609.7674560546875 -1769682142,881604096,4.028061389923096,0.00942540168762207,609.7698974609375 -1769682142,908890112,4.033432960510254,0.009446024894714355,609.771728515625 -1769682142,942495232,4.038776874542236,0.009501993656158447,609.7735595703125 -1769682142,972634368,4.0438408851623535,0.009538352489471436,609.7753295898438 -1769682143,10845696,4.050475120544434,0.009584903717041016,609.7775268554688 -1769682143,51579904,4.05527925491333,0.009651541709899902,609.779052734375 -1769682143,73594112,4.059950828552246,0.009719550609588623,609.7803344726562 -1769682143,106358016,4.066041469573975,0.009805619716644287,609.78173828125 -1769682143,158276864,4.071951389312744,0.00990229845046997,609.7828369140625 -1769682143,168129024,4.074794769287109,0.009958744049072266,609.783203125 -1769682143,207485440,4.080249786376953,0.010034322738647461,609.7837524414062 -1769682143,256756992,4.085397243499756,0.01009601354598999,609.783935546875 -1769682143,280620800,4.089186191558838,0.010125279426574707,609.7841796875 -1769682143,307580672,4.0929036140441895,0.010145723819732666,609.7842407226562 -1769682143,344444928,4.0974860191345215,0.010152995586395264,609.7843627929688 -1769682143,372665600,4.099732398986816,0.010146141052246094,609.784423828125 -1769682143,409032704,4.10398006439209,0.010141193866729736,609.7848510742188 -1769682143,452784896,4.107086658477783,0.01013404130935669,609.7852172851562 -1769682143,473792512,4.110068321228027,0.01013094186782837,609.7857055664062 -1769682143,508807424,4.113938808441162,0.010109126567840576,609.7864990234375 -1769682143,555551744,4.1176300048828125,0.010092020034790039,609.7872924804688 -1769682143,573548032,4.120273590087891,0.010085701942443848,609.7879638671875 -1769682143,606856192,4.1228251457214355,0.010063409805297852,609.7886352539062 -1769682143,640696064,4.125181674957275,0.010058701038360596,609.7894897460938 -1769682143,676258816,4.128244400024414,0.010024011135101318,609.7906494140625 -1769682143,709265664,4.13038444519043,0.010013222694396973,609.7915649414062 -1769682143,742781696,4.132474899291992,0.010012626647949219,609.7926025390625 -1769682143,772895488,4.134450435638428,0.010010898113250732,609.793701171875 -1769682143,807197696,4.1369218826293945,0.010009229183197021,609.7951049804688 -1769682143,851460352,4.138669967651367,0.010023355484008789,609.796142578125 -1769682143,874819584,4.140958309173584,0.01002037525177002,609.797607421875 -1769682143,907351808,4.142546653747559,0.010012030601501465,609.7987670898438 -1769682143,951162112,4.144467353820801,0.009984314441680908,609.80029296875 -1769682143,973148416,4.145360469818115,0.009983181953430176,609.8012084960938 -1769682144,6945792,4.147043704986572,0.009928107261657715,609.8030395507812 -1769682144,67931904,4.148219108581543,0.009910821914672852,609.8046875 -1769682144,76698880,4.149636745452881,0.00986635684967041,609.8069458007812 -1769682144,108196096,4.150630950927734,0.00985783338546753,609.8087768554688 -1769682144,151806464,4.1515793800354,0.009869813919067383,609.8107299804688 -1769682144,174125568,4.15275764465332,0.009871482849121094,609.8133544921875 -1769682144,208753408,4.153599262237549,0.00989687442779541,609.815185546875 -1769682144,249830144,4.15447998046875,0.009929895401000977,609.8175659179688 -1769682144,275116800,4.155132293701172,0.009944558143615723,609.8192749023438 -1769682144,306441216,4.155640125274658,0.009960830211639404,609.82080078125 -1769682144,354049792,4.156154155731201,0.009971678256988525,609.822998046875 -1769682144,374406144,4.156439781188965,0.009964823722839355,609.8246459960938 -1769682144,407035904,4.1567158699035645,0.009961724281311035,609.8263549804688 -1769682144,440686848,4.156917095184326,0.009982466697692871,609.828125 -1769682144,474667776,4.1570844650268555,0.00997835397720337,609.8305053710938 -1769682144,506985728,4.157147407531738,0.009990870952606201,609.832275390625 -1769682144,551859968,4.157127380371094,0.010019958019256592,609.8340454101562 -1769682144,573354752,4.157094955444336,0.010025262832641602,609.8363037109375 -1769682144,606985472,4.156975746154785,0.010038256645202637,609.8380126953125 -1769682144,641091072,4.156843185424805,0.010055840015411377,609.839599609375 -1769682144,673088256,4.1566996574401855,0.010055303573608398,609.8411865234375 -1769682144,708526080,4.156436443328857,0.009990811347961426,609.8434448242188 -1769682144,753797888,4.15609884262085,0.009934306144714355,609.845947265625 -1769682144,773134080,4.155930995941162,0.009936988353729248,609.8472900390625 -1769682144,806860032,4.155579090118408,0.009859442710876465,609.8501586914062 -1769682144,855654144,4.155283451080322,0.009852170944213867,609.8524780273438 -1769682144,874435584,4.15491247177124,0.009808957576751709,609.8558349609375 -1769682144,907858688,4.154616355895996,0.009811222553253174,609.8582153320312 -1769682144,941720576,4.154323101043701,0.009846031665802002,609.8606567382812 -1769682144,974113536,4.153931140899658,0.009838998317718506,609.8638305664062 -1769682145,8961792,4.153632164001465,0.0098494291305542,609.8660278320312 -1769682145,40992000,4.153331279754639,0.009878993034362793,609.8682861328125 -1769682145,73220608,4.153036594390869,0.00987309217453003,609.8704833984375 -1769682145,109328896,4.152667045593262,0.009816288948059082,609.87353515625 -1769682145,139544832,4.152386665344238,0.009819746017456055,609.8758544921875 -1769682145,173478656,4.152044296264648,0.00976252555847168,609.879150390625 -1769682145,209758976,4.1518096923828125,0.00974196195602417,609.8816528320312 -1769682145,253410816,4.151578903198242,0.009750723838806152,609.88427734375 -1769682145,273331712,4.151251792907715,0.00969916582107544,609.887939453125 -1769682145,308050176,4.1510114669799805,0.009673655033111572,609.8908081054688 -1769682145,350400256,4.150789737701416,0.009686589241027832,609.8935546875 -1769682145,373579008,4.150555610656738,0.009623169898986816,609.8974609375 -1769682145,406616832,4.150392055511475,0.009588122367858887,609.9005126953125 -1769682145,439656960,4.150249481201172,0.009582221508026123,609.9036254882812 -1769682145,474694400,4.150095462799072,0.00950765609741211,609.9078979492188 -1769682145,508039168,4.150002956390381,0.009469687938690186,609.9113159179688 -1769682145,565124608,4.1499223709106445,0.009440124034881592,609.9158935546875 -1769682145,573602560,4.149881362915039,0.009466767311096191,609.9182739257812 -1769682145,607548672,4.149810314178467,0.009387314319610596,609.9230346679688 -1769682145,653584128,4.149769306182861,0.009410381317138672,609.9266357421875 -1769682145,675378432,4.149747848510742,0.009375452995300293,609.9314575195312 -1769682145,707129600,4.149759292602539,0.009381473064422607,609.9351806640625 -1769682145,740119808,4.149783611297607,0.009432077407836914,609.938720703125 -1769682145,774256384,4.1498332023620605,0.009441673755645752,609.943359375 -1769682145,808157696,4.1498847007751465,0.009486734867095947,609.9465942382812 -1769682145,842903040,4.149947643280029,0.009561598300933838,609.9498291015625 -1769682145,873743360,4.150042533874512,0.009578883647918701,609.953857421875 -1769682145,906784256,4.150120735168457,0.009609043598175049,609.9567260742188 -1769682145,941640960,4.150206565856934,0.009679615497589111,609.9594116210938 -1769682145,975340800,4.150323390960693,0.009688615798950195,609.9628295898438 -1769682146,8243712,4.150424957275391,0.009704828262329102,609.9653930664062 -1769682146,57854720,4.1505866050720215,0.009727537631988525,609.9685668945312 -1769682146,80745984,4.150737762451172,0.009736061096191406,609.9710083007812 -1769682146,106891776,4.150897979736328,0.009738683700561523,609.973388671875 -1769682146,145352704,4.151126384735107,0.009734272956848145,609.9766235351562 -1769682146,174226944,4.151331424713135,0.009724676609039307,609.97900390625 -1769682146,210392832,4.151538848876953,0.009718596935272217,609.9815063476562 -1769682146,247170816,4.151774883270264,0.009709954261779785,609.98486328125 -1769682146,273200128,4.151985168457031,0.009708404541015625,609.9873046875 -1769682146,306667008,4.152197360992432,0.00973653793334961,609.98974609375 -1769682146,352943104,4.152472972869873,0.009776771068572998,609.9929809570312 -1769682146,374003968,4.152666091918945,0.009818673133850098,609.9951782226562 -1769682146,406799872,4.152895927429199,0.009855866432189941,609.9972534179688 -1769682146,440391424,4.153141498565674,0.009913921356201172,609.9990844726562 -1769682146,474859520,4.15346622467041,0.009942352771759033,610.0013427734375 -1769682146,508851712,4.153750896453857,0.009963810443878174,610.0029907226562 -1769682146,541490432,4.154036045074463,0.009993970394134521,610.0045166015625 -1769682146,573412096,4.154427528381348,0.009973347187042236,610.00634765625 -1769682146,613021696,4.154770851135254,0.0099639892578125,610.0076904296875 -1769682146,642670848,4.155120372772217,0.009964287281036377,610.0089111328125 -1769682146,674643200,4.155584335327148,0.009930551052093506,610.0106201171875 -1769682146,707312896,4.15595817565918,0.009919345378875732,610.0119018554688 -1769682146,752555520,4.156486988067627,0.009892284870147705,610.0136108398438 -1769682146,775310080,4.156923294067383,0.009868144989013672,610.0149536132812 -1769682146,807140864,4.157366752624512,0.00983208417892456,610.0162963867188 -1769682146,840674048,4.157815933227539,0.009822726249694824,610.0177001953125 -1769682146,875823104,4.158438205718994,0.009775996208190918,610.0197143554688 -1769682146,908013312,4.158916473388672,0.009741544723510742,610.0213623046875 -1769682146,945517056,4.159552097320557,0.00970315933227539,610.0235595703125 -1769682146,973541376,4.160033226013184,0.00968480110168457,610.0254516601562 -1769682147,9246464,4.160517692565918,0.009682118892669678,610.0274047851562 -1769682147,46342656,4.161155700683594,0.009688377380371094,610.0301513671875 -1769682147,73549056,4.161632061004639,0.009699523448944092,610.0322265625 -1769682147,107021056,4.162113666534424,0.009725332260131836,610.0343627929688 -1769682147,153174016,4.162749767303467,0.009776949882507324,610.037109375 -1769682147,175243520,4.163193225860596,0.009824275970458984,610.0390625 -1769682147,207521792,4.163609027862549,0.009878695011138916,610.0408325195312 -1769682147,240209408,4.164030075073242,0.009925663471221924,610.04248046875 -1769682147,273823488,4.164597988128662,0.009950578212738037,610.0443115234375 -1769682147,307452416,4.165034294128418,0.009966075420379639,610.0455322265625 -1769682147,341031168,4.165461540222168,0.009988903999328613,610.0466918945312 -1769682147,373821184,4.16602087020874,0.009971141815185547,610.0480346679688 -1769682147,407954432,4.16644287109375,0.009960711002349854,610.049072265625 -1769682147,442617088,4.166858196258545,0.009953975677490234,610.0501098632812 -1769682147,475709440,4.167370796203613,0.009914875030517578,610.0516357421875 -1769682147,510286848,4.167761325836182,0.009852766990661621,610.0527954101562 -1769682147,542663424,4.1681365966796875,0.009779632091522217,610.0540161132812 -1769682147,573591808,4.1686110496521,0.009648621082305908,610.0557250976562 -1769682147,606907904,4.169000625610352,0.009563982486724854,610.0570068359375 -1769682147,644036608,4.169506072998047,0.009468495845794678,610.058837890625 -1769682147,675842560,4.169894695281982,0.009417712688446045,610.0601806640625 -1769682147,708522752,4.170287132263184,0.009377896785736084,610.0616455078125 -1769682147,741169920,4.170673847198486,0.009372889995574951,610.0631713867188 -1769682147,774535680,4.171182632446289,0.0093308687210083,610.0652465820312 -1769682147,808943616,4.171590805053711,0.009325683116912842,610.06689453125 -1769682147,853164800,4.172131538391113,0.009346306324005127,610.0689086914062 -1769682147,873748224,4.172533988952637,0.009379804134368896,610.0704345703125 -1769682147,907412480,4.172974586486816,0.00941312313079834,610.07177734375 -1769682147,958771712,4.17356538772583,0.009532690048217773,610.0735473632812 -1769682147,973082112,4.17400598526001,0.009641945362091064,610.0747680664062 -1769682148,7552512,4.174458026885986,0.009745001792907715,610.0759887695312 -1769682148,53312768,4.174914360046387,0.009853899478912354,610.0770874023438 -1769682148,73720576,4.175532341003418,0.009939908981323242,610.07861328125 -1769682148,108430592,4.175997734069824,0.00999671220779419,610.07958984375 -1769682148,142911488,4.176455497741699,0.010054171085357666,610.08056640625 -1769682148,173828352,4.177006721496582,0.010041654109954834,610.0819091796875 -1769682148,207656704,4.1774187088012695,0.00999230146408081,610.082763671875 -1769682148,240737792,4.177818298339844,0.009933888912200928,610.083740234375 -1769682148,273802240,4.1783318519592285,0.00984114408493042,610.0848999023438 -1769682148,309398528,4.178715705871582,0.00977170467376709,610.0857543945312 -1769682148,342603776,4.179093837738037,0.009711742401123047,610.086669921875 -1769682148,374887680,4.179563999176025,0.009620428085327148,610.0880126953125 -1769682148,407001856,4.179905891418457,0.009582340717315674,610.0890502929688 -1769682148,456875776,4.180308818817139,0.009506702423095703,610.0905151367188 -1769682148,476112640,4.180544376373291,0.009443163871765137,610.091552734375 -1769682148,507290624,4.180795192718506,0.009387373924255371,610.0925903320312 -1769682148,544156160,4.181121349334717,0.009370625019073486,610.09375 -1769682148,579898624,4.181352138519287,0.009366095066070557,610.0944213867188 -1769682148,609075968,4.181670665740967,0.009430348873138428,610.0949096679688 -1769682148,645202432,4.1820902824401855,0.009543240070343018,610.0950927734375 -1769682148,673667328,4.182392597198486,0.009619832038879395,610.0950927734375 -1769682148,708734720,4.182790756225586,0.009697973728179932,610.094970703125 -1769682148,746132736,4.183297634124756,0.009770095348358154,610.0946044921875 -1769682148,775241728,4.183737277984619,0.009806156158447266,610.0942993164062 -1769682148,808843264,4.184213638305664,0.009831428527832031,610.0939331054688 -1769682148,853282304,4.1848464012146,0.009864509105682373,610.0936889648438 -1769682148,874208000,4.185423851013184,0.009879231452941895,610.0933837890625 -1769682148,907043328,4.1860175132751465,0.009925127029418945,610.0933227539062 -1769682148,940161792,4.18661642074585,0.009978055953979492,610.09326171875 -1769682148,977589248,4.1874237060546875,0.010031282901763916,610.0932006835938 -1769682149,8341248,4.188103199005127,0.010053455829620361,610.09326171875 -1769682149,41005056,4.1888108253479,0.010071635246276855,610.0933837890625 -1769682149,73474048,4.189774036407471,0.010066390037536621,610.0936279296875 -1769682149,112133632,4.190545558929443,0.010028243064880371,610.0938720703125 -1769682149,144408576,4.191474437713623,0.009935319423675537,610.0942993164062 -1769682149,174872320,4.192193508148193,0.009863555431365967,610.0946044921875 -1769682149,206777088,4.192910194396973,0.009791433811187744,610.0950927734375 -1769682149,256440832,4.1938886642456055,0.009693324565887451,610.0956420898438 -1769682149,274349568,4.1946306228637695,0.009624123573303223,610.09619140625 -1769682149,307384320,4.195400714874268,0.009558439254760742,610.0968017578125 -1769682149,342465536,4.196182727813721,0.009503483772277832,610.0974731445312 -1769682149,375970560,4.197201251983643,0.009419143199920654,610.0985107421875 -1769682149,409616384,4.197969913482666,0.009366750717163086,610.0994873046875 -1769682149,441814272,4.1985650062561035,0.009311437606811523,610.1004028320312 -1769682149,473738752,4.19931697845459,0.009301900863647461,610.1018676757812 -1769682149,514326528,4.199843406677246,0.009320199489593506,610.1030883789062 -1769682149,548616704,4.20050048828125,0.009349703788757324,610.1047973632812 -1769682149,574917376,4.200978755950928,0.00939708948135376,610.1060791015625 -1769682149,607627520,4.201403617858887,0.009470582008361816,610.1075439453125 -1769682149,655545600,4.20193338394165,0.00953829288482666,610.1094970703125 -1769682149,673620480,4.2023024559021,0.009591519832611084,610.1109619140625 -1769682149,706967040,4.2026214599609375,0.009640634059906006,610.112548828125 -1769682149,740054784,4.202915191650391,0.009701728820800781,610.1141357421875 -1769682149,777042944,4.203294277191162,0.009744644165039062,610.1160888671875 -1769682149,807501568,4.203513145446777,0.009772717952728271,610.1176147460938 -1769682149,840704512,4.203671455383301,0.009818494319915771,610.1190185546875 -1769682149,875326464,4.203855514526367,0.009820818901062012,610.1209716796875 -1769682149,910196992,4.203971862792969,0.009797155857086182,610.1222534179688 -1769682149,942760960,4.203965187072754,0.009780585765838623,610.12353515625 -1769682149,974128896,4.2038774490356445,0.009725034236907959,610.125244140625 -1769682150,7343104,4.203752517700195,0.009695291519165039,610.12646484375 -1769682150,59496448,4.203420639038086,0.009654045104980469,610.1281127929688 -1769682150,66871040,4.203225135803223,0.009634613990783691,610.1289672851562 -1769682150,107593728,4.202552795410156,0.00955742597579956,610.1305541992188 -1769682150,142697984,4.201889991760254,0.009587585926055908,610.1317749023438 -1769682150,173655808,4.200879096984863,0.009612500667572021,610.1336059570312 -1769682150,208642816,4.200048446655273,0.009643375873565674,610.135009765625 -1769682150,242889472,4.199080467224121,0.009701073169708252,610.1362915039062 -1769682150,273683712,4.197723865509033,0.009756743907928467,610.1380615234375 -1769682150,307159296,4.196598052978516,0.009798645973205566,610.1392822265625 -1769682150,346964224,4.194958209991455,0.009875178337097168,610.1408081054688 -1769682150,375438848,4.193645477294922,0.009909868240356445,610.1417846679688 -1769682150,407685632,4.1922783851623535,0.009937644004821777,610.1427612304688 -1769682150,455304704,4.190806865692139,0.009975910186767578,610.1437377929688 -1769682150,474208256,4.188641548156738,0.01006382703781128,610.1449584960938 -1769682150,509699584,4.186916351318359,0.010151863098144531,610.1458740234375 -1769682150,540657920,4.18510627746582,0.010243654251098633,610.1469116210938 -1769682150,573822720,4.182648181915283,0.010293364524841309,610.148193359375 -1769682150,607581184,4.180716514587402,0.010307610034942627,610.1492919921875 -1769682150,645752320,4.178023815155029,0.010316967964172363,610.1508178710938 -1769682150,675795456,4.175927639007568,0.010313153266906738,610.1519775390625 -1769682150,709674240,4.173763751983643,0.010301530361175537,610.1531982421875 -1769682150,758918656,4.17063045501709,0.01027977466583252,610.1549682617188 -1769682150,773394688,4.168251037597656,0.010268807411193848,610.1563720703125 -1769682150,807253504,4.1658172607421875,0.010251104831695557,610.1578979492188 -1769682150,850046976,4.163252353668213,0.010259091854095459,610.159423828125 -1769682150,874656768,4.1597466468811035,0.010250985622406006,610.1614379882812 -1769682150,909593344,4.157052516937256,0.010206282138824463,610.1629028320312 -1769682150,940388352,4.154293060302734,0.010167181491851807,610.1642456054688 -1769682150,980020736,4.150495529174805,0.010069727897644043,610.1658935546875 -1769682151,25555712,4.147502899169922,0.010003447532653809,610.1671142578125 -1769682151,48842752,4.143340110778809,0.00991743803024292,610.1687622070312 -1769682151,73741824,4.1400885581970215,0.009847819805145264,610.1701049804688 -1769682151,110963200,4.1367316246032715,0.009771585464477539,610.1715087890625 -1769682151,143568896,4.133193016052246,0.00979381799697876,610.1731567382812 -1769682151,173761792,4.128373622894287,0.009799480438232422,610.17578125 -1769682151,207614208,4.124713897705078,0.009829521179199219,610.1778564453125 -1769682151,256293888,4.119583606719971,0.009879767894744873,610.1808471679688 -1769682151,273953792,4.1156005859375,0.009930789470672607,610.1832885742188 -1769682151,307443456,4.1115031242370605,0.009974479675292969,610.1856689453125 -1769682151,340240128,4.10732889175415,0.01003962755203247,610.18798828125 -1769682151,377947136,4.10156774520874,0.01008683443069458,610.1911010742188 -1769682151,408153856,4.097204685211182,0.010140299797058105,610.1932983398438 -1769682151,448256768,4.091022491455078,0.010226905345916748,610.1961669921875 -1769682151,474999040,4.086280822753906,0.010304629802703857,610.1981201171875 -1769682151,510131712,4.081300258636475,0.010409653186798096,610.1998901367188 -1769682151,541193472,4.07622766494751,0.01052933931350708,610.2015380859375 -1769682151,575589376,4.069199085235596,0.010637104511260986,610.2035522460938 -1769682151,607296256,4.063769817352295,0.010659992694854736,610.2049560546875 -1769682151,655239680,4.056307315826416,0.010676145553588867,610.2067260742188 -1769682151,674028544,4.050633907318115,0.010684967041015625,610.2080688476562 -1769682151,709595904,4.044864177703857,0.010692298412322998,610.2092895507812 -1769682151,741744640,4.038815975189209,0.010711252689361572,610.2105102539062 -1769682151,780445184,4.030640602111816,0.010720551013946533,610.2120971679688 -1769682151,807753728,4.024347305297852,0.01073378324508667,610.2132568359375 -1769682151,843483904,4.017888069152832,0.010766983032226562,610.2142944335938 -1769682151,875047424,4.009038925170898,0.010773539543151855,610.2156372070312 -1769682151,914775040,4.002269744873047,0.010784924030303955,610.2166748046875 -1769682151,944506368,3.9930381774902344,0.01079171895980835,610.2178344726562 -1769682151,974579968,3.9860215187072754,0.0107574462890625,610.2186889648438 -1769682152,10848000,3.9788451194763184,0.010717809200286865,610.2195434570312 -1769682152,55534592,3.968940496444702,0.010665059089660645,610.220703125 -1769682152,74032640,3.9613571166992188,0.010632812976837158,610.2215576171875 -1769682152,107223808,3.953627824783325,0.010607302188873291,610.2225341796875 -1769682152,140238080,3.9457502365112305,0.010595440864562988,610.2235107421875 -1769682152,175441920,3.9350497722625732,0.01061701774597168,610.224853515625 -1769682152,208424448,3.926842212677002,0.010687053203582764,610.2258911132812 -1769682152,244481536,3.9184508323669434,0.01078331470489502,610.2267456054688 -1769682152,274681344,3.9069395065307617,0.010920226573944092,610.2278442382812 -1769682152,308867072,3.8981809616088867,0.011027932167053223,610.2283325195312 -1769682152,341105152,3.8892035484313965,0.011143326759338379,610.228759765625 -1769682152,374084864,3.877136707305908,0.011290431022644043,610.2288818359375 -1769682152,407562496,3.867902994155884,0.011392056941986084,610.228759765625 -1769682152,444598528,3.855412006378174,0.011503040790557861,610.2282104492188 -1769682152,475884800,3.845940113067627,0.011572003364562988,610.2276611328125 -1769682152,508096768,3.8362839221954346,0.011636734008789062,610.22705078125 -1769682152,554583808,3.826418876647949,0.011690974235534668,610.2262573242188 -1769682152,574641920,3.812833786010742,0.011763811111450195,610.22509765625 -1769682152,608130304,3.802499771118164,0.011794447898864746,610.2239990234375 -1769682152,640872192,3.7919318675994873,0.011819899082183838,610.2227783203125 -1769682152,674258176,3.777663230895996,0.011859238147735596,610.220947265625 -1769682152,707463424,3.7668750286102295,0.01187354326248169,610.2192993164062 -1769682152,744723200,3.752279043197632,0.011889815330505371,610.2167358398438 -1769682152,774429440,3.74112606048584,0.01191413402557373,610.2145385742188 -1769682152,808457728,3.7297897338867188,0.011943697929382324,610.2122192382812 -1769682152,846420992,3.714541435241699,0.011997580528259277,610.2088012695312 -1769682152,874407168,3.702876329421997,0.01205211877822876,610.2060546875 -1769682152,907208192,3.6911532878875732,0.01212233304977417,610.203125 -1769682152,960151040,3.675363063812256,0.012241661548614502,610.1987915039062 -1769682152,968324352,3.6673672199249268,0.012288153171539307,610.1964111328125 -1769682153,8313344,3.6511523723602295,0.012452363967895508,610.1914672851562 -1769682153,41080576,3.6388487815856934,0.012518465518951416,610.187255859375 -1769682153,75300096,3.6222219467163086,0.012719333171844482,610.181396484375 -1769682153,111290880,3.6095967292785645,0.012852787971496582,610.1767578125 -1769682153,143523328,3.596879482269287,0.01291656494140625,610.1719970703125 -1769682153,174223104,3.5796549320220947,0.013097941875457764,610.1654663085938 -1769682153,207468544,3.56675386428833,0.01317131519317627,610.160400390625 -1769682153,259376640,3.5493357181549072,0.013243496417999268,610.1537475585938 -1769682153,274945024,3.5360107421875,0.013287007808685303,610.148681640625 -1769682153,307624448,3.5225017070770264,0.013336002826690674,610.143798828125 -1769682153,355857920,3.5042710304260254,0.013364136219024658,610.1371459960938 -1769682153,374384640,3.490471839904785,0.01337122917175293,610.1321411132812 -1769682153,408009216,3.476619243621826,0.013372659683227539,610.1270751953125 -1769682153,442157824,3.462653636932373,0.013320982456207275,610.1218872070312 -1769682153,478417664,3.443861722946167,0.013373374938964844,610.1149291992188 -1769682153,509928192,3.429675340652466,0.013371527194976807,610.109619140625 -1769682153,545704192,3.410494089126587,0.013365983963012695,610.1024780273438 -1769682153,574413824,3.3960494995117188,0.013366758823394775,610.0971069335938 -1769682153,612193792,3.381523847579956,0.01336759328842163,610.0916748046875 -1769682153,643447040,3.366849422454834,0.013324320316314697,610.0863647460938 -1769682153,675359232,3.3471243381500244,0.013403892517089844,610.0791625976562 -1769682153,707579904,3.3322315216064453,0.013432621955871582,610.0736694335938 -1769682153,758601984,3.3123881816864014,0.013464033603668213,610.06640625 -1769682153,768521216,3.3022701740264893,0.013423621654510498,610.0626831054688 -1769682153,824288512,3.281766653060913,0.01333630084991455,610.054931640625 -1769682153,843009280,3.2662739753723145,0.01316988468170166,610.0488891601562 -1769682153,875226624,3.2454111576080322,0.01313704252243042,610.04052734375 -1769682153,907272448,3.2297141551971436,0.013104557991027832,610.033935546875 -1769682153,943097600,3.213921308517456,0.013027429580688477,610.0272216796875 -1769682153,974233600,3.192803382873535,0.013100504875183105,610.0178833007812 -1769682154,25802496,3.1768457889556885,0.013103306293487549,610.0106811523438 -1769682154,56696832,3.155573606491089,0.013113081455230713,610.0010986328125 -1769682154,70071552,3.14485764503479,0.013056695461273193,609.9961547851562 -1769682154,108575488,3.1231300830841064,0.013110458850860596,609.986572265625 -1769682154,140881920,3.106722831726074,0.013048291206359863,609.9794921875 -1769682154,179867648,3.084681272506714,0.013086438179016113,609.97021484375 -1769682154,207636224,3.0681209564208984,0.013070106506347656,609.96337890625 -1769682154,242939136,3.0515472888946533,0.013000071048736572,609.9567260742188 -1769682154,275214592,3.029376983642578,0.013045132160186768,609.9480590820312 -1769682154,313399296,3.0125880241394043,0.013039588928222656,609.941650390625 -1769682154,343321088,2.9958014488220215,0.012946724891662598,609.935302734375 -1769682154,375003648,2.9732558727264404,0.013058960437774658,609.9273071289062 -1769682154,407636224,2.956357955932617,0.01317906379699707,609.9217529296875 -1769682154,448773632,2.933652639389038,0.013369441032409668,609.91455078125 -1769682154,474629632,2.916639804840088,0.013521909713745117,609.9093017578125 -1769682154,507816448,2.899543046951294,0.013669788837432861,609.9039916992188 -1769682154,540397312,2.882406711578369,0.013780653476715088,609.8985595703125 -1769682154,580105984,2.8594398498535156,0.01400679349899292,609.8910522460938 -1769682154,609966080,2.842013120651245,0.014123201370239258,609.88525390625 -1769682154,642695936,2.824591636657715,0.01415950059890747,609.8792724609375 -1769682154,675347456,2.8010873794555664,0.014275670051574707,609.87109375 -1769682154,709556992,2.783341646194458,0.014215052127838135,609.8646850585938 -1769682154,741280256,2.765533924102783,0.014069616794586182,609.8582153320312 -1769682154,774105856,2.741701126098633,0.013968557119369507,609.8494873046875 -1769682154,808598784,2.723646879196167,0.013868540525436401,609.8428344726562 -1769682154,856766720,2.699434280395508,0.013764351606369019,609.8341064453125 -1769682154,874046208,2.6811912059783936,0.013718247413635254,609.8274536132812 -1769682154,907505408,2.6628706455230713,0.013693422079086304,609.8206787109375 -1769682154,942071040,2.6445584297180176,0.013630986213684082,609.8139038085938 -1769682157,982116096,0.0,-0.0,609.8541259765625 -1769682158,7977216,0.0,-0.0,609.8541259765625 -1769682158,45611264,0.0,-0.0,609.8541259765625 -1769682158,74780928,0.0,-0.0,609.8541259765625 -1769682158,110979840,0.0,-0.0,609.8541259765625 -1769682158,150271488,0.0,-0.0,609.8541259765625 -1769682158,176170752,0.0,-0.0,609.8541259765625 -1769682158,207754752,0.0,-0.0,609.8541259765625 -1769682158,259920128,0.0,-0.0,609.8541259765625 -1769682158,269520640,0.0,-0.0,609.8541259765625 -1769682158,308075264,0.0,-0.0,609.8541259765625 -1769682158,341237760,0.0,-0.0,609.8541259765625 -1769682158,376476416,0.0,-0.0,609.8541259765625 -1769682158,411150080,0.0,-0.0,609.8541259765625 -1769682158,444909312,0.0,-0.0,609.8541259765625 -1769682158,474940416,0.0,-0.0,609.8541259765625 -1769682158,511097344,0.0,-0.0,609.8541259765625 -1769682158,545890048,0.0,-0.0,609.8541259765625 -1769682158,575280640,0.0,-0.0,609.8541259765625 -1769682158,608097024,0.0,-0.0,609.8541259765625 -1769682158,660713728,0.0,-0.0,609.8541259765625 -1769682158,668152320,0.0,-0.0,609.8541259765625 -1769682158,709788928,0.0,-0.0,609.8541259765625 -1769682158,753166080,0.0,-0.0,609.8541259765625 -1769682158,775462144,0.0,-0.0,609.8541259765625 -1769682158,801373952,0.0,-0.0,609.8541259765625 -1769682158,845110272,0.0,-0.0,609.8541259765625 -1769682158,874618880,0.0,-0.0,609.8541259765625 -1769682158,909497344,0.0,-0.0,609.8541259765625 -1769682158,956896256,0.0,-0.0,609.8541259765625 -1769682158,974360832,0.0,-0.0,609.8541259765625 -1769682159,8856320,0.0,-0.0,609.8541259765625 -1769682159,54490624,0.0,-0.0,609.8541259765625 -1769682159,75139072,0.0,-0.0,609.8541259765625 -1769682159,108480768,0.0,-0.0,609.8541259765625 -1769682159,146513152,0.0,-0.0,609.8541259765625 -1769682159,175200000,0.0,-0.0,609.8541259765625 -1769682159,209602560,0.0,-0.0,609.8541259765625 -1769682159,246182400,0.0,-0.0,609.8541259765625 -1769682159,274810880,0.0,-0.0,609.8541259765625 -1769682159,307977472,0.01646745391190052,0.002282199449837208,609.8528442382812 -1769682159,341676032,0.03290480747818947,0.003522201906889677,609.8486328125 -1769682159,375904512,0.054711904376745224,0.004959048703312874,609.8405151367188 -1769682159,409948160,0.07100990414619446,0.005990112200379372,609.8338623046875 -1769682159,455758336,0.08719686418771744,0.006970844231545925,609.8272094726562 -1769682159,475392000,0.10890986025333405,0.00814834050834179,609.8192749023438 -1769682159,508088576,0.12524712085723877,0.008904190734028816,609.8139038085938 -1769682159,549371904,0.147283673286438,0.009732630103826523,609.8073120117188 -1769682159,574764544,0.16369718313217163,0.010202677920460701,609.8029174804688 -1769682159,608636672,0.1799885779619217,0.010559998452663422,609.7985229492188 -1769682159,647462656,0.20200471580028534,0.010872066020965576,609.7929077148438 -1769682159,674899200,0.21894554793834686,0.011007867753505707,609.7885131835938 -1769682159,709126400,0.236598938703537,0.011078529059886932,609.7838134765625 -1769682159,744195584,0.25536221265792847,0.011098340153694153,609.77880859375 -1769682159,776418048,0.28082194924354553,0.011094525456428528,609.7715454101562 -1769682159,808638208,0.29986998438835144,0.011066999286413193,609.7656860351562 -1769682159,844850176,0.3273927569389343,0.011023081839084625,609.7572021484375 -1769682159,874690304,0.34844765067100525,0.01099368929862976,609.75048828125 -1769682159,908705792,0.370537668466568,0.010978929698467255,609.743408203125 -1769682159,942390784,0.3931029736995697,0.010969884693622589,609.7359619140625 -1769682159,975007232,0.4242825508117676,0.010989420115947723,609.7254028320312 -1769682160,10759936,0.44760531187057495,0.011018015444278717,609.7171630859375 -1769682160,43973632,0.48024895787239075,0.01107625663280487,609.70556640625 -1769682160,74629888,0.5048568844795227,0.011134237051010132,609.696533203125 -1769682160,107990016,0.530433177947998,0.0112062469124794,609.6871337890625 -1769682160,142672640,0.5565781593322754,0.011269040405750275,609.6773071289062 -1769682160,176081408,0.591789960861206,0.01140543818473816,609.66357421875 -1769682160,208673280,0.6183471083641052,0.01150195300579071,609.6527709960938 -1769682160,255010816,0.6451399922370911,0.011579707264900208,609.6416625976562 -1769682160,275375104,0.6812154054641724,0.011712424457073212,609.6261596679688 -1769682160,311536896,0.7084360122680664,0.011777892708778381,609.6140747070312 -1769682160,342540544,0.7362242937088013,0.011827915906906128,609.6014404296875 -1769682160,374998784,0.7709525227546692,0.011938661336898804,609.5840454101562 -1769682160,408814592,0.7949067950248718,0.011979565024375916,609.5707397460938 -1769682160,445470976,0.827975869178772,0.01203659176826477,609.5529174804688 -1769682160,475069440,0.8540663719177246,0.012073129415512085,609.5391235351562 -1769682160,508422144,0.880544126033783,0.01211501657962799,609.5250244140625 -1769682160,560755200,0.916264533996582,0.01216837763786316,609.5055541992188 -1769682160,569861376,0.9342669248580933,0.012174814939498901,609.49560546875 -1769682160,609225216,0.9705340266227722,0.012247473001480103,609.4754638671875 -1769682160,657721600,0.9979514479637146,0.012238562107086182,609.4598999023438 -1769682160,674695168,1.0340549945831299,0.012331604957580566,609.4389038085938 -1769682160,709295872,1.059652328491211,0.012363553047180176,609.423095703125 -1769682160,741261312,1.0858134031295776,0.012344449758529663,609.4072265625 -1769682160,775015168,1.1216702461242676,0.012425631284713745,609.3858032226562 -1769682160,808281856,1.1486177444458008,0.012446701526641846,609.36962890625 -1769682160,842105856,1.1757131814956665,0.01240547001361847,609.3533325195312 -1769682160,874878720,1.2120839357376099,0.012464761734008789,609.3314819335938 -1769682160,910625280,1.239471197128296,0.012469083070755005,609.3148803710938 -1769682160,959722240,1.2762112617492676,0.012463688850402832,609.292724609375 -1769682160,974626560,1.303755283355713,0.012461289763450623,609.2760009765625 -1769682161,8751872,1.3311381340026855,0.012460440397262573,609.25927734375 -1769682161,55447296,1.3581188917160034,0.01241368055343628,609.2424926757812 -1769682161,76645632,1.3921279907226562,0.012538939714431763,609.2200317382812 -1769682161,108696064,1.4175803661346436,0.012601912021636963,609.203125 -1769682161,145705728,1.450742483139038,0.012693285942077637,609.1802978515625 -1769682161,175143936,1.4762427806854248,0.012761682271957397,609.1629638671875 -1769682161,211955712,1.5022491216659546,0.012817680835723877,609.1453857421875 -1769682161,247956480,1.5370653867721558,0.012861132621765137,609.12158203125 -1769682161,274866432,1.5630992650985718,0.012862145900726318,609.1036376953125 -1769682161,308525056,1.5889863967895508,0.012852966785430908,609.0856323242188 -1769682161,346327808,1.6237523555755615,0.01282164454460144,609.061767578125 -1769682161,376724480,1.649837613105774,0.012782573699951172,609.0438842773438 -1769682161,408233728,1.6760351657867432,0.01273927092552185,609.0261840820312 -1769682161,455304448,1.7022013664245605,0.012616991996765137,609.0084838867188 -1769682161,476551680,1.736817479133606,0.012648016214370728,608.9850463867188 -1769682161,510056960,1.7626832723617554,0.012602001428604126,608.9675903320312 -1769682161,542497024,1.7886300086975098,0.012419551610946655,608.9501953125 -1769682161,575408640,1.8229920864105225,0.012394577264785767,608.927001953125 -1769682161,609777152,1.8488481044769287,0.012311547994613647,608.90966796875 -1769682161,643502592,1.874475359916687,0.012140631675720215,608.892333984375 -1769682161,675189248,1.9085307121276855,0.012136220932006836,608.8693237304688 -1769682161,713743872,1.9340606927871704,0.012086570262908936,608.8521118164062 -1769682161,747100416,1.96803617477417,0.012460947036743164,608.8284912109375 -1769682161,775427328,1.9934505224227905,0.012623369693756104,608.8095092773438 -1769682161,810949120,2.018716812133789,0.012852996587753296,608.789306640625 -1769682161,855930112,2.0523219108581543,0.013163000345230103,608.7610473632812 -1769682161,877524736,2.0774264335632324,0.013383686542510986,608.7389526367188 -1769682161,909005568,2.1023244857788086,0.013567745685577393,608.7164916992188 -1769682161,941321728,2.1273367404937744,0.013577520847320557,608.693603515625 -1769682161,978339072,2.160439968109131,0.013830244541168213,608.6629028320312 -1769682162,9884928,2.1850132942199707,0.01387721300125122,608.6398315429688 -1769682162,53231104,2.217526912689209,0.013905256986618042,608.609130859375 -1769682162,75261952,2.2417376041412354,0.01390048861503601,608.5863037109375 -1769682162,111545088,2.2658398151397705,0.013882935047149658,608.5635986328125 -1769682162,149219840,2.297828197479248,0.013843894004821777,608.5333862304688 -1769682162,176237824,2.3217642307281494,0.013829171657562256,608.5108032226562 -1769682162,208897536,2.345494270324707,0.01382705569267273,608.4882202148438 -1769682162,257341440,2.3767762184143066,0.01386365294456482,608.4579467773438 -1769682162,274774272,2.399993896484375,0.013914406299591064,608.4349975585938 -1769682162,308610816,2.4230360984802246,0.013965129852294922,608.411865234375 -1769682162,342314496,2.445993185043335,0.013848066329956055,608.388427734375 -1769682162,376720640,2.4763052463531494,0.014042645692825317,608.3568725585938 -1769682162,408786176,2.4989757537841797,0.01403820514678955,608.3331298828125 -1769682162,441836032,2.521449327468872,0.013844996690750122,608.3093872070312 -1769682162,475535616,2.551119089126587,0.014005392789840698,608.2782592773438 -1769682162,509939456,2.573093891143799,0.01400226354598999,608.2553100585938 -1769682162,546019328,2.602012872695923,0.013974249362945557,608.2251586914062 -1769682162,575945728,2.6234090328216553,0.014230966567993164,608.2030029296875 -1769682162,611579648,2.6446731090545654,0.014332413673400879,608.1815795898438 -1769682162,655239680,2.672837257385254,0.014872431755065918,608.1549072265625 -1769682162,675508224,2.693711280822754,0.015173733234405518,608.1364135742188 -1769682162,710067200,2.7143514156341553,0.015458464622497559,608.1187133789062 -1769682162,754880768,2.7348527908325195,0.015597999095916748,608.1016845703125 -1769682162,776077312,2.7620017528533936,0.01591724157333374,608.07958984375 -1769682162,810889472,2.782087802886963,0.016011297702789307,608.063232421875 -1769682162,844334848,2.8084208965301514,0.016093790531158447,608.0415649414062 -1769682162,874977536,2.828080415725708,0.01613539457321167,608.025390625 -1769682162,910836224,2.8475472927093506,0.016157984733581543,608.0091552734375 -1769682162,946242304,2.8730454444885254,0.016182422637939453,607.987548828125 -1769682162,975181568,2.8920109272003174,0.016217529773712158,607.97119140625 -1769682163,8354304,2.9107143878936768,0.016258060932159424,607.9546508789062 -1769682163,43105280,2.929169178009033,0.01614069938659668,607.9379272460938 -1769682163,76742400,2.953425168991089,0.016383588314056396,607.9152221679688 -1769682163,110369280,2.9715118408203125,0.016444146633148193,607.8978881835938 -1769682163,153450240,2.9892659187316895,0.016354024410247803,607.8802490234375 -1769682163,175597312,3.0128273963928223,0.016579627990722656,607.8563232421875 -1769682163,209175040,3.0301272869110107,0.016660749912261963,607.8381958007812 -1769682163,242917888,3.0473222732543945,0.016544103622436523,607.8198852539062 -1769682163,275949056,3.07014799118042,0.016532599925994873,607.7953491210938 -1769682163,308663040,3.0871262550354004,0.016357243061065674,607.7769165039062 -1769682163,341902336,3.103726387023926,0.016025424003601074,607.7583618164062 -1769682163,375122176,3.125554323196411,0.0160028338432312,607.7337036132812 -1769682163,410674688,3.1418497562408447,0.015874624252319336,607.7150268554688 -1769682163,447184896,3.1632580757141113,0.015797972679138184,607.6900024414062 -1769682163,476054784,3.1792707443237305,0.015816152095794678,607.6710815429688 -1769682163,510028800,3.195176839828491,0.0158500075340271,607.6519165039062 -1769682163,554732032,3.2109549045562744,0.015700101852416992,607.6326293945312 -1769682163,577157120,3.231785774230957,0.01594299077987671,607.6066284179688 -1769682163,610450176,3.2470571994781494,0.015986323356628418,607.587158203125 -1769682163,643133952,3.262247323989868,0.015829622745513916,607.5675659179688 -1769682163,675111936,3.2822277545928955,0.016084790229797363,607.5414428710938 -1769682163,711432704,3.297149419784546,0.016127347946166992,607.5218505859375 -1769682163,752929280,3.3166940212249756,0.01619243621826172,607.49560546875 -1769682163,775144448,3.3312554359436035,0.0162506103515625,607.4757690429688 -1769682163,808502528,3.3457438945770264,0.016315102577209473,607.4557495117188 -1769682163,855909376,3.3649446964263916,0.01636403799057007,607.428955078125 -1769682163,876311296,3.3791770935058594,0.016524910926818848,607.408935546875 -1769682163,910883072,3.3932409286499023,0.016732215881347656,607.388916015625 -1769682163,942364416,3.4071474075317383,0.01673710346221924,607.3689575195312 -1769682163,979011328,3.425553798675537,0.017170369625091553,607.3424072265625 -1769682164,8772608,3.4391748905181885,0.017312586307525635,607.322509765625 -1769682164,42528512,3.452681064605713,0.017225682735443115,607.3025512695312 -1769682164,76221696,3.4702377319335938,0.017589271068572998,607.2764282226562 -1769682164,110121728,3.483264446258545,0.017532944679260254,607.2567749023438 -1769682164,154144768,3.5004780292510986,0.01728212833404541,607.2302856445312 -1769682164,175317760,3.5132572650909424,0.017062067985534668,607.210205078125 -1769682164,211817984,3.525886297225952,0.016844332218170166,607.1898803710938 -1769682164,262412288,3.5424458980560303,0.016557395458221436,607.16259765625 -1769682164,269716224,3.5506670475006104,0.01629239320755005,607.14892578125 -1769682164,308942336,3.566924571990967,0.016193270683288574,607.12158203125 -1769682164,355304704,3.5790538787841797,0.015842020511627197,607.1008911132812 -1769682164,376931840,3.5950329303741455,0.015932857990264893,607.0734252929688 -1769682164,409449984,3.606674909591675,0.015972435474395752,607.0527954101562 -1769682164,442369792,3.6178481578826904,0.016072750091552734,607.0320434570312 -1769682164,475657728,3.632627010345459,0.01642298698425293,607.0037841796875 -1769682164,511329792,3.6437196731567383,0.01611393690109253,606.9818725585938 -1769682164,543739136,3.654733657836914,0.015419483184814453,606.959716796875 -1769682164,575518720,3.6691198348999023,0.015093743801116943,606.9293823242188 -1769682164,609801216,3.6798341274261475,0.014673113822937012,606.90625 -1769682164,653457152,3.6940035820007324,0.014105081558227539,606.8751220703125 -1769682164,676336128,3.704512119293213,0.01384824514389038,606.8517456054688 -1769682164,708782336,3.7148847579956055,0.01367419958114624,606.8284912109375 -1769682164,758854656,3.7285518646240234,0.013523995876312256,606.7977294921875 -1769682164,775134720,3.738670825958252,0.013479650020599365,606.7749633789062 -1769682164,809029632,3.7486586570739746,0.013517439365386963,606.7523193359375 -1769682164,841892608,3.7585277557373047,0.013386428356170654,606.7296142578125 -1769682164,877624320,3.7715110778808594,0.01389080286026001,606.69873046875 -1769682164,910970368,3.781156063079834,0.014071226119995117,606.6749877929688 -1769682164,943282944,3.7905871868133545,0.013885974884033203,606.6508178710938 -1769682164,976139776,3.8030667304992676,0.014117419719696045,606.618408203125 -1769682165,8775936,3.8123199939727783,0.013984918594360352,606.5945434570312 -1769682165,43683328,3.821629762649536,0.013856828212738037,606.5717163085938 -1769682165,75913472,3.8339316844940186,0.014841139316558838,606.5426025390625 -1769682165,110402304,3.842961311340332,0.015552222728729248,606.5209350585938 -1769682165,161769984,3.854459762573242,0.01662057638168335,606.4910888671875 -1769682165,169584896,3.859811782836914,0.017272114753723145,606.4756469726562 -1769682165,209779456,3.870436906814575,0.018529832363128662,606.443115234375 -1769682165,255425536,3.87848162651062,0.018391847610473633,606.417236328125 -1769682165,275850752,3.889073610305786,0.01820695400238037,606.3804931640625 -1769682165,309037056,3.896923542022705,0.017592549324035645,606.3522338867188 -1769682165,341874176,3.9047048091888428,0.01656949520111084,606.3240356445312 -1769682165,378570240,3.914886474609375,0.01588970422744751,606.2872314453125 -1769682165,409351424,3.922304391860962,0.015193521976470947,606.2604370117188 -1769682165,442383616,3.9296960830688477,0.014281749725341797,606.234375 -1769682165,475247616,3.9391672611236572,0.014080047607421875,606.2006225585938 -1769682165,508638208,3.9459543228149414,0.01391756534576416,606.1759033203125 -1769682165,546741248,3.954793691635132,0.013604342937469482,606.1428833007812 -1769682165,576824064,3.9614431858062744,0.013301491737365723,606.1182250976562 -1769682165,610749184,3.9681649208068848,0.012712299823760986,606.0936279296875 -1769682165,657160448,3.9769973754882812,0.011574089527130127,606.0613403320312 -1769682165,676114944,3.983494997024536,0.010719001293182373,606.0375366210938 -1769682165,711693568,3.9898715019226074,0.009911835193634033,606.0142211914062 -1769682165,742373120,3.9963440895080566,0.00879216194152832,605.9915771484375 -1769682165,777067520,4.004955768585205,0.008532822132110596,605.9623413085938 -1769682165,809374976,4.011302947998047,0.008350253105163574,605.9413452148438 -1769682165,842765056,4.017592430114746,0.008020997047424316,605.9212036132812 -1769682165,875763200,4.025821685791016,0.008205175399780273,605.8953857421875 -1769682165,911261440,4.031863212585449,0.008227705955505371,605.876953125 -1769682165,951361280,4.039773941040039,0.008290410041809082,605.8530883789062 -1769682165,975710720,4.0455522537231445,0.008346140384674072,605.8355712890625 -1769682166,11572224,4.05123233795166,0.008401691913604736,605.8184814453125 -1769682166,56633344,4.058640480041504,0.008457183837890625,605.7960815429688 -1769682166,76251392,4.064072132110596,0.00848078727722168,605.7794799804688 -1769682166,108980224,4.069640159606934,0.008458733558654785,605.7634887695312 -1769682166,142361600,4.075040340423584,0.008735120296478271,605.748779296875 -1769682166,177635584,4.0816144943237305,0.009840726852416992,605.73095703125 -1769682166,209591808,4.086211204528809,0.01051020622253418,605.71875 -1769682166,243649280,4.090724468231201,0.010831773281097412,605.7072143554688 -1769682166,275504384,4.0966410636901855,0.011296272277832031,605.6926879882812 -1769682166,315288832,4.101154327392578,0.010915040969848633,605.6815795898438 -1769682166,350299392,4.106945514678955,0.01003497838973999,605.6659545898438 -1769682166,375956224,4.111240386962891,0.009320616722106934,605.6537475585938 -1769682166,409647616,4.115447521209717,0.008620381355285645,605.641357421875 -1769682166,464290816,4.1207380294799805,0.007775425910949707,605.6246948242188 -1769682166,473918464,4.12328577041626,0.007240235805511475,605.6162109375 -1769682166,511500288,4.128195285797119,0.006797671318054199,605.5993041992188 -1769682166,542010624,4.131783962249756,0.0062334537506103516,605.5867309570312 -1769682166,575883520,4.136383533477783,0.0059326887130737305,605.5699462890625 -1769682166,609088512,4.139754772186279,0.005659699440002441,605.5576782226562 -1769682166,656256256,4.144172668457031,0.005130350589752197,605.5416870117188 -1769682166,675736832,4.147459506988525,0.004452943801879883,605.5302124023438 -1769682166,708915968,4.150649547576904,0.0037741661071777344,605.51904296875 -1769682166,757613568,4.154653549194336,0.002956867218017578,605.5046997070312 -1769682166,778890496,4.157773494720459,0.0022693872451782227,605.4942016601562 -1769682166,809025792,4.160900115966797,0.002098977565765381,605.48388671875 -1769682166,854143488,4.163904666900635,0.0020659565925598145,605.4739379882812 -1769682166,876664064,4.167781352996826,0.0024036765098571777,605.4612426757812 -1769682166,911178496,4.170591354370117,0.002604663372039795,605.4520263671875 -1769682166,943397888,4.173277378082275,0.0027047395706176758,605.4432373046875 -1769682166,975448832,4.176661968231201,0.003102123737335205,605.4318237304688 -1769682167,10996992,4.17912483215332,0.0032912492752075195,605.4234619140625 -1769682167,46495232,4.182202339172363,0.0034893155097961426,605.41259765625 -1769682167,76765184,4.184439182281494,0.0035952329635620117,605.404541015625 -1769682167,108891648,4.1866044998168945,0.003665030002593994,605.3966064453125 -1769682167,216501504,4.189613342285156,0.0037837624549865723,605.38671875 -1769682167,219961856,4.191899299621582,0.004238307476043701,605.3803100585938 -1769682167,226019584,4.193922519683838,0.004730403423309326,605.374755859375 -1769682167,253851904,4.1963791847229,0.0052964091300964355,605.3682250976562 -1769682167,272318720,4.197574615478516,0.005477786064147949,605.365234375 -1769682167,309945856,4.2000651359558105,0.005747973918914795,605.3597412109375 -1769682167,359183616,4.202544212341309,0.005275428295135498,605.3536987304688 -1769682167,376461056,4.204288482666016,0.004765927791595459,605.3486328125 -1769682167,409652480,4.205924987792969,0.00424426794052124,605.3433227539062 -1769682167,466672128,4.2080817222595215,0.0034992098808288574,605.3357543945312 -1769682167,476687872,4.209626197814941,0.003019869327545166,605.329833984375 -1769682167,508968192,4.211029052734375,0.0026396512985229492,605.3236694335938 -1769682167,546926080,4.212737560272217,0.0022333264350891113,605.3153076171875 -1769682167,576115200,4.213977813720703,0.0019965171813964844,605.3088989257812 -1769682167,609975296,4.21515417098999,0.001811981201171875,605.302490234375 -1769682167,647975936,4.216501712799072,0.0015993118286132812,605.2939453125 -1769682167,675715584,4.217456340789795,0.0013436079025268555,605.2876586914062 -1769682167,710079744,4.218306064605713,0.000998079776763916,605.2816162109375 -1769682167,768191744,4.219366073608398,0.0005605816841125488,605.273681640625 -1769682167,777322752,4.220128059387207,0.00027239322662353516,605.2680053710938 -1769682167,810837248,4.2209978103637695,-5.328655242919922e-05,605.2622680664062 -1769682167,855515904,4.2217817306518555,3.933906555175781e-06,605.2567138671875 -1769682167,876781312,4.22272253036499,0.00039827823638916016,605.2495727539062 -1769682167,910271232,4.223363876342773,0.0006633400917053223,605.244384765625 -1769682167,942560256,4.223821640014648,0.0008545517921447754,605.2393798828125 -1769682167,976292096,4.2243218421936035,0.0012028813362121582,605.2329711914062 -1769682168,10395904,4.224603652954102,0.001387953758239746,605.2284545898438 -1769682168,55503104,4.22480583190918,0.0015845894813537598,605.2225952148438 -1769682168,76695808,4.224925994873047,0.0016949772834777832,605.21826171875 -1769682168,109339136,4.225022792816162,0.001690506935119629,605.214111328125 -1769682168,156478208,4.225149154663086,0.0016532540321350098,605.20849609375 -1769682168,178605056,4.225240707397461,0.0018288493156433105,605.2048950195312 -1769682168,209070080,4.225282192230225,0.0020862817764282227,605.2015991210938 -1769682168,256652800,4.225193977355957,0.002307713031768799,605.1985473632812 -1769682168,292739840,4.2250237464904785,0.0026502609252929688,605.1950073242188 -1769682168,302810368,4.224889755249023,0.002747952938079834,605.1932983398438 -1769682168,345812224,4.224626541137695,0.0027331113815307617,605.1890258789062 -1769682168,375990784,4.224610805511475,0.0024598240852355957,605.18603515625 -1769682168,409364480,4.224783420562744,0.0018555521965026855,605.1826171875 -1769682168,442707456,4.224981307983398,0.0014551281929016113,605.178955078125 -1769682168,476308736,4.225281715393066,0.001201629638671875,605.1739501953125 -1769682168,510298624,4.225478649139404,0.0010368824005126953,605.1702270507812 -1769682168,545837824,4.225631237030029,0.0008813142776489258,605.1651000976562 -1769682168,576949504,4.225712776184082,0.0007950067520141602,605.1612548828125 -1769682168,609033728,4.225707530975342,0.000736534595489502,605.1574096679688 -1769682168,655070976,4.225661277770996,0.0006511807441711426,605.1536254882812 -1769682168,676261376,4.2255048751831055,0.0007179975509643555,605.148681640625 -1769682168,709504000,4.225235462188721,0.0008380413055419922,605.1450805664062 -1769682168,742473984,4.224941730499268,0.0009337663650512695,605.1414184570312 -1769682168,776783616,4.224538326263428,0.0011508464813232422,605.1369018554688 -1769682168,809430784,4.224174499511719,0.0011872649192810059,605.133544921875 -1769682168,842266624,4.223843574523926,0.0013611316680908203,605.13037109375 -1769682168,876441344,4.223463535308838,0.0017818808555603027,605.126220703125 -1769682168,909451264,4.222967147827148,0.0020515918731689453,605.123291015625 -1769682168,958291456,4.222324848175049,0.0023670196533203125,605.1194458007812 -1769682168,975666432,4.221876621246338,0.0025766491889953613,605.1166381835938 -1769682169,9710080,4.221271514892578,0.002750873565673828,605.1138305664062 -1769682169,44014592,4.220566272735596,0.002782762050628662,605.1097412109375 -1769682169,76231680,4.220324516296387,0.0025765299797058105,605.1062622070312 -1769682169,109955072,4.219885349273682,0.0025963187217712402,605.1027221679688 -1769682169,154535168,4.219212532043457,0.002710700035095215,605.0977172851562 -1769682169,176121344,4.218597888946533,0.0027534961700439453,605.0938720703125 -1769682169,209342976,4.217944145202637,0.002710998058319092,605.0895385742188 -1769682169,247121664,4.216921329498291,0.002601146697998047,605.0836791992188 -1769682169,276094720,4.216048240661621,0.002504587173461914,605.0792846679688 -1769682169,309453824,4.215079307556152,0.002391993999481201,605.0748291015625 -1769682169,360999680,4.214270114898682,0.0017154812812805176,605.0690307617188 -1769682169,370523648,4.213925838470459,0.0014687776565551758,605.0662841796875 -1769682169,409186304,4.213191032409668,0.0015097260475158691,605.0615234375 -1769682169,456848896,4.212314128875732,0.001699686050415039,605.0575561523438 -1769682169,475683328,4.211681842803955,0.0018960833549499512,605.0550537109375 -1769682169,510119424,4.210983753204346,0.002110898494720459,605.0526733398438 -1769682169,542387456,4.210296154022217,0.002304255962371826,605.0503540039062 -1769682169,577922816,4.209407329559326,0.002608060836791992,605.0473022460938 -1769682169,609856512,4.208688735961914,0.0027875304222106934,605.0448608398438 -1769682169,657690368,4.207954406738281,0.0028975605964660645,605.0422973632812 -1769682169,671089920,4.20728874206543,0.0030108094215393066,605.039794921875 -1769682169,712525824,4.206165790557861,0.003569483757019043,605.0361938476562 -1769682169,749297152,4.204980850219727,0.004239916801452637,605.032470703125 -1769682169,779048704,4.204057693481445,0.004682004451751709,605.0298461914062 -1769682169,810379264,4.203120231628418,0.005056917667388916,605.0274047851562 -1769682169,861442560,4.20176362991333,0.005417883396148682,605.0244750976562 -1769682169,869378048,4.201076030731201,0.005479753017425537,605.0231323242188 -1769682169,909176832,4.199666500091553,0.005564749240875244,605.0208740234375 -1769682169,942587904,4.198604106903076,0.00555497407913208,605.0194702148438 -1769682169,976310784,4.197345733642578,0.005535483360290527,605.017822265625 -1769682170,9572096,4.196860313415527,0.004955291748046875,605.0162963867188 -1769682170,47110912,4.196561813354492,0.004457533359527588,605.0138549804688 -1769682170,76017408,4.1963791847229,0.004368484020233154,605.0122680664062 -1769682170,109499392,4.19611120223999,0.004342257976531982,605.0106201171875 -1769682170,145673728,4.195794582366943,0.004320919513702393,605.0086059570312 -1769682170,176767232,4.195420742034912,0.004360795021057129,605.0072631835938 -1769682170,210073856,4.194973468780518,0.004019618034362793,605.0054931640625 -1769682170,256498432,4.194491863250732,0.003545820713043213,605.003662109375 -1769682170,276402176,4.194159507751465,0.002803325653076172,605.0013427734375 -1769682170,312155136,4.194515705108643,0.001540541648864746,604.9994506835938 -1769682170,343028736,4.194782733917236,0.0009941458702087402,604.998046875 -1769682170,375945216,4.194957733154297,0.0011309981346130371,604.9977416992188 -1769682170,409362432,4.195094585418701,0.0015230774879455566,604.9986572265625 -1769682170,445015296,4.195223331451416,0.0021788477897644043,605.0009155273438 -1769682170,476913408,4.1952385902404785,0.0026941299438476562,605.0032348632812 -1769682170,510909440,4.1952128410339355,0.0031937360763549805,605.0056762695312 -1769682170,558502400,4.1950836181640625,0.003795623779296875,605.0093383789062 -1769682170,578579200,4.194924831390381,0.004169106483459473,605.0120239257812 -1769682170,609623552,4.194722652435303,0.0044754743576049805,605.0148315429688 -1769682170,646128640,4.194478988647461,0.004723668098449707,605.0186767578125 -1769682170,677475072,4.194291591644287,0.004792451858520508,605.0218505859375 -1769682170,710125824,4.193841457366943,0.005122363567352295,605.0253295898438 -1769682170,744403712,4.193215847015381,0.005889177322387695,605.0303955078125 -1769682170,776105216,4.192746639251709,0.0064544677734375,605.0347290039062 -1769682170,809392128,4.192262649536133,0.00695425271987915,605.0396728515625 -1769682170,849814272,4.19143009185791,0.007564961910247803,605.046875 -1769682170,876555264,4.190777778625488,0.0076146721839904785,605.0526733398438 -1769682170,909741312,4.190115928649902,0.007535338401794434,605.0588989257812 -1769682170,949810688,4.18975830078125,0.007103383541107178,605.0670776367188 -1769682170,976647424,4.190204620361328,0.006159365177154541,605.0725708007812 -1769682171,10811648,4.190664291381836,0.0058095455169677734,605.0780639648438 -1769682171,55583744,4.191123962402344,0.005743622779846191,605.08349609375 -1769682171,76695808,4.191732883453369,0.005620360374450684,605.0906982421875 -1769682171,110183424,4.1922125816345215,0.005575120449066162,605.0960083007812 -1769682171,142605056,4.192691802978516,0.005570054054260254,605.1015625 -1769682171,176645632,4.1932454109191895,0.005389153957366943,605.1097412109375 -1769682171,209741056,4.193506240844727,0.0050550103187561035,605.1161499023438 -1769682171,243605760,4.193948268890381,0.00435715913772583,605.1223754882812 -1769682171,276139776,4.194774150848389,0.0029366612434387207,605.1309204101562 -1769682171,310978048,4.1954240798950195,0.0022066831588745117,605.1378784179688 -1769682171,357625600,4.196270942687988,0.0014250874519348145,605.1481323242188 -1769682171,376086272,4.196633338928223,0.0014133453369140625,605.1565551757812 -1769682171,409731072,4.197011947631836,0.0017868280410766602,605.1663818359375 -1769682171,459066880,4.197391986846924,0.0024431943893432617,605.1771240234375 -1769682171,476255744,4.197926998138428,0.003038167953491211,605.1923828125 -1769682171,511262976,4.1983208656311035,0.003571629524230957,605.204345703125 -1769682171,550855680,4.198841094970703,0.0041887760162353516,605.220947265625 -1769682171,576390656,4.1992316246032715,0.0045607686042785645,605.2337036132812 -1769682171,609967616,4.199616432189941,0.00484853982925415,605.2467651367188 -1769682171,647189248,4.200138568878174,0.00506669282913208,605.264892578125 -1769682171,676244736,4.200520038604736,0.005090117454528809,605.2791137695312 -1769682171,709719552,4.200843811035156,0.0051056742668151855,605.2939453125 -1769682171,743129600,4.201050281524658,0.005643486976623535,605.3095703125 -1769682171,776311552,4.20133113861084,0.00600588321685791,605.331298828125 -1769682171,810522368,4.201540946960449,0.006408393383026123,605.3485107421875 -1769682171,856782080,4.201646327972412,0.007116436958312988,605.3660888671875 -1769682171,876131840,4.201488971710205,0.007109940052032471,605.3902587890625 -1769682171,909635328,4.2016472816467285,0.006739437580108643,605.4085693359375 -1769682171,946632448,4.2020463943481445,0.006134450435638428,605.4326782226562 -1769682171,977008128,4.202333450317383,0.005833268165588379,605.4506225585938 -1769682172,1249024,4.20252799987793,0.005860269069671631,605.4625244140625 -1769682172,42846464,4.202915668487549,0.005543947219848633,605.486328125 -1769682172,76678400,4.203284740447998,0.004993081092834473,605.5103149414062 -1769682172,109752576,4.203553199768066,0.004746615886688232,605.5286254882812 -1769682172,154147328,4.203906059265137,0.0044078826904296875,605.5536499023438 -1769682172,176628480,4.204085350036621,0.004148125648498535,605.5731811523438 -1769682172,209740544,4.203761577606201,0.0042269229888916016,605.5933227539062 -1769682172,244307968,4.203226089477539,0.0035543441772460938,605.6201782226562 -1769682172,276072448,4.202831268310547,0.0028968453407287598,605.6403198242188 -1769682172,312555008,4.202444076538086,0.0022676587104797363,605.6605224609375 -1769682172,347821056,4.201928615570068,0.0015376806259155273,605.687744140625 -1769682172,376439808,4.2013936042785645,0.0012648701667785645,605.708251953125 -1769682172,409697536,4.200786113739014,0.0014243125915527344,605.7295532226562 -1769682172,445448704,4.200007438659668,0.0020357370376586914,605.7588500976562 -1769682172,477302272,4.19943380355835,0.0026708245277404785,605.78076171875 -1769682172,510051840,4.198883056640625,0.003204047679901123,605.8021850585938 -1769682172,545888512,4.198160171508789,0.0037874579429626465,605.8307495117188 -1769682172,579296512,4.19761848449707,0.004122138023376465,605.852294921875 -1769682172,610674176,4.197103500366211,0.0043572187423706055,605.874267578125 -1769682172,646012160,4.196437358856201,0.004532217979431152,605.9044189453125 -1769682172,676626688,4.195955276489258,0.00457531213760376,605.9278564453125 -1769682172,711267072,4.195490837097168,0.004575252532958984,605.9519653320312 -1769682172,744817408,4.1948652267456055,0.0046073198318481445,605.9852905273438 -1769682172,776653824,4.194415092468262,0.004634559154510498,606.0110473632812 -1769682172,809842432,4.193978786468506,0.004652798175811768,606.0372314453125 -1769682172,846806528,4.193197727203369,0.004790663719177246,606.0728759765625 -1769682172,879525376,4.1920695304870605,0.005034267902374268,606.1002197265625 -1769682172,910912000,4.1909637451171875,0.0047591328620910645,606.1279296875 -1769682172,955177728,4.189539909362793,0.004170596599578857,606.1651000976562 -1769682172,976898304,4.188499450683594,0.003631293773651123,606.1931762695312 -1769682173,9910272,4.187480449676514,0.003080606460571289,606.2216796875 -1769682173,55416576,4.186480522155762,0.0029114484786987305,606.2508544921875 -1769682173,76962560,4.185153961181641,0.0017297863960266113,606.2909545898438 -1769682173,111340288,4.184185028076172,0.0011767148971557617,606.322265625 -1769682173,147098112,4.183036804199219,0.001477658748626709,606.3663940429688 -1769682173,176600832,4.181934833526611,0.0017324090003967285,606.4013061523438 -1769682173,209703680,4.180844306945801,0.0016500353813171387,606.437255859375 -1769682173,244343808,4.179785251617432,0.001990795135498047,606.4741821289062 -1769682173,276423680,4.178404808044434,0.0012607574462890625,606.5248413085938 -1769682173,309473280,4.177392482757568,0.0010908842086791992,606.5636596679688 -1769682173,343972864,4.176416873931885,0.0014830231666564941,606.603271484375 -1769682173,376344320,4.175121784210205,0.0007944107055664062,606.656982421875 -1769682173,410858240,4.17415714263916,0.0007854104042053223,606.697998046875 -1769682173,457293568,4.173208713531494,0.0013499855995178223,606.7393798828125 -1769682173,478695424,4.171974182128906,0.0008241534233093262,606.7953491210938 -1769682173,511089920,4.171082973480225,0.0008003115653991699,606.8377685546875 -1769682173,542925312,4.170224666595459,0.0013102889060974121,606.880859375 -1769682173,577230080,4.169102668762207,0.0006340146064758301,606.93896484375 -1769682173,609632512,4.168271541595459,0.0005499720573425293,606.9833374023438 -1769682173,646193152,4.167211055755615,0.00041985511779785156,607.0432739257812 -1769682173,676575744,4.166425704956055,0.0003160238265991211,607.0888671875 -1769682173,710830336,4.165666103363037,0.00022876262664794922,607.1348266601562 -1769682173,757204224,4.164690017700195,0.00015842914581298828,607.1966552734375 -1769682173,776704256,4.163981914520264,0.00012999773025512695,607.2432250976562 -1769682173,809576960,4.1634674072265625,0.000459134578704834,607.2902221679688 -1769682173,853161984,4.162270545959473,0.0010411739349365234,607.3539428710938 -1769682173,877135360,4.161383628845215,0.0011022686958312988,607.4019165039062 -1769682173,910290432,4.160515785217285,0.0010826587677001953,607.4498901367188 -1769682173,942746880,4.159675598144531,0.0016461014747619629,607.4979858398438 -1769682173,980207360,4.158583641052246,0.0008639097213745117,607.5621337890625 -1769682174,10987776,4.157785415649414,0.0007273554801940918,607.6104125976562 -1769682174,44133120,4.157160758972168,0.0014110207557678223,607.658935546875 -1769682174,76846080,4.156529903411865,0.0013123154640197754,607.7238159179688 -1769682175,12279296,4.150117874145508,0.008500933647155762,609.1473999023438 -1769682175,81367552,4.144186496734619,0.008262932300567627,609.2015380859375 -1769682175,84209152,4.13884973526001,0.007888734340667725,609.2415161132812 -1769682175,127165440,4.131182670593262,0.007477164268493652,609.2811889648438 -1769682175,158300928,4.119405746459961,0.006925821304321289,609.3338012695312 -1769682175,168249600,4.112438201904297,0.006880819797515869,609.3599853515625 -1769682175,210708224,4.096336364746094,0.006213843822479248,609.412109375 -1769682175,242914048,4.083091735839844,0.006422281265258789,609.4511108398438 -1769682175,278121216,4.063271999359131,0.005633831024169922,609.5029907226562 -1769682175,310792960,4.047703266143799,0.005473136901855469,609.5418701171875 -1769682175,346537216,4.023349761962891,0.005588054656982422,609.5938110351562 -1769682175,376629504,4.003457069396973,0.005876421928405762,609.6331176757812 -1769682175,410163712,3.982625961303711,0.006206870079040527,609.6726684570312 -1769682175,453100288,3.952674150466919,0.0066727399826049805,609.7257080078125 -1769682175,478168576,3.9282593727111816,0.007009267807006836,609.7654418945312 -1769682175,511344384,3.9022843837738037,0.007327854633331299,609.8053588867188 -1769682175,547804416,3.866111993789673,0.0077100396156311035,609.8583374023438 -1769682175,577872128,3.8371798992156982,0.008115410804748535,609.89794921875 -1769682175,609825792,3.8068695068359375,0.008897960186004639,609.9373168945312 -1769682175,654842368,3.775696039199829,0.010726094245910645,609.97705078125 -1769682175,677592320,3.731565237045288,0.012241125106811523,610.031005859375 -1769682175,712079360,3.6969528198242188,0.013324379920959473,610.07177734375 -1769682175,749825024,3.649249792098999,0.01378720998764038,610.125244140625 -1769682175,778205952,3.611497640609741,0.013888776302337646,610.164794921875 -1769682175,803533056,3.5858988761901855,0.014225006103515625,610.1908569335938 -1769682175,849121536,3.5188941955566406,0.014036118984222412,610.2553100585938 -1769682175,877832704,3.477097272872925,0.014640212059020996,610.29345703125 -1769682175,910181888,3.4338839054107666,0.01535940170288086,610.3311767578125 -1769682175,945871872,3.374770402908325,0.016158580780029297,610.3810424804688 -1769682175,977900544,3.32853364944458,0.015867888927459717,610.417236328125 -1769682176,10656000,3.2812039852142334,0.015286087989807129,610.4523315429688 -1769682176,60681472,3.2159125804901123,0.014447152614593506,610.49755859375 -1769682176,71197184,3.182331085205078,0.014294743537902832,610.5195922851562 -1769682176,110075648,3.1142468452453613,0.013330817222595215,610.5628051757812 -1769682176,144161280,3.062640905380249,0.013183534145355225,610.5944213867188 -1769682176,177172736,2.999695062637329,0.012559890747070312,610.6351928710938 -1769682176,210233088,2.9594624042510986,0.012432456016540527,610.6638793945312 -1769682176,244720896,2.9239416122436523,0.01259392499923706,610.690673828125 -1769682176,277966336,2.8827874660491943,0.012273132801055908,610.7236328125 -1769682176,310959104,2.856577157974243,0.012246936559677124,610.7467041015625 -1769682176,347937280,2.830965757369995,0.012234002351760864,610.7754516601562 -1769682176,377376256,2.816272497177124,0.01224285364151001,610.7957763671875 -1769682176,409433088,2.8041467666625977,0.012350916862487793,610.8152465820312 -1769682176,445486592,2.7951903343200684,0.01282733678817749,610.8410034179688 -1769682176,476876288,2.7940661907196045,0.013337403535842896,610.8601684570312 -1769682176,512184576,2.7976632118225098,0.01385045051574707,610.8788452148438 -1769682176,553696768,2.8054544925689697,0.014501571655273438,610.8971557617188 -1769682176,578471680,2.822873115539551,0.014898926019668579,610.92041015625 -1769682176,610660864,2.840867519378662,0.015242993831634521,610.9370727539062 -1769682176,643301376,2.865060806274414,0.015654951333999634,610.9531860351562 -1769682176,676832512,2.901536703109741,0.01572898030281067,610.9734497070312 -1769682176,711816192,2.9325263500213623,0.015829533338546753,610.9880981445312 -1769682176,743990528,2.9633803367614746,0.01619786024093628,611.0025634765625 -1769682176,776538368,3.0049173831939697,0.017368733882904053,611.0220336914062 -1769682176,809728256,3.0362212657928467,0.01883113384246826,611.0379028320312 -1769682176,843272448,3.0675594806671143,0.020499110221862793,611.0545043945312 -1769682176,878418176,3.109412908554077,0.02214372158050537,611.0771484375 -1769682176,910505216,3.1408398151397705,0.02258545160293579,611.0933837890625 -1769682176,958749440,3.1828107833862305,0.022529900074005127,611.113525390625 -1769682176,976531712,3.2142951488494873,0.022313177585601807,611.1278076171875 -1769682177,10173696,3.245791435241699,0.022025644779205322,611.1414184570312 -1769682177,43648000,3.277405261993408,0.02195340394973755,611.1546630859375 -1769682177,78296320,3.31986141204834,0.022292912006378174,611.1715087890625 -1769682177,110978048,3.3517699241638184,0.02292788028717041,611.18359375 -1769682177,162542080,3.3943207263946533,0.02383667230606079,611.1990966796875 -1769682177,169180160,3.415557622909546,0.023881733417510986,611.2061767578125 -1769682177,211280128,3.458036184310913,0.022941648960113525,611.2185668945312 -1769682177,246852864,3.500624179840088,0.021868526935577393,611.2288208007812 -1769682177,277394688,3.5325582027435303,0.021102964878082275,611.2353515625 -1769682177,310234112,3.564497709274292,0.020393967628479004,611.2411499023438 -1769682177,347332608,3.607131004333496,0.019568979740142822,611.248046875 -1769682177,378246912,3.6391496658325195,0.01904118061065674,611.2528076171875 -1769682177,410247680,3.671178102493286,0.01859837770462036,611.2573852539062 -1769682177,456225024,3.713691234588623,0.018139302730560303,611.2635498046875 -1769682177,477329408,3.7449631690979004,0.017896056175231934,611.2682495117188 -1769682177,512730368,3.7752766609191895,0.017731785774230957,611.2731323242188 -1769682177,543698944,3.80450177192688,0.017713844776153564,611.2782592773438 -1769682177,578838016,3.8419294357299805,0.018064677715301514,611.2857055664062 -1769682177,609855488,3.8692967891693115,0.018833518028259277,611.2924194335938 -1769682177,643561728,3.895942449569702,0.019781768321990967,611.2999877929688 -1769682177,676986624,3.9302446842193604,0.020796597003936768,611.3109130859375 -1769682177,712059392,3.955090045928955,0.021550416946411133,611.3195190429688 -1769682177,747270144,3.9873504638671875,0.022431612014770508,611.331298828125 -1769682177,777029120,4.010400295257568,0.02299976348876953,611.3401489257812 -1769682177,811353856,4.032818794250488,0.02412492036819458,611.3491821289062 -1769682177,855032320,4.061432838439941,0.026906311511993408,611.3627319335938 -1769682177,877604096,4.082024097442627,0.02908426523208618,611.3737182617188 -1769682177,910677504,4.101731300354004,0.0306473970413208,611.3848876953125 -1769682177,943282944,4.120947360992432,0.03111046552658081,611.395263671875 -1769682177,980350720,4.145469665527344,0.03082174062728882,611.40771484375 -1769682178,11076352,4.163078308105469,0.030513882637023926,611.416259765625 -1769682178,46967808,4.185752868652344,0.030605316162109375,611.426513671875 -1769682178,77448960,4.2019734382629395,0.03111112117767334,611.4337158203125 -1769682178,112242176,4.217417240142822,0.03168696165084839,611.4404296875 -1769682178,143779840,4.231861114501953,0.031607747077941895,611.4462280273438 -1769682178,176903168,4.250139236450195,0.030254662036895752,611.4520874023438 -1769682178,209735168,4.263357162475586,0.029161810874938965,611.455078125 -1769682178,260928512,4.28007173538208,0.027771830558776855,611.4579467773438 -1769682178,277286656,4.291936874389648,0.026836812496185303,611.4595336914062 -1769682178,312414464,4.303236484527588,0.026028156280517578,611.4607543945312 -1769682178,343795968,4.314167022705078,0.025357544422149658,611.4617919921875 -1769682178,378517760,4.32757568359375,0.02464824914932251,611.4630737304688 -1769682178,410189824,4.337150573730469,0.024274230003356934,611.4640502929688 -1769682178,444423424,4.346046447753906,0.024027466773986816,611.4651489257812 -1769682178,480366592,4.356900215148926,0.024222910404205322,611.4669799804688 -1769682178,511978240,4.3645734786987305,0.024922192096710205,611.4693603515625 -1769682178,544934400,4.374136924743652,0.026027917861938477,611.4735717773438 -1769682178,576963584,4.38083028793335,0.0268593430519104,611.4773559570312 -1769682178,612050688,4.387246131896973,0.027632832527160645,611.4813232421875 -1769682178,645556480,4.39467191696167,0.028534650802612305,611.4869384765625 -1769682178,678205184,4.400272369384766,0.029452621936798096,611.491455078125 -1769682178,709939456,4.4055657386779785,0.031156957149505615,611.496826171875 -1769682178,744435712,4.411924839019775,0.03377252817153931,611.5051879882812 -1769682178,769462016,4.414775848388672,0.0348626971244812,611.5095825195312 -1769682178,811689472,4.419869422912598,0.03523200750350952,611.517578125 -1769682178,845891584,4.424562931060791,0.03494584560394287,611.5242309570312 -1769682178,878072576,4.427758693695068,0.034571051597595215,611.5285034179688 -1769682178,909748224,4.4309210777282715,0.034301578998565674,611.5322875976562 -1769682178,945573376,4.434525966644287,0.03445303440093994,611.5365600585938 -1769682178,977115648,4.436930179595947,0.03467559814453125,611.539306640625 -1769682179,10235648,4.438603401184082,0.03436309099197388,611.5410766601562 -1769682179,44634112,4.440418720245361,0.0333094596862793,611.5415649414062 -1769682179,77639168,4.4416961669921875,0.03246551752090454,611.5407104492188 -1769682179,112209920,4.44266414642334,0.03166365623474121,611.539306640625 -1769682179,155105792,4.4435200691223145,0.03091871738433838,611.5374145507812 -1769682179,176907520,4.444416046142578,0.030127286911010742,611.5344848632812 -1769682179,211513856,4.4448723793029785,0.029647469520568848,611.5321655273438 -1769682179,247032576,4.44520902633667,0.029163479804992676,611.5289916992188 -1769682179,278735360,4.445399284362793,0.028917133808135986,611.526611328125 -1769682179,311442944,4.445413589477539,0.02881026268005371,611.5242919921875 -1769682179,346707712,4.445043087005615,0.029170453548431396,611.5219116210938 -1769682179,377683712,4.444713115692139,0.029701292514801025,611.520751953125 -1769682179,409765632,4.4442620277404785,0.030278444290161133,611.5199584960938 -1769682179,457828864,4.443484783172607,0.031033694744110107,611.5191650390625 -1769682179,479077888,4.442821025848389,0.0315590500831604,611.5187377929688 -1769682179,510932736,4.442066192626953,0.032022833824157715,611.5181884765625 -1769682179,557245440,4.4414963722229,0.032771408557891846,611.517822265625 -1769682179,577293312,4.440584182739258,0.0342409610748291,611.5181884765625 -1769682179,612434688,4.439638137817383,0.035389721393585205,611.518798828125 -1769682179,646283008,4.438021183013916,0.035795748233795166,611.5191650390625 -1769682179,677227008,4.435808181762695,0.03561776876449585,611.5193481445312 -1769682179,710485248,4.434115886688232,0.03531229496002197,611.5192260742188 -1769682179,743892992,4.431796073913574,0.034792184829711914,611.5189208984375 -1769682179,777074688,4.430103778839111,0.03450089693069458,611.5185546875 -1769682179,846403584,4.428448677062988,0.034451186656951904,611.51806640625 -1769682179,864382976,4.426007270812988,0.03448301553726196,611.517333984375 -1769682179,889019392,4.423096179962158,0.03404510021209717,611.5160522460938 -1769682179,902533632,4.4211602210998535,0.03373980522155762,611.5146484375 -1769682179,943956992,4.417289733886719,0.0332108736038208,611.5104370117188 -1769682179,977399552,4.413439750671387,0.03278893232345581,611.5050659179688 -1769682180,12508672,4.4105706214904785,0.03249704837799072,611.5003051757812 -1769682180,48216576,4.406771659851074,0.03218024969100952,611.4935302734375 -1769682180,77576192,4.403947353363037,0.03199291229248047,611.4882202148438 -1769682180,110272256,4.401137828826904,0.03184962272644043,611.4828491210938 -1769682180,153639680,4.397457599639893,0.031712472438812256,611.4757080078125 -1769682180,177896960,4.394744396209717,0.03166508674621582,611.4705810546875 -1769682180,212805632,4.392017364501953,0.03175950050354004,611.4656372070312 -1769682180,244723200,4.388487815856934,0.03200078010559082,611.4598999023438 -1769682180,277480960,4.385905742645264,0.03220534324645996,611.4558715820312 -1769682180,310205184,4.383354663848877,0.032418668270111084,611.4520874023438 -1769682180,347127552,4.380041122436523,0.032693564891815186,611.4473876953125 -1769682180,377271808,4.377625942230225,0.03289002180099487,611.44384765625 -1769682180,412584192,4.375406742095947,0.03327751159667969,611.4404296875 -1769682180,448258816,4.37264347076416,0.03393012285232544,611.4361572265625 -1769682180,477314048,4.37036657333374,0.034355103969573975,611.43310546875 -1769682180,511039232,4.3671040534973145,0.034272074699401855,611.4296264648438 -1769682180,561446144,4.362926006317139,0.0339779257774353,611.4251098632812 -1769682180,568212224,4.360866546630859,0.033777594566345215,611.4228515625 -1769682180,610220288,4.3568220138549805,0.03340691328048706,611.4185180664062 -1769682180,643610880,4.353397369384766,0.03303879499435425,611.415283203125 -1769682180,679247616,4.346673011779785,0.03287613391876221,611.4111938476562 -1769682180,711444224,4.340286731719971,0.032859623432159424,611.408447265625 -1769682180,745335040,4.333289623260498,0.032842814922332764,611.4051513671875 -1769682180,777412096,4.3303351402282715,0.03280472755432129,611.4019165039062 -1769682180,810600960,4.3274712562561035,0.032826900482177734,611.3980102539062 -1769682180,843822336,4.323890209197998,0.03287672996520996,611.391845703125 -1769682180,877354496,4.321338653564453,0.03292691707611084,611.3865966796875 -1769682180,910386176,4.318861961364746,0.03299134969711304,611.381103515625 -1769682180,958744832,4.3157548904418945,0.03309190273284912,611.3734130859375 -1769682180,977091072,4.3135552406311035,0.033171117305755615,611.3675537109375 -1769682181,11126528,4.311464309692383,0.03324002027511597,611.3614501953125 -1769682181,47319040,4.30888032913208,0.033303141593933105,611.353271484375 -1769682181,80097536,4.307007789611816,0.03327876329421997,611.3470458984375 -1769682181,112806656,4.305230140686035,0.033145248889923096,611.3407592773438 -1769682181,151779072,4.3030314445495605,0.0329052209854126,611.3323364257812 -1769682181,177470976,4.3014116287231445,0.03271204233169556,611.3260498046875 -1769682181,214547712,4.299875259399414,0.03253746032714844,611.3198852539062 -1769682181,247796224,4.297944068908691,0.0323522686958313,611.3117065429688 -1769682181,277676032,4.296576976776123,0.032292306423187256,611.3056640625 -1769682181,310637568,4.295374393463135,0.032403647899627686,611.299560546875 -1769682181,356940800,4.294039726257324,0.03247976303100586,611.2913818359375 -1769682181,377490688,4.292973041534424,0.03237336874008179,611.2852172851562 -1769682181,412789760,4.291510105133057,0.03212416172027588,611.2786865234375 -1769682181,445072128,4.2896623611450195,0.03184664249420166,611.2697143554688 -1769682181,479632128,4.288330078125,0.03165125846862793,611.2630004882812 -1769682181,510144256,4.287022590637207,0.03143388032913208,611.2562255859375 -1769682181,544837632,4.285337924957275,0.031110107898712158,611.2474975585938 -1769682181,577854208,4.284099578857422,0.030831456184387207,611.2413940429688 -1769682181,612557312,4.28289794921875,0.03053128719329834,611.2356567382812 -1769682181,644868352,4.281418323516846,0.030214905738830566,611.228759765625 -1769682181,677581056,4.280519485473633,0.030353665351867676,611.2240600585938 -1769682181,711078656,4.279655456542969,0.03076314926147461,611.2196655273438 -1769682181,762926592,4.278571128845215,0.03145092725753784,611.2138671875 -1769682181,772587008,4.278041839599609,0.03178125619888306,611.2108154296875 -1769682181,810402816,4.277028560638428,0.032605767250061035,611.2037353515625 -1769682181,845419520,4.27606725692749,0.033353447914123535,611.1953735351562 -1769682181,880008704,4.275376796722412,0.03384119272232056,611.1880493164062 -1769682181,912243456,4.274701118469238,0.034240663051605225,611.179931640625 -1769682181,950059008,4.273849964141846,0.03459054231643677,611.1683349609375 -1769682181,977655808,4.2732930183410645,0.034676194190979004,611.1593017578125 -1769682182,15127808,4.272878170013428,0.034380555152893066,611.14990234375 -1769682182,49399296,4.272355079650879,0.03367668390274048,611.1368408203125 -1769682182,77476864,4.271980285644531,0.03310871124267578,611.127197265625 -1769682182,110479872,4.271615505218506,0.032579898834228516,611.1175537109375 -1769682182,162954496,4.271152496337891,0.03201329708099365,611.1049194335938 -1769682182,170285312,4.270932674407959,0.031706809997558594,611.0986938476562 -1769682182,212176896,4.2704949378967285,0.03148961067199707,611.085693359375 -1769682182,244246272,4.270188808441162,0.03108680248260498,611.072021484375 -1769682182,282780672,4.270076274871826,0.03035980463027954,611.0613403320312 -1769682182,310664704,4.270143032073975,0.029609978199005127,611.0501098632812 -1769682182,346260480,4.270346641540527,0.029182851314544678,611.0347900390625 -1769682182,377594368,4.270495414733887,0.029073774814605713,611.0230102539062 -1769682182,412088832,4.2706403732299805,0.029041647911071777,611.0109252929688 -1769682182,447241728,4.270819187164307,0.029043614864349365,610.9946899414062 -1769682182,477348096,4.2709527015686035,0.02905505895614624,610.9825439453125 -1769682182,511130112,4.270852088928223,0.028719842433929443,610.9705810546875 -1769682182,562102784,4.270683288574219,0.02790534496307373,610.9551391601562 -1769682182,570235904,4.270763397216797,0.027369022369384766,610.9478149414062 -1769682182,610622976,4.271233558654785,0.02773338556289673,610.9346923828125 -1769682182,648237312,4.271636486053467,0.028680026531219482,610.9240112304688 -1769682182,679579136,4.271938800811768,0.029498398303985596,610.9169311523438 -1769682182,710596096,4.272216796875,0.030337512493133545,610.9103393554688 -1769682182,744744192,4.2725300788879395,0.03144526481628418,610.9014282226562 -1769682182,777639680,4.272755146026611,0.03221338987350464,610.894287109375 -1769682182,812717824,4.27295446395874,0.03289937973022461,610.886474609375 -1769682182,848575232,4.273138046264648,0.033651113510131836,610.8750610351562 -1769682182,877181696,4.273258686065674,0.03403580188751221,610.8656616210938 -1769682182,910309376,4.273547649383545,0.03402191400527954,610.8557739257812 -1769682182,957784064,4.2739644050598145,0.03314763307571411,610.8411254882812 -1769682182,977422336,4.274230003356934,0.03227418661117554,610.8296508789062 -1769682183,10485760,4.274470329284668,0.031394124031066895,610.8182373046875 -1769682183,44089600,4.274733066558838,0.030354678630828857,610.8034057617188 -1769682183,80443904,4.274885177612305,0.02972966432571411,610.79248046875 -1769682183,110898432,4.275014400482178,0.029253721237182617,610.781494140625 -1769682183,145719296,4.274870872497559,0.028599917888641357,610.7662963867188 -1769682183,177505792,4.274845600128174,0.027673959732055664,610.7535400390625 -1769682183,210890496,4.2748026847839355,0.026561379432678223,610.739501953125 -1769682183,251559168,4.275432586669922,0.02576303482055664,610.7195434570312 -1769682183,278537216,4.275877475738525,0.026004552841186523,610.7041015625 -1769682183,310556928,4.276303768157959,0.02641737461090088,610.6885375976562 -1769682183,357066496,4.276841163635254,0.02701181173324585,610.6676635742188 -1769682183,377198848,4.277220726013184,0.027408897876739502,610.6522216796875 -1769682183,410676480,4.277470588684082,0.02764195203781128,610.6373291015625 -1769682183,446464000,4.277431964874268,0.026948094367980957,610.61865234375 -1769682183,479050752,4.2773847579956055,0.026192843914031982,610.6057739257812 -1769682183,511500032,4.278114318847656,0.025866329669952393,610.5941772460938 -1769682183,546669568,4.278989791870117,0.026474475860595703,610.5818481445312 -1769682183,577714432,4.27962589263916,0.02714639902114868,610.5741577148438 -1769682183,614556672,4.280238628387451,0.027868688106536865,610.5674438476562 -1769682183,649265152,4.281018257141113,0.028836488723754883,610.558837890625 -1769682183,677344000,4.281598091125488,0.029526352882385254,610.5523071289062 -1769682183,711641856,4.282153606414795,0.03016519546508789,610.5452880859375 -1769682183,755469312,4.282764434814453,0.03090798854827881,610.5349731445312 -1769682183,777689344,4.28321647644043,0.031353116035461426,610.5264892578125 -1769682183,810634240,4.2836408615112305,0.03161966800689697,610.517333984375 -1769682183,843974144,4.2842912673950195,0.03142577409744263,610.5039672851562 -1769682183,881626624,4.284737586975098,0.0309598445892334,610.4931030273438 -1769682183,910997504,4.285146236419678,0.030393123626708984,610.482177734375 -1769682183,945519616,4.285592079162598,0.02957296371459961,610.4678955078125 -1769682183,978143232,4.285878658294678,0.028956174850463867,610.457763671875 -1769682184,13944576,4.286092758178711,0.028387069702148438,610.4483032226562 -1769682184,50072320,4.286186695098877,0.027634918689727783,610.4368286132812 -1769682184,78308352,4.285919666290283,0.026700198650360107,610.4281005859375 -1769682184,110790912,4.285529613494873,0.025690674781799316,610.4188232421875 -1769682184,158888704,4.285491943359375,0.024705588817596436,610.4058837890625 -1769682184,167187200,4.285785675048828,0.02477473020553589,610.3994750976562 -1769682184,212269568,4.286334037780762,0.025631189346313477,610.38671875 -1769682184,244488448,4.286851406097412,0.02663964033126831,610.3739624023438 -1769682184,285886976,4.2872185707092285,0.0273551344871521,610.3643798828125 -1769682184,327170560,4.287557125091553,0.0279884934425354,610.3551635742188 -1769682184,349373440,4.287537097930908,0.0279274582862854,610.3433837890625 -1769682184,377636096,4.287505149841309,0.027367055416107178,610.33544921875 -1769682184,413116928,4.2876410484313965,0.026703953742980957,610.328369140625 -1769682184,453497600,4.288259983062744,0.02638918161392212,610.3208618164062 -1769682184,478348032,4.288668632507324,0.02631467580795288,610.3167114257812 -1769682184,511472896,4.289044380187988,0.026304244995117188,610.3134155273438 -1769682184,554400768,4.289534568786621,0.0263901948928833,610.3098754882812 -1769682184,577934848,4.28989315032959,0.026494860649108887,610.3074951171875 -1769682184,610582272,4.290152549743652,0.02663475275039673,610.304931640625 -1769682184,646468608,4.290441036224365,0.02684009075164795,610.3012084960938 -1769682184,679800832,4.2906389236450195,0.026989996433258057,610.2979125976562 -1769682184,710604800,4.290731906890869,0.02710247039794922,610.2942504882812 -1769682184,750124288,4.290670871734619,0.027332663536071777,610.2891235351562 -1769682184,777976064,4.290561199188232,0.027622699737548828,610.28564453125 -1769682184,810530816,4.290397644042969,0.027908265590667725,610.28271484375 -1769682184,844453120,4.2900471687316895,0.02820640802383423,610.2798461914062 -1769682184,878313216,4.289751052856445,0.02837812900543213,610.2784423828125 -1769682184,911119616,4.289405345916748,0.02850550413131714,610.277587890625 -1769682184,949556736,4.2888264656066895,0.028639793395996094,610.27734375 -1769682184,979436032,4.288090705871582,0.02838212251663208,610.2774658203125 -1769682185,10352640,4.287092685699463,0.027656376361846924,610.27685546875 -1769682185,63753728,4.285538673400879,0.027001142501831055,610.274658203125 -1769682185,71214080,4.285170555114746,0.0268058180809021,610.2731323242188 -1769682185,114519296,4.284365177154541,0.026980698108673096,610.2697143554688 -1769682185,144337664,4.283510208129883,0.02725088596343994,610.26611328125 -1769682185,177643008,4.2828369140625,0.027446448802947998,610.263427734375 -1769682185,211020288,4.282138347625732,0.027622997760772705,610.2609252929688 -1769682185,248676352,4.280882835388184,0.02742224931716919,610.2581176757812 -1769682185,278536704,4.279872894287109,0.026843547821044922,610.2565307617188 -1769682185,310617856,4.278852462768555,0.026179969310760498,610.2553100585938 -1769682185,349926912,4.277565956115723,0.025338172912597656,610.254638671875 -1769682185,379200768,4.27658748626709,0.024773836135864258,610.2550659179688 -1769682185,410690560,4.275599956512451,0.024235785007476807,610.2564697265625 -1769682185,454837504,4.274283409118652,0.02359539270401001,610.260009765625 -1769682185,478054656,4.273303508758545,0.02320873737335205,610.263916015625 -1769682185,511015424,4.272333145141602,0.022940218448638916,610.2686767578125 -1769682185,546020096,4.271029472351074,0.022770404815673828,610.2757568359375 -1769682185,581750272,4.270045757293701,0.022751271724700928,610.28125 -1769682185,611161344,4.269073486328125,0.022770166397094727,610.2864990234375 -1769682185,645609472,4.267780303955078,0.02282947301864624,610.2930297851562 -1769682185,677696256,4.266611099243164,0.02318274974822998,610.2979125976562 -1769682185,711175424,4.265435695648193,0.023756742477416992,610.3035888671875 -1769682185,750275840,4.2638983726501465,0.024509906768798828,610.3121337890625 -1769682185,779410176,4.2627716064453125,0.025003492832183838,610.3191528320312 -1769682185,810863616,4.26162052154541,0.02541893720626831,610.3269653320312 -1769682185,854932480,4.260138511657715,0.025851905345916748,610.33837890625 -1769682185,878347008,4.258938789367676,0.026015937328338623,610.347412109375 -1769682185,912083968,4.257504463195801,0.025562584400177002,610.3564453125 -1769682185,945361408,4.255553245544434,0.02476370334625244,610.3677978515625 -1769682185,982236672,4.254169464111328,0.02427119016647339,610.3759155273438 -1769682186,11039744,4.252831935882568,0.023918330669403076,610.3839111328125 -1769682186,50645504,4.251030445098877,0.023594796657562256,610.3944091796875 -1769682186,77261568,4.249699592590332,0.023414194583892822,610.4020385742188 -1769682186,114322688,4.248364448547363,0.02326357364654541,610.4096069335938 -1769682186,148159232,4.246523380279541,0.022997617721557617,610.4195556640625 -1769682186,177875456,4.245092868804932,0.022584080696105957,610.427001953125 -1769682186,210615296,4.243680000305176,0.02212148904800415,610.4345703125 -1769682186,262284288,4.2418646812438965,0.021531343460083008,610.44482421875 -1769682186,272974336,4.241003513336182,0.021407127380371094,610.4503173828125 -1769682186,311673600,4.239286422729492,0.020943820476531982,610.4620361328125 -1769682186,345679360,4.237590789794922,0.020662426948547363,610.4747314453125 -1769682186,378978304,4.236353397369385,0.020515501499176025,610.4849243164062 -1769682186,410937600,4.2351274490356445,0.020393192768096924,610.4954833984375 -1769682186,446707968,4.233555316925049,0.020298898220062256,610.5100708007812 -1769682186,478000384,4.232399940490723,0.020259857177734375,610.5213623046875 -1769682186,511354368,4.231266498565674,0.02023845911026001,610.53271484375 -1769682186,549790976,4.22981071472168,0.020236074924468994,610.5482177734375 -1769682186,594567168,4.22875452041626,0.020258009433746338,610.5598754882812 -1769682186,599894016,4.227994441986084,0.0204736590385437,610.5676879882812 -1769682186,648705792,4.226181983947754,0.020821034908294678,610.5878295898438 -1769682186,679911168,4.225161552429199,0.021101951599121094,610.6001586914062 -1769682186,710602240,4.224184513092041,0.02134495973587036,610.6126098632812 -1769682186,745870336,4.222936630249023,0.02158266305923462,610.6295166015625 -1769682186,777803776,4.222012996673584,0.02170741558074951,610.6424560546875 -1769682186,813585408,4.220996379852295,0.02159827947616577,610.6554565429688 -1769682186,845857024,4.219682216644287,0.021194517612457275,610.672607421875 -1769682186,877716992,4.2187018394470215,0.020914137363433838,610.6852416992188 -1769682186,910895872,4.217832565307617,0.020693600177764893,610.6976318359375 -1769682186,949323776,4.21682071685791,0.020564138889312744,610.7139282226562 -1769682186,978582272,4.2160868644714355,0.020491182804107666,610.7260131835938 -1769682187,10957056,4.215392112731934,0.020445644855499268,610.7379760742188 -1769682187,45458688,4.214527606964111,0.02040499448776245,610.7537231445312 -1769682187,78257920,4.2138285636901855,0.020247995853424072,610.7654418945312 -1769682187,110791680,4.213217735290527,0.019968032836914062,610.7769165039062 -1769682187,144951296,4.2124505043029785,0.019595801830291748,610.7921752929688 -1769682187,178674432,4.212189197540283,0.019498586654663086,610.8035278320312 -1769682187,211309568,4.211992263793945,0.019462287425994873,610.8152465820312 -1769682187,246796544,4.211786270141602,0.01940011978149414,610.8312377929688 -1769682187,277691136,4.211692810058594,0.01935100555419922,610.8436889648438 -1769682187,310739968,4.211629867553711,0.01932501792907715,610.8564453125 -1769682187,347495424,4.211602687835693,0.019334077835083008,610.8738403320312 -1769682187,377752064,4.2116007804870605,0.019384562969207764,610.8871459960938 -1769682187,412197120,4.2116379737854,0.01945209503173828,610.9003295898438 -1769682187,457153280,4.211753845214844,0.019558846950531006,610.9177856445312 -1769682187,478307840,4.211879253387451,0.01964426040649414,610.9306030273438 -1769682187,511307776,4.212038516998291,0.019723176956176758,610.9432373046875 -1769682187,544755200,4.212193965911865,0.019909679889678955,610.9597778320312 -1769682187,578473216,4.212294578552246,0.020076990127563477,610.9721069335938 -1769682187,611555328,4.212425708770752,0.020186007022857666,610.9843139648438 -1769682187,648925952,4.212560653686523,0.02024787664413452,611.0008544921875 -1769682187,677900544,4.212621212005615,0.020228862762451172,611.0134887695312 -1769682187,711205888,4.212619781494141,0.02016007900238037,611.026611328125 -1769682187,747622656,4.212486743927002,0.019800245761871338,611.0442504882812 -1769682187,777796864,4.212347030639648,0.019443809986114502,611.0574951171875 -1769682187,811378432,4.212158203125,0.019196391105651855,611.0707397460938 -1769682187,848378368,4.212236404418945,0.0192030668258667,611.0883178710938 -1769682187,878247680,4.212298393249512,0.019304871559143066,611.1013793945312 -1769682187,910900736,4.212380886077881,0.019421815872192383,611.1141967773438 -1769682187,945560832,4.212372303009033,0.019616365432739258,611.130859375 -1769682187,969173248,4.212327480316162,0.01978069543838501,611.1389770507812 -1769682188,12193536,4.211928367614746,0.019467413425445557,611.15478515625 -1769682188,44864768,4.2114362716674805,0.01894080638885498,611.1702270507812 -1769682188,77870848,4.211006164550781,0.018536806106567383,611.1815795898438 -1769682188,112140544,4.210713863372803,0.01842176914215088,611.1930541992188 -1769682188,144895744,4.210278034210205,0.018389999866485596,611.2086181640625 -1769682188,178308608,4.209835529327393,0.018370628356933594,611.2208862304688 -1769682188,212887040,4.209423065185547,0.01834702491760254,611.2337036132812 -1769682188,261106176,4.208703517913818,0.018340766429901123,611.2517700195312 -1769682188,269857280,4.208293914794922,0.018443942070007324,611.26123046875 -1769682188,311165184,4.207493305206299,0.018406689167022705,611.280517578125 -1769682188,351464704,4.206485271453857,0.01847761869430542,611.3002319335938 -1769682188,373339136,4.20594596862793,0.018719077110290527,611.3101806640625 -1769682188,412106752,4.20477294921875,0.018640637397766113,611.329833984375 -1769682188,446322176,4.203464508056641,0.018790245056152344,611.349365234375 -1769682188,477933056,4.2023797035217285,0.018979191780090332,611.3639526367188 -1769682188,510839552,4.201175689697266,0.01919025182723999,611.3783569335938 -1769682188,550729728,4.199406147003174,0.01944708824157715,611.3974609375 -1769682188,579098624,4.198014736175537,0.019611656665802002,611.4116821289062 -1769682188,614300672,4.196561336517334,0.0197446346282959,611.42578125 -1769682188,650039040,4.1942243576049805,0.01963907480239868,611.4445190429688 -1769682188,678294528,4.192229270935059,0.019110798835754395,611.4581909179688 -1769682188,711909120,4.190046787261963,0.01850980520248413,611.4716186523438 -1769682188,757387008,4.187103271484375,0.017849445343017578,611.4893188476562 -1769682188,777699584,4.184871196746826,0.017762601375579834,611.502685546875 -1769682188,810901504,4.182436943054199,0.01784956455230713,611.5159912109375 -1769682188,845649408,4.178889274597168,0.0180814266204834,611.5331420898438 -1769682188,881310464,4.176137447357178,0.0183255672454834,611.5455322265625 -1769682188,911215360,4.173222541809082,0.018480539321899414,611.5572509765625 -1769682188,946181376,4.168764591217041,0.018112480640411377,611.5722045898438 -1769682188,978366976,4.165257453918457,0.017611384391784668,611.5830688476562 -1769682189,14799104,4.161773681640625,0.017142891883850098,611.5936279296875 -1769682189,47432448,4.156866073608398,0.016978323459625244,611.6080322265625 -1769682189,78318592,4.15295934677124,0.01706939935684204,611.6193237304688 -1769682189,127918848,4.1490159034729,0.017196059226989746,611.6310424804688 -1769682189,163581696,4.143418788909912,0.017328858375549316,611.647705078125 -1769682189,172244736,4.140496253967285,0.01752495765686035,611.656494140625 -1769682189,211350784,4.13449239730835,0.01745814085006714,611.6751098632812 -1769682189,248200704,4.128101348876953,0.017586708068847656,611.6947631835938 -1769682189,278316032,4.123222351074219,0.01774519681930542,611.7098999023438 -1769682189,313197824,4.118166923522949,0.017926037311553955,611.7250366210938 -1769682189,350830592,4.111263275146484,0.018238186836242676,611.7448120117188 -1769682189,378398464,4.105859279632568,0.01853400468826294,611.7589111328125 -1769682189,414266624,4.100297927856445,0.018867552280426025,611.7722778320312 -1769682189,449393664,4.092618465423584,0.019305169582366943,611.7889404296875 -1769682189,478400512,4.086734294891357,0.019589126110076904,611.800537109375 -1769682189,511951872,4.08071231842041,0.019816458225250244,611.8115844726562 -1769682189,557485824,4.072358131408691,0.019965946674346924,611.82568359375 -1769682189,578031616,4.065931797027588,0.019852936267852783,611.8363037109375 -1769682189,611119104,4.059250354766846,0.019296467304229736,611.8465576171875 -1769682189,645328128,4.050117015838623,0.01814216375350952,611.8599243164062 -1769682189,684987648,4.043202877044678,0.017265737056732178,611.869873046875 -1769682189,711589632,4.036083698272705,0.01676309108734131,611.8800048828125 -1769682189,745492480,4.026436805725098,0.016641855239868164,611.8934936523438 -1769682189,779738624,4.01883602142334,0.016780197620391846,611.9033203125 -1769682189,811391232,4.011115550994873,0.01703011989593506,611.9126586914062 -1769682189,851086080,4.000649929046631,0.017451763153076172,611.9240112304688 -1769682189,879336960,3.992361307144165,0.017550945281982422,611.9318237304688 -1769682189,911078912,3.9838387966156006,0.017226457595825195,611.9390869140625 -1769682189,963850752,3.972266912460327,0.016587376594543457,611.9480590820312 -1769682189,971667712,3.9664106369018555,0.016442835330963135,611.9525146484375 -1769682190,11310080,3.9542994499206543,0.016275763511657715,611.9619140625 -1769682190,48423424,3.94181752204895,0.01648324728012085,611.9725341796875 -1769682190,80668160,3.9323503971099854,0.016635537147521973,611.981689453125 -1769682190,111703808,3.9226837158203125,0.01680278778076172,611.9920043945312 -1769682190,154446848,3.9094595909118652,0.017065703868865967,612.007080078125 -1769682190,177868800,3.8994619846343994,0.01731276512145996,612.01904296875 -1769682190,214630400,3.8893814086914062,0.01761019229888916,612.0311889648438 -1769682190,249230080,3.8756611347198486,0.018068671226501465,612.0469360351562 -1769682190,279364864,3.865109920501709,0.01844543218612671,612.05810546875 -1769682190,311173376,3.8544819355010986,0.01881784200668335,612.068359375 -1769682190,361590272,3.8400936126708984,0.01922285556793213,612.0804443359375 -1769682190,368573184,3.8327999114990234,0.01942199468612671,612.0858154296875 -1769682190,412025344,3.817923069000244,0.01963222026824951,612.0952758789062 -1769682190,446019072,3.8027515411376953,0.019786596298217773,612.103515625 -1769682190,478991104,3.7912380695343018,0.019841432571411133,612.1091918945312 -1769682190,511263488,3.779649257659912,0.019846796989440918,612.1146240234375 -1769682190,547129856,3.7639923095703125,0.01975959539413452,612.1218872070312 -1769682190,580439808,3.751976251602173,0.01953434944152832,612.1276245117188 -1769682190,611637248,3.7395973205566406,0.01882028579711914,612.133056640625 -1769682190,648282880,3.722916603088379,0.01739645004272461,612.1397094726562 -1769682190,678580480,3.7104830741882324,0.016426026821136475,612.1443481445312 -1769682190,711078656,3.6978707313537598,0.015780985355377197,612.1487426757812 -1769682190,759201536,3.680860757827759,0.015612006187438965,612.1546020507812 -1769682190,780298240,3.6679494380950928,0.015771567821502686,612.1585693359375 -1769682190,812375296,3.6549510955810547,0.016048789024353027,612.1621704101562 -1769682190,846173440,3.637425184249878,0.016507506370544434,612.1661376953125 -1769682190,879106304,3.6241455078125,0.016881346702575684,612.16845703125 -1769682190,911912448,3.6105902194976807,0.017129957675933838,612.1702880859375 -1769682190,947784448,3.5920698642730713,0.01676309108734131,612.1723022460938 -1769682190,983902720,3.5782101154327393,0.016435325145721436,612.1737060546875 -1769682191,12239104,3.564122200012207,0.016221821308135986,612.175048828125 -1769682191,46539776,3.5450475215911865,0.016499459743499756,612.1773071289062 -1769682191,78524416,3.530614137649536,0.016965150833129883,612.1793823242188 -1769682191,114397952,3.5161049365997314,0.017450928688049316,612.181640625 -1769682191,147915776,3.496577739715576,0.018031656742095947,612.1849975585938 -1769682191,178872576,3.4817843437194824,0.01840674877166748,612.187744140625 -1769682191,211222272,3.4669189453125,0.018735170364379883,612.1906127929688 -1769682191,258576896,3.446927309036255,0.019131720066070557,612.1946411132812 -1769682191,278043392,3.4318203926086426,0.01939946413040161,612.1976318359375 -1769682191,311115264,3.416550874710083,0.01964545249938965,612.2005004882812 -1769682191,361474304,3.396160840988159,0.019972145557403564,612.2037353515625 -1769682191,387097344,3.380758047103882,0.020134925842285156,612.2056884765625 -1769682191,402560512,3.3704724311828613,0.02016127109527588,612.2064208984375 -1769682191,445762048,3.344576120376587,0.020069658756256104,612.2071533203125 -1769682191,479343360,3.3289144039154053,0.019992530345916748,612.2068481445312 -1769682191,513586176,3.3131802082061768,0.01990187168121338,612.2059936523438 -1769682191,550530560,3.2920045852661133,0.01982271671295166,612.2044067382812 -1769682191,578583296,3.276095151901245,0.01980423927307129,612.2028198242188 -1769682191,611145472,3.260080337524414,0.01979905366897583,612.2008056640625 -1769682191,658940416,3.2385709285736084,0.01981407403945923,612.1976318359375 -1769682191,668630784,3.2277469635009766,0.019794046878814697,612.1958618164062 -1769682191,712045824,3.206033706665039,0.019516170024871826,612.1919555664062 -1769682191,744971520,3.1836962699890137,0.0184745192527771,612.1869506835938 -1769682191,782593280,3.166848659515381,0.017541825771331787,612.1820678710938 -1769682191,812206592,3.1501359939575195,0.016743004322052002,612.1764526367188 -1769682191,847649024,3.127429246902466,0.015988200902938843,612.16845703125 -1769682191,878227712,3.110229969024658,0.01593276858329773,612.1622314453125 -1769682191,911566336,3.0928292274475098,0.01610502600669861,612.1561889648438 -1769682191,947389440,3.0695064067840576,0.01645791530609131,612.1480102539062 -1769682191,978819328,3.051826238632202,0.016785413026809692,612.141845703125 -1769682192,12990720,3.0340802669525146,0.01710456609725952,612.1355590820312 -1769682192,66423296,3.0103328227996826,0.017513632774353027,612.1270751953125 -1769682192,74366464,2.9984219074249268,0.017628073692321777,612.122802734375 -1769682192,111195392,2.974213123321533,0.01782447099685669,612.1143188476562 -1769682192,157027328,2.9497992992401123,0.017513751983642578,612.1061401367188 -1769682192,181515264,2.931384801864624,0.017287135124206543,612.1002197265625 -1769682192,211609600,2.912628173828125,0.017068475484848022,612.0941772460938 -1769682192,245615872,2.8874285221099854,0.017444610595703125,612.0869140625 -1769682192,279628288,2.868364095687866,0.017908483743667603,612.0817260742188 -1769682192,312313344,2.8492484092712402,0.01837986707687378,612.07666015625 -1769682192,348450304,2.8236987590789795,0.01894882321357727,612.0701293945312 -1769682192,378470144,2.8044543266296387,0.019329309463500977,612.0653076171875 -1769682192,414422272,2.785327911376953,0.019650429487228394,612.0603637695312 -1769682192,449999872,2.759801149368286,0.01999548077583313,612.0538940429688 -1769682192,478663424,2.7406182289123535,0.020197242498397827,612.0490112304688 -1769682192,511549696,2.721261501312256,0.020357072353363037,612.0440673828125 -1769682192,560102912,2.6954495906829834,0.020497441291809082,612.0375366210938 -1769682192,578192896,2.675997018814087,0.020592331886291504,612.0325317382812 -1769682192,612699904,2.656500816345215,0.020617634057998657,612.0275268554688 -1769682192,645751552,2.630617141723633,0.020441055297851562,612.0201416015625 -1769682192,678667008,2.6112184524536133,0.020230978727340698,612.0137939453125 -1769682192,712712192,2.591815710067749,0.020024597644805908,612.0070190429688 -1769682192,749669888,2.5659306049346924,0.01976799964904785,611.9970092773438 -1769682192,779077376,2.5463814735412598,0.01962047815322876,611.9890747070312 -1769682192,812577280,2.5267157554626465,0.019483894109725952,611.9807739257812 -1769682192,846703360,2.5005249977111816,0.019372165203094482,611.9692993164062 -1769682192,878900480,2.480865716934204,0.01934531331062317,611.96044921875 -1769682192,911492608,2.4612598419189453,0.01936623454093933,611.9512329101562 -1769682192,949529856,2.4353232383728027,0.019430339336395264,611.9384765625 -1769682192,980226816,2.4158735275268555,0.01953071355819702,611.9285278320312 -1769682193,11240192,2.3964459896087646,0.019626140594482422,611.9181518554688 -1769682193,46710272,2.37097430229187,0.0195370614528656,611.9037475585938 -1769682193,78844672,2.351571798324585,0.01940995454788208,611.8923950195312 -1769682193,114721536,2.332108736038208,0.0193139910697937,611.88037109375 -1769682193,147259392,2.305921792984009,0.01904234290122986,611.8633422851562 -1769682193,178759424,2.286003351211548,0.018596112728118896,611.8491821289062 -1769682193,213827840,2.2662975788116455,0.01811203360557556,611.833740234375 -1769682193,247267328,2.2398948669433594,0.01749354600906372,611.8121948242188 -1769682193,278801920,2.2200028896331787,0.01705235242843628,611.7957763671875 -1769682193,311523584,2.199683427810669,0.0168607234954834,611.7796020507812 -1769682193,359555584,2.1726388931274414,0.017041683197021484,611.7589111328125 -1769682193,379446016,2.152287244796753,0.017268091440200806,611.7440185546875 -1769682193,411816960,2.1318633556365967,0.017518937587738037,611.7294311523438 -1769682193,445488384,2.1046457290649414,0.01785862445831299,611.7105102539062 -1769682193,478278912,2.084150791168213,0.01810246706008911,611.6964721679688 -1769682193,511449344,2.0637595653533936,0.018320798873901367,611.6824951171875 -1769682193,546133760,2.0365774631500244,0.01853272318840027,611.6640625 -1769682193,578718464,2.0160601139068604,0.018627285957336426,611.6505126953125 -1769682193,611687680,1.9954081773757935,0.018650531768798828,611.6371459960938 -1769682193,646206208,1.9680638313293457,0.0185890793800354,611.6199951171875 -1769682193,679086336,1.9473052024841309,0.018513023853302002,611.6077270507812 -1769682193,712763904,1.9263949394226074,0.01842626929283142,611.5960083007812 -1769682193,746932224,1.8983181715011597,0.017878234386444092,611.5813598632812 -1769682193,779480576,1.8772274255752563,0.01758265495300293,611.5709228515625 -1769682193,811924736,1.8561729192733765,0.01739346981048584,611.5606079101562 -1769682193,850168576,1.8282965421676636,0.017250865697860718,611.5463256835938 -1769682193,880329728,1.8071783781051636,0.01760721206665039,611.5353393554688 -1769682193,913402368,1.7860618829727173,0.01819533109664917,611.5241088867188 -1769682193,958332416,1.7579014301300049,0.01911899447441101,611.5079956054688 -1769682193,978757376,1.7366875410079956,0.019919127225875854,611.494873046875 -1769682194,11490048,1.715356707572937,0.020718634128570557,611.48046875 -1769682194,46050048,1.6870864629745483,0.02170446515083313,611.4594116210938 -1769682194,79378432,1.66574227809906,0.02230018377304077,611.4422607421875 -1769682194,111647488,1.6443183422088623,0.022760838270187378,611.424560546875 -1769682194,147953920,1.6157522201538086,0.023149967193603516,611.4005126953125 -1769682194,179054336,1.594377040863037,0.023289114236831665,611.3825073242188 -1769682194,213975552,1.5729994773864746,0.023320257663726807,611.3648071289062 -1769682194,247396864,1.5446606874465942,0.023214608430862427,611.342041015625 -1769682194,278899712,1.5233439207077026,0.023586124181747437,611.3255004882812 -1769682194,328106496,1.502416729927063,0.02384456992149353,611.3076171875 -1769682194,359278336,1.4746215343475342,0.02416934072971344,611.2817993164062 -1769682194,369326848,1.4606510400772095,0.024282485246658325,611.26806640625 -1769682194,411667456,1.4326316118240356,0.024754926562309265,611.2392578125 -1769682194,447260160,1.404662847518921,0.025169074535369873,611.2085571289062 -1769682194,479800320,1.3835598230361938,0.02544616162776947,611.1844482421875 -1769682194,506852864,1.3628665208816528,0.025491729378700256,611.159423828125 -1769682194,546940416,1.335777759552002,0.025345101952552795,611.1243896484375 -1769682194,578677760,1.315462350845337,0.025116726756095886,611.0972900390625 -1769682194,613070848,1.2950336933135986,0.024561792612075806,611.0703125 -1769682194,655183360,1.2682331800460815,0.023586049675941467,611.03662109375 -1769682194,679677440,1.2480218410491943,0.022997930645942688,611.0136108398438 -1769682194,712930304,1.2278318405151367,0.02242499589920044,610.9920654296875 -1769682194,748692224,1.2010810375213623,0.021662637591362,610.96533203125 -1769682194,779363840,1.1810410022735596,0.02108989655971527,610.9466552734375 -1769682194,812738816,1.1610195636749268,0.020522847771644592,610.9290771484375 -1769682194,848842240,1.134880781173706,0.019788265228271484,610.9072875976562 -1769682194,878763008,1.1153063774108887,0.019286498427391052,610.8922729492188 -1769682194,911963392,1.0955941677093506,0.018848657608032227,610.878173828125 -1769682194,945184000,1.0696755647659302,0.018390357494354248,610.8607788085938 -1769682194,979032320,1.0504316091537476,0.018181830644607544,610.848388671875 -1769682195,15344896,1.0312912464141846,0.0180647075176239,610.836181640625 -1769682195,62748672,1.0058852434158325,0.01801358163356781,610.8200073242188 -1769682195,67971328,0.9932780265808105,0.018037810921669006,610.8118286132812 -1769682195,111808512,0.9676822423934937,0.018172502517700195,610.795166015625 -1769682197,547941120,0.0,-0.0,610.519287109375 -1769682197,578963712,0.0,-0.0,610.519287109375 -1769682197,612030976,0.0,-0.0,610.519287109375 -1769682197,651033344,0.0,-0.0,610.519287109375 -1769682197,680354816,0.0,-0.0,610.519287109375 -1769682197,711882240,0.0,-0.0,610.519287109375 -1769682197,751959040,0.0,-0.0,610.519287109375 -1769682197,779987456,0.0,-0.0,610.519287109375 -1769682197,812767488,0.0,-0.0,610.519287109375 -1769682197,847019008,0.0,-0.0,610.519287109375 -1769682197,879002368,0.0,-0.0,610.519287109375 -1769682197,915835136,0.0,-0.0,610.519287109375 -1769682197,946582784,0.0,-0.0,610.519287109375 -1769682197,979719936,0.0,-0.0,610.519287109375 -1769682198,12879872,0.0,-0.0,610.519287109375 -1769682198,51246336,0.0,-0.0,610.519287109375 -1769682198,79638016,0.0,-0.0,610.519287109375 -1769682198,113188608,0.0,-0.0,610.519287109375 -1769682198,159996672,0.0,-0.0,610.519287109375 -1769682198,179217664,0.0,-0.0,610.519287109375 -1769682198,212375808,0.0,-0.0,610.5193481445312 -1769682198,245857536,0.0,-0.0,610.5193481445312 -1769682198,278932224,0.0,-0.0,610.5193481445312 -1769682198,312406272,0.0,-0.0,610.5193481445312 -1769682198,347892736,0.0,-0.0,610.5193481445312 -1769682198,379276288,0.0,-0.0,610.5193481445312 -1769682198,412165632,0.0,-0.0,610.5193481445312 -1769682198,445723392,0.0,-0.0,610.5193481445312 -1769682198,479228160,0.0,-0.0,610.5193481445312 -1769682198,512685824,0.0,-0.0,610.5193481445312 -1769682198,561560320,0.0,-0.0,610.5194702148438 -1769682198,570423552,0.0,-0.0,610.5194702148438 -1769682198,611966464,0.0,-0.0,610.5194702148438 -1769682198,646645760,0.0,-0.0,610.5194702148438 -1769682198,679396352,0.0,-0.0,610.5194702148438 -1769682198,712074496,0.0,-0.0,610.5194702148438 -1769682198,746901504,0.0,-0.0,610.5194702148438 -1769682198,782393600,0.0,-0.0,610.5194702148438 -1769682198,812574720,0.0,-0.0,610.5194702148438 -1769682198,849497856,0.0,-0.0,610.5194702148438 -1769682198,878909952,0.0,-0.0,610.5194702148438 -1769682198,914416896,0.0,-0.0,610.5194702148438 -1769682198,949228544,0.0,-0.0,610.51953125 -1769682198,979188224,0.0,-0.0,610.51953125 -1769682199,12215296,0.0,-0.0,610.51953125 -1769682199,58538752,0.0,-0.0,610.51953125 -1769682199,79518208,0.0,-0.0,610.51953125 -1769682199,112444160,0.0,-0.0,610.51953125 -1769682199,145972736,0.0,-0.0,610.51953125 -1769682199,181851136,0.0,-0.0,610.51953125 -1769682199,212603136,0.0,-0.0,610.51953125 -1769682199,248636160,0.0,-0.0,610.51953125 -1769682199,278988288,0.0,-0.0,610.51953125 -1769682199,313848064,0.0,-0.0,610.51953125 -1769682199,347606784,0.0,-0.0,610.51953125 -1769682199,379577600,0.0,-0.0,610.51953125 -1769682199,412837376,0.0,-0.0,610.51953125 -1769682199,458770432,0.0,-0.0,610.51953125 -1769682199,478819328,0.0,-0.0,610.51953125 -1769682199,514035968,0.0,-0.0,610.51953125 -1769682199,546544384,0.0,-0.0,610.51953125 -1769682199,579883264,0.0,-0.0,610.51953125 -1769682199,613348864,0.0,-0.0,610.51953125 -1769682199,652515840,0.0,-0.0,610.5195922851562 -1769682199,679008000,0.0,-0.0,610.5195922851562 -1769682199,713022208,0.0,-0.0,610.5195922851562 -1769682199,748818688,0.0,-0.0,610.5195922851562 -1769682199,779364352,0.0,-0.0,610.5195922851562 -1769682199,812263168,0.0,-0.0,610.5195922851562 -1769682199,863299072,0.0,-0.0,610.5195922851562 -1769682199,873274880,0.0,-0.0,610.5195922851562 -1769682199,913103616,0.0,-0.0,610.5195922851562 -1769682199,948838144,0.0,-0.0,610.5195922851562 -1769682199,979949312,0.0,-0.0,610.5196533203125 -1769682200,12189696,0.0,-0.0,610.5196533203125 -1769682200,50053376,0.0,-0.0,610.5196533203125 -1769682200,79229440,0.0,-0.0,610.5196533203125 -1769682200,112338432,0.0,-0.0,610.5196533203125 -1769682200,155083776,0.0,-0.0,610.5196533203125 -1769682200,178770176,0.0,-0.0,610.5196533203125 -1769682200,213524736,0.0,-0.0,610.5196533203125 -1769682200,260227072,0.0,-0.0,610.5196533203125 -1769682200,279980800,0.0,-0.0,610.5196533203125 -1769682200,314597888,0.0,-0.0,610.5196533203125 -1769682200,346783488,0.0,-0.0,610.5197143554688 -1769682200,380743424,0.0,-0.0,610.5197143554688 -1769682200,412494080,0.0,-0.0,610.5197143554688 -1769682200,447928064,0.0,-0.0,610.5197143554688 -1769682200,479210240,0.0,-0.0,610.5197143554688 -1769682200,513697536,0.0,-0.0,610.5197143554688 -1769682200,550388992,0.0,-0.0,610.5197143554688 -1769682200,579538176,0.0,-0.0,610.5197143554688 -1769682200,612252672,0.0,-0.0,610.5197143554688 -1769682200,658046464,0.0,-0.0,610.519775390625 -1769682200,679281152,0.0,-0.0,610.519775390625 -1769682200,714242304,0.0,-0.0,610.519775390625 -1769682200,747077888,0.0,-0.0,610.519775390625 -1769682200,779892736,0.0,-0.0,610.519775390625 -1769682200,812372992,0.0,-0.0,610.519775390625 -1769682200,846664704,0.0,-0.0,610.519775390625 -1769682200,879779840,0.0,-0.0,610.519775390625 -1769682200,914250496,0.0,-0.0,610.519775390625 -1769682200,949181184,0.0,-0.0,610.519775390625 -1769682200,983358976,0.0,-0.0,610.519775390625 -1769682201,13711104,0.0,-0.0,610.519775390625 -1769682201,50961664,0.0,-0.0,610.5198364257812 -1769682201,80183808,0.0,-0.0,610.5198364257812 -1769682201,112204800,0.0,-0.0,610.5198364257812 -1769682201,145797120,0.0,-0.0,610.5198364257812 -1769682201,180031488,0.0,-0.0,610.5198364257812 -1769682201,214189568,0.0,-0.0,610.5198974609375 -1769682201,247407872,0.0,-0.0,610.5198974609375 -1769682201,280477184,0.0,-0.0,610.5198974609375 -1769682201,312261888,0.0,-0.0,610.5198974609375 -1769682201,347196416,0.0,-0.0,610.5198974609375 -1769682201,379401984,0.0,-0.0,610.5199584960938 -1769682201,413069312,0.0,-0.0,610.5199584960938 -1769682201,459246848,0.0,-0.0,610.5199584960938 -1769682201,479057152,0.0,-0.0,610.5199584960938 -1769682201,513163264,0.0,-0.0,610.5199584960938 -1769682201,560775680,0.0,-0.0,610.5200805664062 -1769682201,579896320,0.0,-0.0,610.5200805664062 -1769682201,612254464,0.0,-0.0,610.5200805664062 -1769682201,647044608,0.0,-0.0,610.5200805664062 -1769682201,681948416,0.0,-0.0,610.5200805664062 -1769682201,713340160,0.0,-0.0,610.5200805664062 -1769682201,747004160,0.0,-0.0,610.5200805664062 -1769682201,779751168,0.0,-0.0,610.5200805664062 -1769682201,815056128,0.0,-0.0,610.5200805664062 -1769682201,847517440,0.0,-0.0,610.5200805664062 -1769682201,879911168,0.0,-0.0,610.5200805664062 -1769682201,912207616,0.0,-0.0,610.5201416015625 -1769682201,958910720,0.0,-0.0,610.5201416015625 -1769682201,980755712,0.0,-0.0,610.5201416015625 -1769682202,12660736,0.0,-0.0,610.5201416015625 -1769682202,47124736,0.0,-0.0,610.5201416015625 -1769682202,84957184,0.0,-0.0,610.5202026367188 -1769682202,113704704,0.0,-0.0,610.5202026367188 -1769682202,147710208,0.0,-0.0,610.5202026367188 -1769682202,178944768,0.0,-0.0,610.5202026367188 -1769682202,217677312,0.0,-0.0,610.520263671875 -1769682202,251035904,0.0,-0.0,610.520263671875 -1769682202,280160256,0.0,-0.0,610.520263671875 -1769682202,312545024,0.0,-0.0,610.520263671875 -1769682202,357021696,0.0,-0.0,610.520263671875 -1769682202,379308800,0.0,-0.0,610.520263671875 -1769682202,412445440,0.0,-0.0,610.520263671875 -1769682202,463823872,0.0,-0.0,610.5203247070312 -1769682202,482069760,0.0,-0.0,610.5203247070312 -1769682202,503348224,0.0,-0.0,610.5203247070312 -1769682202,547123456,0.0,-0.0,610.5203857421875 -1769682202,579943424,0.0,-0.0,610.5203857421875 -1769682202,613009664,0.0,-0.0,610.5203857421875 -1769682202,654123008,0.0,-0.0,610.5203857421875 -1769682202,681254144,0.0,-0.0,610.5204467773438 -1769682202,713339136,0.0,-0.0,610.5204467773438 -1769682202,759206912,0.0,-0.0,610.5204467773438 -1769682202,779421440,0.0,-0.0,610.5205078125 -1769682202,812734720,0.0,-0.0,610.5205078125 -1769682202,847097600,0.0,-0.0,610.5205078125 -1769682202,886426112,0.0,-0.0,610.5205078125 -1769682202,912331008,0.0,-0.0,610.5205078125 -1769682202,949532416,0.0,-0.0,610.5205078125 -1769682202,980490240,0.0,-0.0,610.5205078125 -1769682203,15202304,0.0,-0.0,610.5205078125 -1769682203,48718336,0.0,-0.0,610.5205688476562 -1769682203,79863040,0.0,-0.0,610.5205688476562 -1769682203,112389120,0.0,-0.0,610.5205688476562 -1769682203,163217408,0.0,-0.0,610.5206909179688 -1769682203,168869632,0.0,-0.0,610.5206909179688 -1769682203,212481280,0.0,-0.0,610.5206909179688 -1769682203,246100480,0.0,-0.0,610.5206909179688 -1769682203,281476864,0.0,-0.0,610.520751953125 -1769682203,313844736,0.0,-0.0,610.520751953125 -1769682203,347720448,0.0,-0.0,610.520751953125 -1769682203,379842304,0.0,-0.0,610.520751953125 -1769682203,413231872,0.0,-0.0,610.520751953125 -1769682203,450597632,0.0,-0.0,610.520751953125 -1769682203,479440640,0.0,-0.0,610.520751953125 -1769682203,512481536,0.0,-0.0,610.5208129882812 -1769682203,559383552,0.0,-0.0,610.5208129882812 -1769682203,580184320,0.0,-0.0,610.5208129882812 -1769682203,613138688,0.0,-0.0,610.5208129882812 -1769682203,647651584,0.0,-0.0,610.5208740234375 -1769682203,683921664,0.0,-0.0,610.5208740234375 -1769682203,713466368,0.0,-0.0,610.5208740234375 -1769682203,750812416,0.0,-0.0,610.5209350585938 -1769682203,779480320,0.0,-0.0,610.5209350585938 -1769682203,814372352,0.0,-0.0,610.5209350585938 -1769682203,850275072,0.0,-0.0,610.52099609375 -1769682203,879459584,0.0,-0.0,610.52099609375 -1769682203,912735488,0.0,-0.0,610.52099609375 -1769682203,965593344,0.0,-0.0,610.52099609375 -1769682203,971025664,0.0,-0.0,610.52099609375 -1769682204,12472064,0.0,-0.0,610.52099609375 -1769682204,47509248,0.0,-0.0,610.52099609375 -1769682204,79958272,0.0,-0.0,610.52099609375 -1769682204,112469248,0.0,-0.0,610.5210571289062 -1769682204,146753536,0.0,-0.0,610.5210571289062 -1769682204,179516416,0.0,-0.0,610.5210571289062 -1769682204,212925952,0.0,-0.0,610.5211181640625 -1769682204,249913856,0.0,-0.0,610.5211181640625 -1769682204,283777024,0.0,-0.0,610.5211181640625 -1769682204,312459008,0.0,-0.0,610.5211181640625 -1769682204,346625024,0.0,-0.0,610.521240234375 -1769682204,379767552,0.0,-0.0,610.521240234375 -1769682204,413758464,0.0,-0.0,610.521240234375 -1769682204,449177600,0.0,-0.0,610.521240234375 -1769682204,480097792,0.0,-0.0,610.521240234375 -1769682204,512474112,0.0,-0.0,610.521240234375 -1769682204,549072384,0.0,-0.0,610.521240234375 -1769682204,580157440,0.0,-0.0,610.521240234375 -1769682204,617533440,0.0,-0.0,610.521240234375 -1769682204,649853440,0.0,-0.0,610.521240234375 -1769682204,680472064,0.0,-0.0,610.5213012695312 -1769682204,713019136,0.0,-0.0,610.5213012695312 -1769682204,760906496,0.0,-0.0,610.5213012695312 -1769682204,779703040,0.0,-0.0,610.5213012695312 -1769682204,812841728,0.0,-0.0,610.5213012695312 -1769682204,847204608,0.0,-0.0,610.5213623046875 -1769682204,880687360,0.0,-0.0,610.5213623046875 -1769682204,913062912,0.0,-0.0,610.5213623046875 -1769682204,948263424,0.0,-0.0,610.5213623046875 -1769682204,980289024,0.0,-0.0,610.5213623046875 -1769682205,13211392,0.0,-0.0,610.5213623046875 -1769682205,48832000,0.0,-0.0,610.5214233398438 -1769682205,80444928,0.0,-0.0,610.5214233398438 -1769682205,114045952,0.0,-0.0,610.5214233398438 -1769682205,161984256,0.0,-0.0,610.5214233398438 -1769682205,181650688,0.0,-0.0,610.5214233398438 -1769682205,212833024,0.0,-0.0,610.521484375 -1769682205,265981696,0.0,-0.0,610.521484375 -1769682205,276981248,0.0,-0.0,610.521484375 -1769682205,330940672,0.0,-0.0,610.521484375 -1769682205,347456256,0.0,-0.0,610.521484375 -1769682205,384185856,0.0,-0.0,610.521484375 -1769682205,412777984,0.0,-0.0,610.521484375 -1769682205,496438784,0.0,-0.0,610.521484375 -1769682205,515661056,0.0,-0.0,610.521484375 -1769682205,547452672,0.0,-0.0,610.521484375 -1769682205,579428864,0.0,-0.0,610.5215454101562 -1769682205,613837312,0.0,-0.0,610.5215454101562 -1769682205,659735808,0.0,-0.0,610.5215454101562 -1769682205,667964928,0.0,-0.0,610.5215454101562 -1769682205,712635904,0.0,-0.0,610.5215454101562 -1769682205,747085312,0.0,-0.0,610.5216064453125 -1769682205,781574144,0.0,-0.0,610.5216064453125 -1769682205,813678848,0.0,-0.0,610.5216064453125 -1769682205,848017664,0.0,-0.0,610.5216064453125 -1769682205,880130048,0.0,-0.0,610.5216064453125 -1769682205,914196992,0.0,-0.0,610.5216064453125 -1769682205,947583232,0.0,-0.0,610.5216674804688 -1769682205,979836928,0.0,-0.0,610.5216674804688 -1769682206,13129472,0.0,-0.0,610.5216674804688 -1769682206,58359552,0.0,-0.0,610.5216674804688 -1769682206,413651200,0.0,-0.0,610.521728515625 -1769682206,449827328,0.0,-0.0,610.521728515625 -1769682206,480384768,0.0,-0.0,610.5218505859375 -1769682206,513718016,0.0,-0.0,610.5218505859375 -1769682206,546755840,0.0,-0.0,610.5218505859375 -1769682206,569829888,0.0,-0.0,610.5218505859375 -1769682206,612945152,0.0,-0.0,610.5218505859375 -1769682206,650286080,0.0,-0.0,610.5219116210938 -1769682206,680046848,0.0,-0.0,610.5219116210938 -1769682206,714145536,0.0,-0.0,610.5219116210938 -1769682206,752692992,0.0,-0.0,610.5219116210938 -1769682206,780060928,0.0,-0.0,610.5219116210938 -1769682206,812741632,0.0,-0.0,610.5219116210938 -1769682206,857533440,0.0,-0.0,610.52197265625 -1769682206,880605696,0.0,-0.0,610.52197265625 -1769682206,913282304,0.0,-0.0,610.52197265625 -1769682206,957183744,0.0,-0.0,610.52197265625 -1769682206,979593472,0.0,-0.0,610.52197265625 -1769682207,446772992,0.0,-0.0,610.5220947265625 -1769682207,480016640,0.0,-0.0,610.5220947265625 -1769682207,513811456,0.0,-0.0,610.5220947265625 -1769682207,548257280,0.0,-0.0,610.5221557617188 -1769682207,580140288,0.0,-0.0,610.5221557617188 -1769682207,615123200,0.0,-0.0,610.5221557617188 -1769682207,647401984,0.0,-0.0,610.5221557617188 -1769682207,680175104,0.0,-0.0,610.5221557617188 -1769682207,713165312,0.0,-0.0,610.522216796875 -1769682207,751116544,0.0,-0.0,610.522216796875 -1769682207,781094912,0.0,-0.0,610.522216796875 -1769682207,813607680,0.0,-0.0,610.522216796875 -1769682207,848231168,0.0,-0.0,610.522216796875 -1769682207,879717120,0.0,-0.0,610.522216796875 -1769682207,913111808,0.0,-0.0,610.522216796875 -1769682207,946620928,0.0,-0.0,610.522216796875 -1769682207,980966400,0.0,-0.0,610.522216796875 -1769682208,13793280,0.0,-0.0,610.522216796875 -1769682208,479720192,0.0,-0.0,610.5223999023438 -1769682208,514244352,0.0,-0.0,610.5223999023438 -1769682208,550054400,0.0,-0.0,610.5223999023438 -1769682208,580701696,0.0,-0.0,610.5223999023438 -1769682208,613005568,0.0,-0.0,610.5223999023438 -1769682208,646714368,0.0,-0.0,610.5223999023438 -1769682208,681321216,0.0,-0.0,610.5223999023438 -1769682208,714007552,0.0,-0.0,610.5223999023438 -1769682208,748898304,0.0,-0.0,610.5223999023438 -1769682208,780890112,0.0,-0.0,610.5223999023438 -1769682208,813432832,0.0,-0.0,610.5223999023438 -1769682208,847763200,0.0,-0.0,610.5223999023438 -1769682208,880700672,0.0,-0.0,610.5223999023438 -1769682208,914050816,0.0,-0.0,610.5223999023438 -1769682208,948689152,0.0,-0.0,610.5223999023438 -1769682208,980248064,0.0,-0.0,610.5223999023438 -1769682209,13663232,0.0,-0.0,610.5223999023438 -1769682209,48967680,0.0,-0.0,610.5223999023438 -1769682209,550690560,0.0,-0.0,610.5223999023438 -1769682209,581540864,0.0,-0.0,610.5223999023438 -1769682209,613680640,0.0,-0.0,610.5223999023438 -1769682209,648251648,0.0,-0.0,610.5223999023438 -1769682209,681176064,0.0,-0.0,610.5223999023438 -1769682209,713235968,0.0,-0.0,610.5223999023438 -1769682209,748465920,0.0,-0.0,610.5223999023438 -1769682209,783519744,0.0,-0.0,610.5223999023438 -1769682209,814968064,0.0,-0.0,610.5223999023438 -1769682209,848047104,0.0,-0.0,610.5223999023438 -1769682209,879817728,0.0,-0.0,610.5223999023438 -1769682209,914148352,0.0,-0.0,610.5223999023438 -1769682209,951064064,0.0,-0.0,610.5223999023438 -1769682209,982614528,0.0,-0.0,610.5223999023438 -1769682210,13415936,0.0,-0.0,610.5223999023438 -1769682210,62181376,0.0,-0.0,610.5223999023438 -1769682210,69845760,0.0,-0.0,610.5223999023438 -1769682210,613713152,0.0,-0.0,610.5223999023438 -1769682210,647152896,0.0,-0.0,610.5223999023438 -1769682210,680732160,0.0,-0.0,610.5223999023438 -1769682210,714959360,0.0,-0.0,610.5223999023438 -1769682210,751610880,0.0,-0.0,610.5223999023438 -1769682210,780151296,0.0,-0.0,610.5223999023438 -1769682210,813879040,0.0,-0.0,610.5223999023438 -1769682210,850827008,0.0,-0.0,610.5223999023438 -1769682210,880617984,0.0,-0.0,610.5223999023438 -1769682210,913469440,0.0,-0.0,610.5223999023438 -1769682210,960053248,0.0,-0.0,610.5223999023438 -1769682210,979924736,0.0,-0.0,610.5223999023438 -1769682211,13974528,0.0,-0.0,610.5223999023438 -1769682211,48370432,0.0,-0.0,610.5223999023438 -1769682211,81715968,0.0,-0.0,610.5223999023438 -1769682211,113379840,0.0,-0.0,610.5223999023438 -1769682211,147083776,0.0,-0.0,610.5223999023438 -1769682211,183228416,0.0,-0.0,610.5223999023438 -1769682211,213723392,0.0,-0.0,610.5223999023438 -1769682211,682214400,0.0,-0.0,610.5223999023438 -1769682211,714928640,0.0,-0.0,610.5223999023438 -1769682211,765383424,0.0,-0.0,610.5223999023438 -1769682211,772264960,0.0,-0.0,610.5223999023438 -1769682211,813314816,0.0,-0.0,610.5223999023438 -1769682211,862832384,0.0,-0.0,610.5223999023438 -1769682211,870007808,0.0,-0.0,610.5223999023438 -1769682211,913292800,0.0,-0.0,610.5223999023438 -1769682211,947898624,0.0,-0.0,610.5223999023438 -1769682211,980865792,0.0,-0.0,610.5223999023438 -1769682212,14882304,0.0,-0.0,610.5223999023438 -1769682212,48634624,0.0,-0.0,610.5223999023438 -1769682212,80637184,0.0,-0.0,610.5223999023438 -1769682212,114171904,0.0,-0.0,610.5223999023438 -1769682212,149696512,0.0,-0.0,610.5223999023438 -1769682212,181921536,0.0,-0.0,610.5223999023438 -1769682212,213685760,0.0,-0.0,610.5223999023438 -1769682212,260640000,0.0,-0.0,610.5223999023438 -1769682212,280925696,0.0,-0.0,610.5223999023438 -1769682212,762665472,0.0,-0.0,610.5223999023438 -1769682212,768870400,0.0,-0.0,610.5223999023438 -1769682212,814328832,0.0,-0.0,610.5223999023438 -1769682212,847870464,0.0,-0.0,610.5223999023438 -1769682212,881034496,0.0,-0.0,610.5223999023438 -1769682212,913886464,0.0,-0.0,610.5223999023438 -1769682212,948845568,0.0,-0.0,610.5223999023438 -1769682212,980126464,0.0,-0.0,610.5223999023438 -1769682213,15469824,0.0,-0.0,610.5223999023438 -1769682213,59959040,0.0,-0.0,610.5223999023438 -1769682213,80347904,0.0,-0.0,610.5223999023438 -1769682213,114457600,0.0,-0.0,610.5223999023438 -1769682213,159570944,0.0,-0.0,610.5223999023438 -1769682213,180527360,0.0,-0.0,610.5223999023438 -1769682213,213548032,0.0,-0.0,610.5223999023438 -1769682213,250955008,0.0,-0.0,610.5223999023438 -1769682213,283951616,0.0,-0.0,610.5223999023438 -1769682213,851806976,0.06103570759296417,0.010404916480183601,610.494873046875 -1769682213,881264640,0.07321997731924057,0.01142288837581873,610.487548828125 -1769682213,913535232,0.08536332100629807,0.012067525647580624,610.4796142578125 -1769682213,960177664,0.10195944458246231,0.012808654457330704,610.4674682617188 -1769682213,969041408,0.11040974408388138,0.013099785894155502,610.4608764648438 -1769682214,14630912,0.127756267786026,0.013542931526899338,610.4466552734375 -1769682214,49905664,0.14547181129455566,0.013832507655024529,610.4309692382812 -1769682214,81401088,0.15883423388004303,0.013978192582726479,610.4183349609375 -1769682214,114237440,0.17218510806560516,0.014079300686717033,610.4049682617188 -1769682214,150128640,0.19035829603672028,0.01418958231806755,610.3860473632812 -1769682214,180818944,0.20410384237766266,0.014251109212636948,610.3710327148438 -1769682214,214877696,0.2182924896478653,0.014323979616165161,610.355224609375 -1769682214,252725760,0.23831325769424438,0.0144476518034935,610.3328857421875 -1769682214,280498432,0.25382062792778015,0.01455911248922348,610.315185546875 -1769682214,313824256,0.2699202001094818,0.014686893671751022,610.296630859375 -1769682214,361282304,0.28999051451683044,0.014829099178314209,610.2703247070312 -1769682214,369785856,0.29878631234169006,0.014865610748529434,610.2567138671875 -1769682214,414332160,0.31466060876846313,0.014967937022447586,610.2290649414062 -1769682214,447556096,0.3281581699848175,0.015035275369882584,610.2013549804688 -1769682214,949974784,0.551561713218689,0.01836484670639038,609.791748046875 -1769682214,987657472,0.5723786950111389,0.018817901611328125,609.7582397460938 -1769682215,14424576,0.5933755040168762,0.01926606148481369,609.7238159179688 -1769682215,49449728,0.6217347979545593,0.01983276754617691,609.6763916015625 -1769682215,80876288,0.6427223682403564,0.020249664783477783,609.6395263671875 -1769682215,114425344,0.6635723114013672,0.02062854915857315,609.6018676757812 -1769682215,150853632,0.690416157245636,0.02112489938735962,609.550048828125 -1769682215,181174784,0.7096025347709656,0.02147415280342102,609.5101928710938 -1769682215,213793280,0.7286855578422546,0.021834060549736023,609.4696044921875 -1769682215,258285312,0.7560700178146362,0.02235954999923706,609.413818359375 -1769682215,281172992,0.7766503095626831,0.0227673202753067,609.3705444335938 -1769682215,314899200,0.7973412871360779,0.023189112544059753,609.325927734375 -1769682215,347693824,0.8252719044685364,0.023797065019607544,609.2643432617188 -1769682215,382423040,0.8463760018348694,0.02426964044570923,609.2164916992188 -1769682215,415555840,0.8675685524940491,0.024750977754592896,609.167236328125 -1769682215,449410560,0.8959264159202576,0.025415167212486267,609.0990600585938 -1769682215,480963328,0.9173049926757812,0.025928333401679993,609.0462036132812 -1769682215,514875136,0.9387401342391968,0.026460111141204834,608.9918823242188 -1769682216,15371264,1.2956031560897827,0.03644898533821106,607.8302612304688 -1769682216,54428416,1.323475956916809,0.03704670071601868,607.7158203125 -1769682216,82000128,1.3442500829696655,0.037444889545440674,607.6276245117188 -1769682216,113999616,1.365081787109375,0.03781035542488098,607.5376586914062 -1769682216,149875456,1.3925522565841675,0.03862786293029785,607.41552734375 -1769682216,172985600,1.4062726497650146,0.03891664743423462,607.3536987304688 -1769682216,216479744,1.433323860168457,0.040424853563308716,607.2280883789062 -1769682216,248570880,1.4603185653686523,0.041661977767944336,607.099609375 -1769682216,281504512,1.480518102645874,0.04258468747138977,607.001220703125 -1769682216,314105344,1.5007197856903076,0.04349642992019653,606.9009399414062 -1769682216,351474432,1.5277384519577026,0.04470476508140564,606.7640380859375 -1769682216,381028608,1.5480738878250122,0.04566621780395508,606.6588745117188 -1769682216,414101504,1.5683039426803589,0.046616554260253906,606.5511474609375 -1769682216,451370752,1.595153570175171,0.04786956310272217,606.4036254882812 -1769682216,481918464,1.6152143478393555,0.04884052276611328,606.289794921875 -1769682216,513860096,1.6351344585418701,0.04978346824645996,606.1732788085938 -1769682216,561142784,1.6617722511291504,0.051036834716796875,606.0137939453125 -1769682216,569040640,1.6750487089157104,0.051442235708236694,605.9320678710938 -1769682217,114829056,2.024792432785034,0.06842169165611267,603.1353759765625 -1769682217,150020864,2.0496199131011963,0.06974920630455017,602.880615234375 -1769682217,181135360,2.0680625438690186,0.07074320316314697,602.6859130859375 -1769682217,214512896,2.0864369869232178,0.07172095775604248,602.4879760742188 -1769682217,250469888,2.110809803009033,0.07300496101379395,602.2194213867188 -1769682217,281689856,2.1290431022644043,0.07397621870040894,602.0144653320312 -1769682217,314854144,2.1471028327941895,0.07489514350891113,601.8065185546875 -1769682217,352030720,2.171006441116333,0.07603180408477783,601.524658203125 -1769682217,382893056,2.1888668537139893,0.0768468976020813,601.3101806640625 -1769682217,415529216,2.206591844558716,0.07760864496231079,601.0931396484375 -1769682217,449263104,2.230024576187134,0.07863503694534302,600.7999267578125 -1769682217,473219328,2.24169659614563,0.07823199033737183,600.6515502929688 -1769682217,514353664,2.2649683952331543,0.07992446422576904,600.3512573242188 -1769682217,547707136,2.288137674331665,0.08047938346862793,600.0459594726562 -1769682217,581801472,2.3053128719329834,0.08104324340820312,599.8130493164062 -1769682217,615286272,2.3215482234954834,0.0817708969116211,599.5763549804688 -1769682217,648750848,2.3428876399993896,0.08313459157943726,599.2550048828125 -1769682217,682823936,2.358797073364258,0.08429133892059326,599.0093994140625 -1769682217,714868224,2.3746285438537598,0.08551663160324097,598.7595825195312 -1769682218,214104064,2.60992431640625,0.11176192760467529,593.9683227539062 -1769682218,260209152,2.6259915828704834,0.1137920618057251,593.5325317382812 -1769682218,280855552,2.6379234790802,0.11523598432540894,593.2008666992188 -1769682218,314087936,2.6496224403381348,0.11655247211456299,592.8651123046875 -1769682218,347826944,2.6648786067962646,0.11837798357009888,592.411376953125 -1769682218,381497088,2.676172971725464,0.1197577714920044,592.0662231445312 -1769682218,414872064,2.6872620582580566,0.12116950750350952,591.7166748046875 -1769682218,448879872,2.701831340789795,0.12310820817947388,591.243408203125 -1769682218,482205184,2.7126426696777344,0.12470752000808716,590.8828735351562 -1769682218,514742272,2.723262071609497,0.1263074278831482,590.5169677734375 -1769682218,549879808,2.73726224899292,0.12868422269821167,590.0211791992188 -1769682218,581385216,2.7475945949554443,0.1306949257850647,589.6431884765625 -1769682218,614417664,2.7579495906829834,0.13244974613189697,589.259765625 -1769682218,658602240,2.771883964538574,0.13407325744628906,588.7384033203125 -1769682218,680763136,2.7821788787841797,0.13520121574401855,588.3397827148438 -1769682218,714463744,2.7924137115478516,0.13628172874450684,587.9348754882812 -1769682218,760718848,2.8058784008026123,0.13769912719726562,587.3855590820312 -1769682218,768067072,2.812584161758423,0.13700520992279053,587.1072998046875 -1769682219,281264640,2.9619827270507812,0.16224157810211182,579.3280029296875 -1769682219,314994688,2.9692230224609375,0.16354310512542725,578.8350830078125 -1769682219,351509760,2.9785866737365723,0.16581511497497559,578.1719970703125 -1769682219,381148160,2.985398292541504,0.1676245927810669,577.6698608398438 -1769682219,416422656,2.992027997970581,0.1693969964981079,577.163330078125 -1769682219,451839232,3.0006935596466064,0.17166686058044434,576.4806518554688 -1769682219,480901120,3.0070383548736572,0.17338240146636963,575.9632568359375 -1769682219,514323712,3.0132033824920654,0.1750890016555786,575.4414672851562 -1769682219,559220992,3.0213663578033447,0.17734122276306152,574.7388916015625 -1769682219,581066752,3.027401924133301,0.17903196811676025,574.2069091796875 -1769682219,615183360,3.0333893299102783,0.18065428733825684,573.6703491210938 -1769682219,649313792,3.0411977767944336,0.1826002597808838,572.9481811523438 -1769682219,685675264,3.04707932472229,0.18385612964630127,572.4008178710938 -1769682219,714441984,3.052924871444702,0.18496441841125488,571.84912109375 -1769682219,766531584,3.0605356693267822,0.18636715412139893,571.1068725585938 -1769682219,772660992,3.0646045207977295,0.1818525791168213,570.73291015625 -1769682219,814243072,3.0717644691467285,0.1882873773574829,569.9796142578125 -1769682220,358793728,3.157902240753174,0.21350741386413574,559.0431518554688 -1769682220,381307648,3.162076950073242,0.21513962745666504,558.3922729492188 -1769682220,414526720,3.1662607192993164,0.21670663356781006,557.7373046875 -1769682220,448191744,3.1716723442077637,0.21872448921203613,556.8578491210938 -1769682220,472167936,3.174564838409424,0.21577811241149902,556.4155883789062 -1769682220,514971904,3.1793811321258545,0.22168588638305664,555.5258178710938 -1769682220,548999168,3.1841957569122314,0.22354602813720703,554.6292114257812 -1769682220,581433088,3.1876282691955566,0.2248220443725586,553.952392578125 -1769682220,614877952,3.190836191177368,0.2260533571243286,553.2715454101562 -1769682220,648373504,3.19492244720459,0.22763586044311523,552.3576049804688 -1769682220,681779712,3.197789192199707,0.2286992073059082,551.66748046875 -1769682220,714551296,3.200552463531494,0.2298896312713623,550.9733276367188 -1769682220,749452288,3.204064130783081,0.2310163974761963,550.0404052734375 -1769682220,781481728,3.2064647674560547,0.23190736770629883,549.3345947265625 -1769682220,815639808,3.208625555038452,0.23274433612823486,548.6240234375 -1769682220,860748544,3.2112667560577393,0.2337968349456787,547.6697998046875 -1769682220,869486080,3.212711811065674,0.2311255931854248,547.1902465820312 -1769682220,914784256,3.2146639823913574,0.23509609699249268,546.2269897460938 -1769682220,948059648,3.216716766357422,0.23575162887573242,545.2590942382812 -1769682221,383920640,3.2227940559387207,0.24900352954864502,534.6292114257812 -1769682221,415661056,3.2222769260406494,0.25018179416656494,533.8701782226562 -1769682221,452448000,3.2214250564575195,0.25170910358428955,532.8531494140625 -1769682221,482677248,3.2207255363464355,0.2528672218322754,532.0865478515625 -1769682221,514694656,3.219949245452881,0.2539944648742676,531.3165283203125 -1769682221,548813312,3.218905448913574,0.25536656379699707,530.2849731445312 -1769682221,581344256,3.218184471130371,0.25636208057403564,529.5078735351562 -1769682221,614788864,3.2174510955810547,0.25732409954071045,528.7281494140625 -1769682221,653980160,3.216538667678833,0.25860774517059326,527.6845703125 -1769682221,682299136,3.2159481048583984,0.2595553398132324,526.8989868164062 -1769682221,714618880,3.2154157161712646,0.2604731321334839,526.11083984375 -1769682221,749705216,3.214677095413208,0.26160264015197754,525.0562744140625 -1769682221,783798016,3.214050769805908,0.26237523555755615,524.2623901367188 -1769682221,815033856,3.2134478092193604,0.26305651664733887,523.4661254882812 -1769682221,850742272,3.212834358215332,0.2638152837753296,522.4012451171875 -1769682221,881207552,3.212493419647217,0.2643120288848877,521.6005859375 -1769682221,916864512,3.2122528553009033,0.2649264335632324,520.7984619140625 -1769682221,957552128,3.21199631690979,0.26540541648864746,519.7257080078125 -1769682222,482626560,3.21395206451416,0.25331807136535645,505.7213439941406 -1769682222,514863872,3.2109153270721436,0.2524813413619995,504.9518127441406 -1769682222,548831744,3.2076656818389893,0.25124162435531616,503.93450927734375 -1769682222,581821952,3.206486940383911,0.25036197900772095,503.17718505859375 -1769682222,617517312,3.206105947494507,0.24948465824127197,502.4239501953125 -1769682222,652703488,3.2045271396636963,0.24808990955352783,501.4254455566406 -1769682222,681211648,3.2030189037323,0.24711906909942627,500.6814270019531 -1769682222,714743808,3.2013115882873535,0.24609047174453735,499.9416198730469 -1769682222,758190592,3.199012041091919,0.24447423219680786,498.96270751953125 -1769682222,771592448,3.196281671524048,0.23735278844833374,498.47686767578125 -1769682222,814609920,3.188858985900879,0.24090224504470825,497.5151062011719 -1769682222,850384896,3.1822423934936523,0.23839318752288818,496.5672302246094 -1769682222,883341312,3.1787943840026855,0.23670589923858643,495.8645324707031 -1769682222,915484672,3.176863193511963,0.23516839742660522,495.16754150390625 -1769682222,948517376,3.1749351024627686,0.23311489820480347,494.24505615234375 -1769682222,981682432,3.173989772796631,0.23136776685714722,493.55743408203125 -1769682223,16192000,3.1735544204711914,0.2295720875263214,492.8731994628906 -1769682223,48303616,3.173124313354492,0.2271462082862854,491.9662780761719 -1769682223,82659584,3.173424243927002,0.22529056668281555,491.2903747558594 -1769682223,114579712,3.1740739345550537,0.22337058186531067,490.6185302734375 -1769682223,148581120,3.175323963165283,0.22062602639198303,489.72967529296875 -1769682223,181209856,3.176405191421509,0.21853819489479065,489.0691223144531 -1769682223,215245824,3.1778669357299805,0.21672847867012024,488.4140930175781 -1769682223,249088000,3.180328607559204,0.21443602442741394,487.54937744140625 -1769682223,282373632,3.182634115219116,0.212680846452713,486.9071350097656 -1769682223,314788608,3.1852288246154785,0.21084672212600708,486.2704162597656 -1769682223,349064448,3.188873052597046,0.2077530473470688,485.4297180175781 -1769682235,250595840,0.0,-0.0,451.21014404296875 -1769682235,283861504,0.0,-0.0,451.210205078125 -1769682235,306318592,0.0,-0.0,451.210205078125 -1769682235,350250240,0.0,-0.0,451.210205078125 -1769682235,382697728,0.0,-0.0,451.210205078125 -1769682235,416664832,0.0,-0.0,451.21026611328125 -1769682235,453504256,0.0,-0.0,451.21026611328125 -1769682235,469904384,0.0,-0.0,451.21026611328125 -1769682235,516407296,0.0,-0.0,451.2103271484375 -1769682235,550402304,0.0,-0.0,451.2103271484375 -1769682235,570142208,0.0,-0.0,451.2103271484375 -1769682235,615940096,0.0,-0.0,451.2103576660156 diff --git a/awkernel_async_lib/Cargo.toml b/awkernel_async_lib/Cargo.toml index 209cd59b9..961ed2ad7 100644 --- a/awkernel_async_lib/Cargo.toml +++ b/awkernel_async_lib/Cargo.toml @@ -45,4 +45,4 @@ no_preempt = [] spinlock = ["awkernel_lib/spinlock"] clippy = [] perf = [] -relax-get-period = [] +need-get-period = [] diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index 743e75632..5dc980180 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -120,7 +120,7 @@ macro_rules! impl_tuple_traits { const SIZE: usize = $last_idx + 1; } - #[cfg(not(feature = "relax-get-period"))] + #[cfg(feature = "need-get-period")] impl<$($T),+> GetPeriod for ($(($T, u32),)+) { fn get_period(&self) -> u32 { self.$last_idx .1 @@ -133,24 +133,19 @@ impl_tuple_traits!(); impl_tuple_traits!(0 => T1); impl_tuple_traits!(1 => T1, T2); impl_tuple_traits!(2 => T1, T2, T3); -impl_tuple_traits!(3 => T1, T2, T3, T4); -impl_tuple_traits!(4 => T1, T2, T3, T4, T5); -impl_tuple_traits!(5 => T1, T2, T3, T4, T5, T6); -impl_tuple_traits!(6 => T1, T2, T3, T4, T5, T6, T7); -impl_tuple_traits!(7 => T1, T2, T3, T4, T5, T6, T7, T8); -#[cfg(not(feature = "relax-get-period"))] +#[cfg(feature = "need-get-period")] pub trait DagSubscriberItem: TupleSize + GetPeriod + Send {} -#[cfg(not(feature = "relax-get-period"))] +#[cfg(feature = "need-get-period")] impl DagSubscriberItem for T where T: TupleSize + GetPeriod + Send {} -#[cfg(feature = "relax-get-period")] +#[cfg(not(feature = "need-get-period"))] pub trait DagSubscriberItem: TupleSize + Send {} -#[cfg(feature = "relax-get-period")] +#[cfg(not(feature = "need-get-period"))] impl DagSubscriberItem for T where T: TupleSize + Send {} -#[cfg(not(feature = "relax-get-period"))] +#[cfg(feature = "need-get-period")] pub fn get_period(args: &T) -> u32 { args.get_period() } @@ -1020,7 +1015,7 @@ where subscribers.recv_all().await; if crate::task::perf::ENABLE_PERIOD_TRACKING.load(core::sync::atomic::Ordering::Relaxed) { - #[cfg(not(feature = "relax-get-period"))] + #[cfg(feature = "need-get-period")] { // [end] pubsub communication latency let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; @@ -1086,7 +1081,7 @@ where loop { if crate::task::perf::ENABLE_PERIOD_TRACKING.load(core::sync::atomic::Ordering::Relaxed) { - #[cfg(not(feature = "relax-get-period"))] + #[cfg(feature = "need-get-period")] { let index = get_period_count(dag_info.dag_id.clone() as usize) as usize; let cpu_id = awkernel_lib::cpu::cpu_id(); @@ -1153,7 +1148,7 @@ where let args: ::Item = subscribers.recv_all().await; if crate::task::perf::ENABLE_PERIOD_TRACKING.load(core::sync::atomic::Ordering::Relaxed) { - #[cfg(not(feature = "relax-get-period"))] + #[cfg(feature = "need-get-period")] { // [end] pubsub communication latency let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index 8ad694c5a..2fb704171 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -385,7 +385,7 @@ where { /// Send with metadata forwarded from `send_all_with_meta`. pub async fn send_with_meta(&self, data: T, _pub_id: u32, _index: usize, _node_id: u32) { - #[cfg(not(feature = "relax-get-period"))] + #[cfg(feature = "need-get-period")] { let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; publish_timestamp_at(_index, start, _pub_id, _node_id); diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index 4634a3510..2d1e673ad 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -474,8 +474,8 @@ pub mod perf { use core::sync::atomic::{AtomicBool, AtomicU32, Ordering}; /// Flag to control whether period tracking is enabled - /// When false (with relax-get-period feature), period tracking is disabled to reduce BSS memory - /// When true (without relax-get-period feature), period tracking is enabled + /// When false (without need-get-period feature), period tracking is disabled to reduce BSS memory + /// When true (with need-get-period feature), period tracking is enabled pub static ENABLE_PERIOD_TRACKING: AtomicBool = AtomicBool::new(false); #[derive(Debug, Clone, PartialEq, Eq)] diff --git a/awkernel_async_lib/src/time_interval.rs b/awkernel_async_lib/src/time_interval.rs index 10a87b0ec..91ea5286a 100644 --- a/awkernel_async_lib/src/time_interval.rs +++ b/awkernel_async_lib/src/time_interval.rs @@ -103,7 +103,7 @@ pub fn interval(period: Duration, dag_id: u32) -> Interval { pub fn interval_at(start: Time, period: Duration, _dag_id: u32) -> Interval { assert!(!period.is_zero(), "`period` must be non-zero."); - #[cfg(not(feature = "relax-get-period"))] + #[cfg(feature = "need-get-period")] { let index = get_period_count(_dag_id.clone() as usize) as usize; update_pre_send_outer_timestamp_at(index, start.uptime().as_nanos() as u64, _dag_id.clone()); diff --git a/userland/Cargo.toml b/userland/Cargo.toml index c6fac4eaa..ab94f86dc 100644 --- a/userland/Cargo.toml +++ b/userland/Cargo.toml @@ -66,10 +66,6 @@ optional = true path = "../applications/tests/test_dag" optional = true -[dependencies.test_autoware] -path = "../applications/tests/test_autoware" -optional = true - [dependencies.test_dvfs] path = "../applications/tests/test_dvfs" optional = true @@ -79,7 +75,7 @@ path = "../applications/tests/test_voluntary_preemption" optional = true [features] -default = ["test_autoware"] +default = ["test_dag"] perf = ["awkernel_services/perf"] # Evaluation applications @@ -97,5 +93,4 @@ test_gedf = ["dep:test_gedf"] test_measure_channel = ["dep:test_measure_channel"] test_measure_channel_heavy = ["dep:test_measure_channel_heavy"] test_dag = ["dep:test_dag"] -test_autoware = ["dep:test_autoware"] test_voluntary_preemption = ["dep:test_voluntary_preemption"] diff --git a/userland/src/lib.rs b/userland/src/lib.rs index 695f13b79..01a66fe18 100644 --- a/userland/src/lib.rs +++ b/userland/src/lib.rs @@ -46,9 +46,6 @@ pub async fn main() -> Result<(), Cow<'static, str>> { #[cfg(feature = "test_dag")] test_dag::run().await; // test for DAG - #[cfg(feature = "test_autoware")] - test_autoware::run().await; // test for autoware - #[cfg(feature = "test_dvfs")] test_dvfs::run().await; // test for DVFS From 87742e578ab145bbc9e5810459b4d56a23be125a Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Wed, 15 Apr 2026 18:31:10 +0900 Subject: [PATCH 19/60] fix: delete the portion of impl about macro Signed-off-by: nokosaaan --- awkernel_async_lib/src/dag.rs | 45 -------------------------------- awkernel_async_lib/src/pubsub.rs | 42 +---------------------------- 2 files changed, 1 insertion(+), 86 deletions(-) diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index 5dc980180..ceb593d55 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -650,51 +650,6 @@ pub async fn finish_create_dags(dags: &[Arc]) -> Result<(), Vec> } } -pub fn reset_all_dags() { - { - let mut dags_node = MCSNode::new(); - let mut dags = DAGS.lock(&mut dags_node); - dags.id_to_dag.clear(); - dags.candidate_id = 1; - } - - { - let mut pending_node = MCSNode::new(); - let mut pending_tasks = PENDING_TASKS.lock(&mut pending_node); - pending_tasks.clear(); - } - - { - let mut source_pending_node = MCSNode::new(); - let mut source_pending_tasks = SOURCE_PENDING_TASKS.lock(&mut source_pending_node); - source_pending_tasks.clear(); - } - - { - let mut node = MCSNode::new(); - let mut mismatch_subscribe = MISMATCH_SUBSCRIBE_NODES.lock(&mut node); - mismatch_subscribe.clear(); - } - - { - let mut node = MCSNode::new(); - let mut mismatch_publish = MISMATCH_PUBLISH_NODES.lock(&mut node); - mismatch_publish.clear(); - } - - { - let mut node = MCSNode::new(); - let mut duplicate_subscribe = DUPLICATE_SUBSCRIBE_NODES.lock(&mut node); - duplicate_subscribe.clear(); - } - - { - let mut node = MCSNode::new(); - let mut duplicate_publish = DUPLICATE_PUBLISH_NODES.lock(&mut node); - duplicate_publish.clear(); - } -} - fn remove_dag(id: u32) { let mut dags_node = MCSNode::new(); let mut dags = DAGS.lock(&mut dags_node); diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index 2fb704171..a13a7ab6b 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -383,7 +383,6 @@ impl Publisher where T: Clone + Sync + Send, { - /// Send with metadata forwarded from `send_all_with_meta`. pub async fn send_with_meta(&self, data: T, _pub_id: u32, _index: usize, _node_id: u32) { #[cfg(feature = "need-get-period")] { @@ -850,11 +849,6 @@ impl_tuple_to_pub_sub!(); impl_tuple_to_pub_sub!(A); impl_tuple_to_pub_sub!(A, B); impl_tuple_to_pub_sub!(A, B, C); -impl_tuple_to_pub_sub!(T0, T1, T2, T3); -impl_tuple_to_pub_sub!(T0, T1, T2, T3, T4); -impl_tuple_to_pub_sub!(T0, T1, T2, T3, T4, T5); -impl_tuple_to_pub_sub!(T0, T1, T2, T3, T4, T5, T6); -impl_tuple_to_pub_sub!(T0, T1, T2, T3, T4, T5, T6, T7); macro_rules! impl_async_receiver_for_tuple { () => { @@ -868,6 +862,7 @@ macro_rules! impl_async_receiver_for_tuple { impl MultipleSender for () { type Item = (); + fn send_all(&self, _item: Self::Item) -> Pin + Send + '_>> { Box::pin(async move{}) } @@ -918,41 +913,6 @@ impl_async_receiver_for_tuple!(); impl_async_receiver_for_tuple!((A, a, p)); impl_async_receiver_for_tuple!((A, a, p), (B, b, q)); impl_async_receiver_for_tuple!((A, a, p), (B, b, q), (C, c, r)); -impl_async_receiver_for_tuple!((T0, v0, p0), (T1, v1, p1), (T2, v2, p2), (T3, v3, p3)); -impl_async_receiver_for_tuple!( - (T0, v0, p0), - (T1, v1, p1), - (T2, v2, p2), - (T3, v3, p3), - (T4, v4, p4) -); -impl_async_receiver_for_tuple!( - (T0, v0, p0), - (T1, v1, p1), - (T2, v2, p2), - (T3, v3, p3), - (T4, v4, p4), - (T5, v5, p5) -); -impl_async_receiver_for_tuple!( - (T0, v0, p0), - (T1, v1, p1), - (T2, v2, p2), - (T3, v3, p3), - (T4, v4, p4), - (T5, v5, p5), - (T6, v6, p6) -); -impl_async_receiver_for_tuple!( - (T0, v0, p0), - (T1, v1, p1), - (T2, v2, p2), - (T3, v3, p3), - (T4, v4, p4), - (T5, v5, p5), - (T6, v6, p6), - (T7, v7, p7) -); #[cfg(test)] mod tests { From 5d30fc2dc568fd29fd5647a0f77747f243d413cf Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Wed, 15 Apr 2026 18:52:57 +0900 Subject: [PATCH 20/60] fix: delete unnecessary imports Signed-off-by: nokosaaan --- awkernel_async_lib/src/dag.rs | 4 +--- awkernel_async_lib/src/time_interval.rs | 6 +++++- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index ceb593d55..bf68f7955 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -55,7 +55,6 @@ mod performance; use crate::{ dag::{ - self, graph::{ algo::{connected_components, is_cyclic_directed}, direction::Direction, @@ -66,8 +65,7 @@ use crate::{ scheduler::SchedulerType, task::{ perf::{ - get_period_count, get_pub_count, get_sink_count, get_sub_count, increment_period_count, - increment_pub_count, increment_sink_count, increment_sub_count, publish_timestamp_at, subscribe_timestamp_at, + get_period_count, increment_period_count, increment_pub_count, increment_sink_count, increment_sub_count, publish_timestamp_at, subscribe_timestamp_at, update_fin_recv_outer_timestamp_at, update_pre_send_outer_timestamp_at, }, DagInfo, diff --git a/awkernel_async_lib/src/time_interval.rs b/awkernel_async_lib/src/time_interval.rs index 91ea5286a..8191565f9 100644 --- a/awkernel_async_lib/src/time_interval.rs +++ b/awkernel_async_lib/src/time_interval.rs @@ -106,7 +106,11 @@ pub fn interval_at(start: Time, period: Duration, _dag_id: u32) -> Interval { #[cfg(feature = "need-get-period")] { let index = get_period_count(_dag_id.clone() as usize) as usize; - update_pre_send_outer_timestamp_at(index, start.uptime().as_nanos() as u64, _dag_id.clone()); + update_pre_send_outer_timestamp_at( + index, + start.uptime().as_nanos() as u64, + _dag_id.clone(), + ); } Interval { delay: None, From 59b53544a09a433378733c3ca40d3c6e678ee17f Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 17 Apr 2026 13:01:11 +0900 Subject: [PATCH 21/60] fix: attach cargo fmt 1 Signed-off-by: nokosaaan --- awkernel_async_lib/src/dag.rs | 22 +++++++++++++++------- 1 file changed, 15 insertions(+), 7 deletions(-) diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index bf68f7955..3c762eacb 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -65,7 +65,8 @@ use crate::{ scheduler::SchedulerType, task::{ perf::{ - get_period_count, increment_period_count, increment_pub_count, increment_sink_count, increment_sub_count, publish_timestamp_at, subscribe_timestamp_at, + get_period_count, increment_period_count, increment_pub_count, increment_sink_count, + increment_sub_count, publish_timestamp_at, subscribe_timestamp_at, update_fin_recv_outer_timestamp_at, update_pre_send_outer_timestamp_at, }, DagInfo, @@ -967,7 +968,8 @@ where let args: <::Subscribers as MultipleReceiver>::Item = subscribers.recv_all().await; - if crate::task::perf::ENABLE_PERIOD_TRACKING.load(core::sync::atomic::Ordering::Relaxed) { + if crate::task::perf::ENABLE_PERIOD_TRACKING.load(core::sync::atomic::Ordering::Relaxed) + { #[cfg(feature = "need-get-period")] { // [end] pubsub communication latency @@ -1033,7 +1035,8 @@ where interval.tick().await; loop { - if crate::task::perf::ENABLE_PERIOD_TRACKING.load(core::sync::atomic::Ordering::Relaxed) { + if crate::task::perf::ENABLE_PERIOD_TRACKING.load(core::sync::atomic::Ordering::Relaxed) + { #[cfg(feature = "need-get-period")] { let index = get_period_count(dag_info.dag_id.clone() as usize) as usize; @@ -1042,7 +1045,8 @@ where crate::task::set_task_period(task_id, Some(index as u32)); } if index != 0 { - let release_time = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + let release_time = + awkernel_lib::time::Time::now().uptime().as_nanos() as u64; update_pre_send_outer_timestamp_at( index, release_time, @@ -1100,7 +1104,8 @@ where loop { let args: ::Item = subscribers.recv_all().await; - if crate::task::perf::ENABLE_PERIOD_TRACKING.load(core::sync::atomic::Ordering::Relaxed) { + if crate::task::perf::ENABLE_PERIOD_TRACKING.load(core::sync::atomic::Ordering::Relaxed) + { #[cfg(feature = "need-get-period")] { // [end] pubsub communication latency @@ -1118,11 +1123,14 @@ where } let timenow = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; if count_st != 0 { - update_fin_recv_outer_timestamp_at(count_st as usize, timenow, dag_info.dag_id); + update_fin_recv_outer_timestamp_at( + count_st as usize, + timenow, + dag_info.dag_id, + ); } increment_sink_count(dag_info.dag_id.clone() as usize); } - } f(args); } From b77385e6eda99c084db3c3b60ea5605f7b59a8fc Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 17 Apr 2026 16:37:44 +0900 Subject: [PATCH 22/60] fix: delete if-else diversion and focus feature diversion Signed-off-by: nokosaaan --- awkernel_async_lib/src/dag.rs | 144 ++++++++++++++++----------------- awkernel_async_lib/src/task.rs | 5 -- 2 files changed, 70 insertions(+), 79 deletions(-) diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index 3c762eacb..686c05c6b 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -968,29 +968,28 @@ where let args: <::Subscribers as MultipleReceiver>::Item = subscribers.recv_all().await; - if crate::task::perf::ENABLE_PERIOD_TRACKING.load(core::sync::atomic::Ordering::Relaxed) + #[cfg(feature = "need-get-period")] { - #[cfg(feature = "need-get-period")] - { - // [end] pubsub communication latency - let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - let count_st = get_period(&args); - subscribe_timestamp_at(count_st as usize, end, 1, dag_info.node_id.clone()); - - // period count from message to TaskInfo - let cpu_id = awkernel_lib::cpu::cpu_id(); - if let Some(task_id) = crate::task::get_current_task(cpu_id) { - crate::task::set_task_period(task_id, Some(count_st)); - } - let results = f(args); - // [start] pubsub communication latency - let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - publish_timestamp_at(count_st as usize, end, 1, dag_info.node_id.clone()); - publishers - .send_all_with_meta(results, 1, count_st as usize, dag_info.node_id) - .await; + // [end] pubsub communication latency + let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + let count_st = get_period(&args); + subscribe_timestamp_at(count_st as usize, end, 1, dag_info.node_id.clone()); + + // period count from message to TaskInfo + let cpu_id = awkernel_lib::cpu::cpu_id(); + if let Some(task_id) = crate::task::get_current_task(cpu_id) { + crate::task::set_task_period(task_id, Some(count_st)); } - } else { + let results = f(args); + // [start] pubsub communication latency + let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + publish_timestamp_at(count_st as usize, end, 1, dag_info.node_id.clone()); + publishers + .send_all_with_meta(results, 1, count_st as usize, dag_info.node_id) + .await; + } + #[cfg(not(feature = "need-get-period"))] + { let results = f(args); publishers.send_all(results).await; } @@ -1035,36 +1034,35 @@ where interval.tick().await; loop { - if crate::task::perf::ENABLE_PERIOD_TRACKING.load(core::sync::atomic::Ordering::Relaxed) + #[cfg(feature = "need-get-period")] { - #[cfg(feature = "need-get-period")] - { - let index = get_period_count(dag_info.dag_id.clone() as usize) as usize; - let cpu_id = awkernel_lib::cpu::cpu_id(); - if let Some(task_id) = crate::task::get_current_task(cpu_id) { - crate::task::set_task_period(task_id, Some(index as u32)); - } - if index != 0 { - let release_time = - awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - update_pre_send_outer_timestamp_at( - index, - release_time, - dag_info.dag_id.clone(), - ); - } - let results = f(); - // [start] pubsub communication latency - let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - publish_timestamp_at(index, end, 0, dag_info.node_id); - publishers - .send_all_with_meta(results, 0, index, dag_info.node_id) - .await; - - increment_period_count(dag_info.dag_id.clone() as usize); - increment_pub_count(0); + let index = get_period_count(dag_info.dag_id.clone() as usize) as usize; + let cpu_id = awkernel_lib::cpu::cpu_id(); + if let Some(task_id) = crate::task::get_current_task(cpu_id) { + crate::task::set_task_period(task_id, Some(index as u32)); } - } else { + if index != 0 { + let release_time = + awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + update_pre_send_outer_timestamp_at( + index, + release_time, + dag_info.dag_id.clone(), + ); + } + let results = f(); + // [start] pubsub communication latency + let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + publish_timestamp_at(index, end, 0, dag_info.node_id); + publishers + .send_all_with_meta(results, 0, index, dag_info.node_id) + .await; + + increment_period_count(dag_info.dag_id.clone() as usize); + increment_pub_count(0); + } + + #[cfg(not(feature = "need-get-period"))] { let results = f(); publishers.send_all(results).await; } @@ -1104,34 +1102,32 @@ where loop { let args: ::Item = subscribers.recv_all().await; - if crate::task::perf::ENABLE_PERIOD_TRACKING.load(core::sync::atomic::Ordering::Relaxed) + #[cfg(feature = "need-get-period")] { - #[cfg(feature = "need-get-period")] - { - // [end] pubsub communication latency - let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - let count_st = get_period(&args); - subscribe_timestamp_at(count_st as usize, end, 2, dag_info.node_id.clone()); - increment_pub_count(1); - increment_sub_count(1); - increment_sub_count(2); - - // period count from message to TaskInfo - let cpu_id = awkernel_lib::cpu::cpu_id(); - if let Some(task_id) = crate::task::get_current_task(cpu_id) { - crate::task::set_task_period(task_id, Some(count_st)); - } - let timenow = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - if count_st != 0 { - update_fin_recv_outer_timestamp_at( - count_st as usize, - timenow, - dag_info.dag_id, - ); - } - increment_sink_count(dag_info.dag_id.clone() as usize); + // [end] pubsub communication latency + let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + let count_st = get_period(&args); + subscribe_timestamp_at(count_st as usize, end, 2, dag_info.node_id.clone()); + increment_pub_count(1); + increment_sub_count(1); + increment_sub_count(2); + + // period count from message to TaskInfo + let cpu_id = awkernel_lib::cpu::cpu_id(); + if let Some(task_id) = crate::task::get_current_task(cpu_id) { + crate::task::set_task_period(task_id, Some(count_st)); + } + let timenow = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + if count_st != 0 { + update_fin_recv_outer_timestamp_at( + count_st as usize, + timenow, + dag_info.dag_id, + ); } + increment_sink_count(dag_info.dag_id.clone() as usize); } + f(args); } }; diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index 2d1e673ad..02049f1be 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -473,11 +473,6 @@ pub mod perf { use core::ptr::{read_volatile, write_volatile}; use core::sync::atomic::{AtomicBool, AtomicU32, Ordering}; - /// Flag to control whether period tracking is enabled - /// When false (without need-get-period feature), period tracking is disabled to reduce BSS memory - /// When true (with need-get-period feature), period tracking is enabled - pub static ENABLE_PERIOD_TRACKING: AtomicBool = AtomicBool::new(false); - #[derive(Debug, Clone, PartialEq, Eq)] #[repr(u8)] pub enum PerfState { From 85d9042b1cc2a6ff0adcb89ac55d250baf3d7079 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 17 Apr 2026 16:40:15 +0900 Subject: [PATCH 23/60] fix: apply cargo fmt 2 Signed-off-by: nokosaaan --- awkernel_async_lib/src/dag.rs | 16 ++++++---------- 1 file changed, 6 insertions(+), 10 deletions(-) diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index 686c05c6b..e7fd72bfe 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -1042,8 +1042,7 @@ where crate::task::set_task_period(task_id, Some(index as u32)); } if index != 0 { - let release_time = - awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + let release_time = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; update_pre_send_outer_timestamp_at( index, release_time, @@ -1061,8 +1060,9 @@ where increment_period_count(dag_info.dag_id.clone() as usize); increment_pub_count(0); } - - #[cfg(not(feature = "need-get-period"))] { + + #[cfg(not(feature = "need-get-period"))] + { let results = f(); publishers.send_all(results).await; } @@ -1119,15 +1119,11 @@ where } let timenow = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; if count_st != 0 { - update_fin_recv_outer_timestamp_at( - count_st as usize, - timenow, - dag_info.dag_id, - ); + update_fin_recv_outer_timestamp_at(count_st as usize, timenow, dag_info.dag_id); } increment_sink_count(dag_info.dag_id.clone() as usize); } - + f(args); } }; From c88633aa5f02f79c288b2407e6c8b00733bc2c28 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 17 Apr 2026 16:47:48 +0900 Subject: [PATCH 24/60] fix: experimental apply for perf Signed-off-by: nokosaaan --- kernel/Cargo.toml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/kernel/Cargo.toml b/kernel/Cargo.toml index 9368f5904..1ab9349cf 100644 --- a/kernel/Cargo.toml +++ b/kernel/Cargo.toml @@ -92,12 +92,14 @@ x86 = [ "awkernel_drivers/uart_16550", ] rv32 = [ + "perf", "no_std_unwinding", "awkernel_lib/rv32", "dep:ns16550a", "awkernel_drivers/rv32", ] rv64 = [ + "perf", "no_std_unwinding", "awkernel_lib/rv64", "dep:ns16550a", @@ -112,6 +114,7 @@ aarch64 = [ "awkernel_drivers/aarch64", ] raspi = [ + "perf", "aarch64", "awkernel_drivers/raspi", "awkernel_drivers/pl011", @@ -119,6 +122,7 @@ raspi = [ ] raspi5 = [ + "perf", "aarch64", "awkernel_drivers/raspi", "awkernel_drivers/pcie", @@ -129,6 +133,7 @@ raspi5 = [ ] aarch64_virt = [ + "perf", "aarch64", "awkernel_drivers/all_pcie", "awkernel_drivers/pl011", From 8495759b3490f16cce17171f2cb85582f854bbf6 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 17 Apr 2026 16:55:36 +0900 Subject: [PATCH 25/60] fix: experimental apply for perf 2 Signed-off-by: nokosaaan --- kernel/Cargo.toml | 3 --- 1 file changed, 3 deletions(-) diff --git a/kernel/Cargo.toml b/kernel/Cargo.toml index 1ab9349cf..942920387 100644 --- a/kernel/Cargo.toml +++ b/kernel/Cargo.toml @@ -114,7 +114,6 @@ aarch64 = [ "awkernel_drivers/aarch64", ] raspi = [ - "perf", "aarch64", "awkernel_drivers/raspi", "awkernel_drivers/pl011", @@ -122,7 +121,6 @@ raspi = [ ] raspi5 = [ - "perf", "aarch64", "awkernel_drivers/raspi", "awkernel_drivers/pcie", @@ -133,7 +131,6 @@ raspi5 = [ ] aarch64_virt = [ - "perf", "aarch64", "awkernel_drivers/all_pcie", "awkernel_drivers/pl011", From 8e03ef47da1a1e1d4770f83b6fcb6c61e97a54aa Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 17 Apr 2026 17:02:37 +0900 Subject: [PATCH 26/60] fix: delete .clone() which has Copy trait Signed-off-by: nokosaaan --- awkernel_async_lib/src/dag.rs | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index e7fd72bfe..797421b3e 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -1029,7 +1029,7 @@ where Attribute::default(), ); - let mut interval = interval(period, dag_info.dag_id.clone() as u32); + let mut interval = interval(period, dag_info.dag_id as u32); // Consume the first tick here to start the loop's main body without an initial delay. interval.tick().await; From a728ff82a5bce8f26610b81e36b23685f4b6cd24 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 17 Apr 2026 17:16:36 +0900 Subject: [PATCH 27/60] fix: unused imports and unnecessary casting Signed-off-by: nokosaaan --- awkernel_async_lib/src/dag.rs | 19 ++++++++++--------- awkernel_async_lib/src/pubsub.rs | 1 + awkernel_async_lib/src/task.rs | 21 +++------------------ awkernel_async_lib/src/time_interval.rs | 1 + 4 files changed, 15 insertions(+), 27 deletions(-) diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index 797421b3e..a5a3e2085 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -63,17 +63,18 @@ use crate::{ visit::{EdgeRef, IntoNodeReferences, NodeRef}, }, scheduler::SchedulerType, - task::{ - perf::{ - get_period_count, increment_period_count, increment_pub_count, increment_sink_count, - increment_sub_count, publish_timestamp_at, subscribe_timestamp_at, - update_fin_recv_outer_timestamp_at, update_pre_send_outer_timestamp_at, - }, - DagInfo, - }, + task::DagInfo, time_interval::interval, Attribute, MultipleReceiver, MultipleSender, VectorToPublishers, VectorToSubscribers, }; + +#[cfg(feature = "need-get-period")] +use crate::task::perf::{ + get_period_count, increment_period_count, increment_pub_count, increment_sink_count, + increment_sub_count, publish_timestamp_at, subscribe_timestamp_at, + update_fin_recv_outer_timestamp_at, update_pre_send_outer_timestamp_at, +}; + use alloc::{ borrow::Cow, boxed::Box, @@ -1029,7 +1030,7 @@ where Attribute::default(), ); - let mut interval = interval(period, dag_info.dag_id as u32); + let mut interval = interval(period, dag_info.dag_id); // Consume the first tick here to start the loop's main body without an initial delay. interval.tick().await; diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index a13a7ab6b..55c3bccad 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -52,6 +52,7 @@ use core::{ use futures::Future; use pin_project::pin_project; +#[cfg(feature = "need-get-period")] use crate::task::perf::publish_timestamp_at; /// Data and timestamp. diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index 02049f1be..d1494b8b8 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -471,7 +471,9 @@ pub mod perf { use array_macro::array; use awkernel_lib::cpu::NUM_MAX_CPU; use core::ptr::{read_volatile, write_volatile}; - use core::sync::atomic::{AtomicBool, AtomicU32, Ordering}; + use core::sync::atomic::{Ordering, AtomicU32}; + #[cfg(feature = "need-get-period")] + use core::sync::atomic::AtomicBool; #[derive(Debug, Clone, PartialEq, Eq)] #[repr(u8)] @@ -560,23 +562,6 @@ pub mod perf { pub static PUB_COUNT: [AtomicU32; MAX_PUBSUB] = array![_ => AtomicU32::new(0); MAX_PUBSUB]; pub static SUB_COUNT: [AtomicU32; MAX_PUBSUB] = array![_ => AtomicU32::new(0); MAX_PUBSUB]; - pub fn reset_perf_logs() { - for i in 0..MAX_PUBSUB { - PUB_COUNT[i].store(0, Ordering::Relaxed); - SUB_COUNT[i].store(0, Ordering::Relaxed); - } - for i in 0..MAX_DAGS { - PERIOD_COUNT[i].store(0, Ordering::Relaxed); - SINK_COUNT[i].store(0, Ordering::Relaxed); - } - *SEND_OUTER_TIMESTAMP.lock(&mut MCSNode::new()) = None; - *RECV_OUTER_TIMESTAMP.lock(&mut MCSNode::new()) = None; - *ABSOLUTE_DEADLINE.lock(&mut MCSNode::new()) = None; - *RELATIVE_DEADLINE.lock(&mut MCSNode::new()) = None; - *NODE_START.lock(&mut MCSNode::new()) = None; - *NODE_FINISH.lock(&mut MCSNode::new()) = None; - } - pub fn increment_pub_count(pub_id: usize) { assert!(pub_id < MAX_PUBSUB, "Pub ID out of bounds"); PUB_COUNT[pub_id].fetch_add(1, Ordering::Relaxed); diff --git a/awkernel_async_lib/src/time_interval.rs b/awkernel_async_lib/src/time_interval.rs index 8191565f9..b583cf516 100644 --- a/awkernel_async_lib/src/time_interval.rs +++ b/awkernel_async_lib/src/time_interval.rs @@ -29,6 +29,7 @@ //! SOFTWARE. use crate::sleep_task::Sleep; +#[cfg(feature = "need-get-period")] use crate::task::perf::{get_period_count, update_pre_send_outer_timestamp_at}; use alloc::boxed::Box; use awkernel_lib::time::Time; From 6585af5baafd2831f361e173b15d93eb0cd871f8 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 17 Apr 2026 17:22:24 +0900 Subject: [PATCH 28/60] fix: apply cargo fmt 3 Signed-off-by: nokosaaan --- awkernel_async_lib/src/dag.rs | 4 ++-- awkernel_async_lib/src/task.rs | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index a5a3e2085..f53dab0a3 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -71,8 +71,8 @@ use crate::{ #[cfg(feature = "need-get-period")] use crate::task::perf::{ get_period_count, increment_period_count, increment_pub_count, increment_sink_count, - increment_sub_count, publish_timestamp_at, subscribe_timestamp_at, - update_fin_recv_outer_timestamp_at, update_pre_send_outer_timestamp_at, + increment_sub_count, publish_timestamp_at, subscribe_timestamp_at, + update_fin_recv_outer_timestamp_at, update_pre_send_outer_timestamp_at, }; use alloc::{ diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index d1494b8b8..47c83c326 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -471,9 +471,9 @@ pub mod perf { use array_macro::array; use awkernel_lib::cpu::NUM_MAX_CPU; use core::ptr::{read_volatile, write_volatile}; - use core::sync::atomic::{Ordering, AtomicU32}; #[cfg(feature = "need-get-period")] use core::sync::atomic::AtomicBool; + use core::sync::atomic::{AtomicU32, Ordering}; #[derive(Debug, Clone, PartialEq, Eq)] #[repr(u8)] From bc19c6943fd0a0153cfa3103d179c79de237003a Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 17 Apr 2026 17:30:43 +0900 Subject: [PATCH 29/60] fix: delete unnecessary import Signed-off-by: nokosaaan --- awkernel_async_lib/src/task.rs | 2 -- 1 file changed, 2 deletions(-) diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index 47c83c326..6cae14695 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -471,8 +471,6 @@ pub mod perf { use array_macro::array; use awkernel_lib::cpu::NUM_MAX_CPU; use core::ptr::{read_volatile, write_volatile}; - #[cfg(feature = "need-get-period")] - use core::sync::atomic::AtomicBool; use core::sync::atomic::{AtomicU32, Ordering}; #[derive(Debug, Clone, PartialEq, Eq)] From adfa4fd998a8a6d76099ca38accaf9edb8310f76 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 17 Apr 2026 18:01:05 +0900 Subject: [PATCH 30/60] fix: delete unnecessary functions and modify kernel/src/main.rs Signed-off-by: nokosaaan --- awkernel_async_lib/src/dag.rs | 26 +--------- awkernel_async_lib/src/pubsub.rs | 2 - awkernel_async_lib/src/task.rs | 84 ++------------------------------ kernel/src/main.rs | 10 ++++ 4 files changed, 16 insertions(+), 106 deletions(-) diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index f53dab0a3..1dd40073c 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -70,8 +70,7 @@ use crate::{ #[cfg(feature = "need-get-period")] use crate::task::perf::{ - get_period_count, increment_period_count, increment_pub_count, increment_sink_count, - increment_sub_count, publish_timestamp_at, subscribe_timestamp_at, + publish_timestamp_at, subscribe_timestamp_at, update_fin_recv_outer_timestamp_at, update_pre_send_outer_timestamp_at, }; @@ -976,11 +975,6 @@ where let count_st = get_period(&args); subscribe_timestamp_at(count_st as usize, end, 1, dag_info.node_id.clone()); - // period count from message to TaskInfo - let cpu_id = awkernel_lib::cpu::cpu_id(); - if let Some(task_id) = crate::task::get_current_task(cpu_id) { - crate::task::set_task_period(task_id, Some(count_st)); - } let results = f(args); // [start] pubsub communication latency let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; @@ -1038,10 +1032,6 @@ where #[cfg(feature = "need-get-period")] { let index = get_period_count(dag_info.dag_id.clone() as usize) as usize; - let cpu_id = awkernel_lib::cpu::cpu_id(); - if let Some(task_id) = crate::task::get_current_task(cpu_id) { - crate::task::set_task_period(task_id, Some(index as u32)); - } if index != 0 { let release_time = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; update_pre_send_outer_timestamp_at( @@ -1057,9 +1047,6 @@ where publishers .send_all_with_meta(results, 0, index, dag_info.node_id) .await; - - increment_period_count(dag_info.dag_id.clone() as usize); - increment_pub_count(0); } #[cfg(not(feature = "need-get-period"))] @@ -1109,20 +1096,11 @@ where let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; let count_st = get_period(&args); subscribe_timestamp_at(count_st as usize, end, 2, dag_info.node_id.clone()); - increment_pub_count(1); - increment_sub_count(1); - increment_sub_count(2); - - // period count from message to TaskInfo - let cpu_id = awkernel_lib::cpu::cpu_id(); - if let Some(task_id) = crate::task::get_current_task(cpu_id) { - crate::task::set_task_period(task_id, Some(count_st)); - } + let timenow = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; if count_st != 0 { update_fin_recv_outer_timestamp_at(count_st as usize, timenow, dag_info.dag_id); } - increment_sink_count(dag_info.dag_id.clone() as usize); } f(args); diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index 55c3bccad..2ea5b6907 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -393,14 +393,12 @@ where let sender = Sender::new(self, data); sender.await; - r#yield().await; } pub async fn send(&self, data: T) { let sender = Sender::new(self, data); sender.await; - r#yield().await; } } diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index 6cae14695..f335ab654 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -158,7 +158,6 @@ pub struct TaskInfo { pub(crate) need_preemption: bool, panicked: bool, pub(crate) dag_info: Option, - pub(crate) current_period: Option, #[cfg(not(feature = "no_preempt"))] thread: Option, @@ -226,16 +225,6 @@ impl TaskInfo { pub fn get_dag_info(&self) -> Option { self.dag_info.clone() } - - #[inline(always)] - pub fn set_current_period(&mut self, p: Option) { - self.current_period = p; - } - - #[inline(always)] - pub fn get_current_period(&self) -> Option { - self.current_period - } } /// State of task. @@ -297,7 +286,6 @@ impl Tasks { need_preemption: false, panicked: false, dag_info, - current_period: None, #[cfg(not(feature = "no_preempt"))] thread: None, @@ -468,10 +456,8 @@ fn get_next_task(execution_ensured: bool) -> Option> { pub mod perf { use crate::task::{self}; use alloc::string::{String, ToString}; - use array_macro::array; use awkernel_lib::cpu::NUM_MAX_CPU; use core::ptr::{read_volatile, write_volatile}; - use core::sync::atomic::{AtomicU32, Ordering}; #[derive(Debug, Clone, PartialEq, Eq)] #[repr(u8)] @@ -544,8 +530,6 @@ pub mod perf { //DAG+1 const MAX_DAGS: usize = 4; - pub static PERIOD_COUNT: [AtomicU32; MAX_DAGS] = array![_ => AtomicU32::new(0); MAX_DAGS]; - pub static SINK_COUNT: [AtomicU32; MAX_DAGS] = array![_ => AtomicU32::new(0); MAX_DAGS]; const MAX_NODES: usize = 20; static NODE_START: Mutex> = Mutex::new(None); @@ -557,48 +541,6 @@ pub mod perf { const MAX_PUBSUB: usize = 3; static PUBLISH: Mutex> = Mutex::new(None); static SUBSCRIBE: Mutex> = Mutex::new(None); - pub static PUB_COUNT: [AtomicU32; MAX_PUBSUB] = array![_ => AtomicU32::new(0); MAX_PUBSUB]; - pub static SUB_COUNT: [AtomicU32; MAX_PUBSUB] = array![_ => AtomicU32::new(0); MAX_PUBSUB]; - - pub fn increment_pub_count(pub_id: usize) { - assert!(pub_id < MAX_PUBSUB, "Pub ID out of bounds"); - PUB_COUNT[pub_id].fetch_add(1, Ordering::Relaxed); - } - - pub fn increment_sub_count(sub_id: usize) { - assert!(sub_id < MAX_PUBSUB, "Sub ID out of bounds"); - SUB_COUNT[sub_id].fetch_add(1, Ordering::Relaxed); - } - - pub fn get_pub_count(pub_id: usize) -> u32 { - assert!(pub_id < MAX_PUBSUB, "Pub ID out of bounds"); - PUB_COUNT[pub_id].load(Ordering::Relaxed) - } - - pub fn get_sub_count(sub_id: usize) -> u32 { - assert!(sub_id < MAX_PUBSUB, "Sub ID out of bounds"); - SUB_COUNT[sub_id].load(Ordering::Relaxed) - } - - pub fn increment_period_count(dag_id: usize) { - assert!(dag_id < MAX_DAGS, "DAG ID out of bounds"); - PERIOD_COUNT[dag_id].fetch_add(1, Ordering::Relaxed); - } - - pub fn get_period_count(dag_id: usize) -> u32 { - assert!(dag_id < MAX_DAGS, "DAG ID out of bounds"); - PERIOD_COUNT[dag_id].load(Ordering::Relaxed) - } - - pub fn increment_sink_count(dag_id: usize) { - assert!(dag_id < MAX_DAGS, "DAG ID out of bounds"); - SINK_COUNT[dag_id].fetch_add(1, Ordering::Relaxed); - } - - pub fn get_sink_count(dag_id: usize) -> u32 { - assert!(dag_id < MAX_DAGS, "DAG ID out of bounds"); - SINK_COUNT[dag_id].load(Ordering::Relaxed) - } pub fn update_pre_send_outer_timestamp_at(index: usize, new_timestamp: u64, dag_id: u32) { assert!(index < MAX_LOGS, "Timestamp index out of bounds"); @@ -653,7 +595,7 @@ pub mod perf { } pub fn node_start(node: NodeRecord, start: u64) { - // assert!(index < MAX_LOGS, "Node log index out of bounds"); + assert!(index < MAX_LOGS, "Node log index out of bounds"); assert!( (node.dag_info.node_id as usize) < MAX_NODES, "Node ID out of bounds" @@ -670,7 +612,7 @@ pub mod perf { } pub fn node_finish(node: NodeRecord, finish: u64) { - // assert!(index < MAX_LOGS, "Node log index out of bounds"); + assert!(index < MAX_LOGS, "Node log index out of bounds"); assert!( (node.dag_info.node_id as usize) < MAX_NODES, "Node ID out of bounds" @@ -687,7 +629,7 @@ pub mod perf { } pub fn node_preempt(node: NodeRecord) { - // assert!(index < MAX_LOGS, "Node log index out of bounds"); + assert!(index < MAX_LOGS, "Node log index out of bounds"); assert!( (node.dag_info.node_id as usize) < MAX_NODES, "Node ID out of bounds" @@ -702,7 +644,7 @@ pub mod perf { } pub fn dag_preempt(node: NodeRecord) { - // assert!(index < MAX_LOGS, "Node log index out of bounds"); + assert!(index < MAX_LOGS, "Node log index out of bounds"); assert!( (node.dag_info.dag_id as usize) < MAX_DAGS, "DAG ID out of bounds" @@ -1566,24 +1508,6 @@ pub fn get_scheduler_type_by_task_id(task_id: u32) -> Option { }) } -pub fn set_task_period(task_id: u32, period: Option) { - if let Some(task) = get_task(task_id) { - let mut node = MCSNode::new(); - let mut info = task.info.lock(&mut node); - info.set_current_period(period); - } -} - -pub fn get_task_period(task_id: u32) -> Option { - if let Some(task) = get_task(task_id) { - let mut node = MCSNode::new(); - let info = task.info.lock(&mut node); - info.get_current_period() - } else { - None - } -} - #[inline(always)] pub fn set_need_preemption(task_id: u32, cpu_id: usize) { let mut node = MCSNode::new(); diff --git a/kernel/src/main.rs b/kernel/src/main.rs index 5d02b2aa0..895d3e803 100644 --- a/kernel/src/main.rs +++ b/kernel/src/main.rs @@ -74,7 +74,17 @@ fn main(kernel_info: KernelInfo) { // Enable awkernel_lib::cpu::sleep_cpu() and awkernel_lib::cpu::wakeup_cpu(). unsafe { awkernel_lib::cpu::init_sleep() }; + let mut last_print = awkernel_lib::time::Time::now(); + loop { + if last_print.elapsed().as_secs() >= 40 { + #[cfg(feature = "perf")] + awkernel_async_lib::task::perf::print_timestamp_table(); + // awkernel_async_lib::task::perf::print_node_table(); + // awkernel_async_lib::task::perf::print_pubsub_table(); + + last_print = awkernel_lib::time::Time::now(); + } // handle IRQs { let _irq_enable = awkernel_lib::interrupt::InterruptEnable::new(); From 377d1b15d889198ccafd7a77f051fb9d147cfd52 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 17 Apr 2026 19:13:23 +0900 Subject: [PATCH 31/60] fix: add get_period_count for getting periodic period Signed-off-by: nokosaaan --- awkernel_async_lib/Cargo.toml | 2 +- awkernel_async_lib/src/dag.rs | 3 ++- awkernel_async_lib/src/task.rs | 17 +++++++++++++---- kernel/src/main.rs | 10 ++++++---- 4 files changed, 22 insertions(+), 10 deletions(-) diff --git a/awkernel_async_lib/Cargo.toml b/awkernel_async_lib/Cargo.toml index 961ed2ad7..37f9923d0 100644 --- a/awkernel_async_lib/Cargo.toml +++ b/awkernel_async_lib/Cargo.toml @@ -39,7 +39,7 @@ default-features = false features = ["awkernel"] [features] -default = [] +default = ["need-get-period"] std = ["awkernel_lib/std", "no_preempt"] no_preempt = [] spinlock = ["awkernel_lib/spinlock"] diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index 1dd40073c..90aa3a1be 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -70,7 +70,7 @@ use crate::{ #[cfg(feature = "need-get-period")] use crate::task::perf::{ - publish_timestamp_at, subscribe_timestamp_at, + get_period_count, increment_period_count,publish_timestamp_at, subscribe_timestamp_at, update_fin_recv_outer_timestamp_at, update_pre_send_outer_timestamp_at, }; @@ -1047,6 +1047,7 @@ where publishers .send_all_with_meta(results, 0, index, dag_info.node_id) .await; + increment_period_count(dag_info.dag_id.clone() as usize); } #[cfg(not(feature = "need-get-period"))] diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index f335ab654..a0a138c22 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -458,6 +458,8 @@ pub mod perf { use alloc::string::{String, ToString}; use awkernel_lib::cpu::NUM_MAX_CPU; use core::ptr::{read_volatile, write_volatile}; + use core::sync::atomic::{AtomicU32, Ordering}; + use array_macro::array; #[derive(Debug, Clone, PartialEq, Eq)] #[repr(u8)] @@ -530,6 +532,7 @@ pub mod perf { //DAG+1 const MAX_DAGS: usize = 4; + pub static PERIOD_COUNT: [AtomicU32; MAX_DAGS] = array![_ => AtomicU32::new(0); MAX_DAGS]; const MAX_NODES: usize = 20; static NODE_START: Mutex> = Mutex::new(None); @@ -542,6 +545,16 @@ pub mod perf { static PUBLISH: Mutex> = Mutex::new(None); static SUBSCRIBE: Mutex> = Mutex::new(None); + pub fn increment_period_count(dag_id: usize) { + assert!(dag_id < MAX_DAGS, "DAG ID out of bounds"); + PERIOD_COUNT[dag_id].fetch_add(1, Ordering::Relaxed); + } + + pub fn get_period_count(dag_id: usize) -> u32 { + assert!(dag_id < MAX_DAGS, "DAG ID out of bounds"); + PERIOD_COUNT[dag_id].load(Ordering::Relaxed) + } + pub fn update_pre_send_outer_timestamp_at(index: usize, new_timestamp: u64, dag_id: u32) { assert!(index < MAX_LOGS, "Timestamp index out of bounds"); @@ -595,7 +608,6 @@ pub mod perf { } pub fn node_start(node: NodeRecord, start: u64) { - assert!(index < MAX_LOGS, "Node log index out of bounds"); assert!( (node.dag_info.node_id as usize) < MAX_NODES, "Node ID out of bounds" @@ -612,7 +624,6 @@ pub mod perf { } pub fn node_finish(node: NodeRecord, finish: u64) { - assert!(index < MAX_LOGS, "Node log index out of bounds"); assert!( (node.dag_info.node_id as usize) < MAX_NODES, "Node ID out of bounds" @@ -629,7 +640,6 @@ pub mod perf { } pub fn node_preempt(node: NodeRecord) { - assert!(index < MAX_LOGS, "Node log index out of bounds"); assert!( (node.dag_info.node_id as usize) < MAX_NODES, "Node ID out of bounds" @@ -644,7 +654,6 @@ pub mod perf { } pub fn dag_preempt(node: NodeRecord) { - assert!(index < MAX_LOGS, "Node log index out of bounds"); assert!( (node.dag_info.dag_id as usize) < MAX_DAGS, "DAG ID out of bounds" diff --git a/kernel/src/main.rs b/kernel/src/main.rs index 895d3e803..7f17cbc18 100644 --- a/kernel/src/main.rs +++ b/kernel/src/main.rs @@ -79,10 +79,12 @@ fn main(kernel_info: KernelInfo) { loop { if last_print.elapsed().as_secs() >= 40 { #[cfg(feature = "perf")] - awkernel_async_lib::task::perf::print_timestamp_table(); - // awkernel_async_lib::task::perf::print_node_table(); - // awkernel_async_lib::task::perf::print_pubsub_table(); - + { + awkernel_async_lib::task::perf::print_timestamp_table(); + // awkernel_async_lib::task::perf::print_node_table(); + // awkernel_async_lib::task::perf::print_pubsub_table(); + } + last_print = awkernel_lib::time::Time::now(); } // handle IRQs From ddd69c2f67c9c0908f3c7ebb47cddeea5a6299ca Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 17 Apr 2026 19:17:06 +0900 Subject: [PATCH 32/60] fix: async_lib/Cargo.toml Signed-off-by: nokosaaan --- awkernel_async_lib/Cargo.toml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/awkernel_async_lib/Cargo.toml b/awkernel_async_lib/Cargo.toml index 37f9923d0..961ed2ad7 100644 --- a/awkernel_async_lib/Cargo.toml +++ b/awkernel_async_lib/Cargo.toml @@ -39,7 +39,7 @@ default-features = false features = ["awkernel"] [features] -default = ["need-get-period"] +default = [] std = ["awkernel_lib/std", "no_preempt"] no_preempt = [] spinlock = ["awkernel_lib/spinlock"] From 37cae777876fa70ce0111d2d6b729ef4a255c9bf Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 17 Apr 2026 19:18:27 +0900 Subject: [PATCH 33/60] fix: apply cargo fmt 4 Signed-off-by: nokosaaan --- awkernel_async_lib/src/dag.rs | 2 +- awkernel_async_lib/src/task.rs | 2 +- kernel/src/main.rs | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index 90aa3a1be..1f6cab477 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -70,7 +70,7 @@ use crate::{ #[cfg(feature = "need-get-period")] use crate::task::perf::{ - get_period_count, increment_period_count,publish_timestamp_at, subscribe_timestamp_at, + get_period_count, increment_period_count, publish_timestamp_at, subscribe_timestamp_at, update_fin_recv_outer_timestamp_at, update_pre_send_outer_timestamp_at, }; diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index a0a138c22..faadc2640 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -456,10 +456,10 @@ fn get_next_task(execution_ensured: bool) -> Option> { pub mod perf { use crate::task::{self}; use alloc::string::{String, ToString}; + use array_macro::array; use awkernel_lib::cpu::NUM_MAX_CPU; use core::ptr::{read_volatile, write_volatile}; use core::sync::atomic::{AtomicU32, Ordering}; - use array_macro::array; #[derive(Debug, Clone, PartialEq, Eq)] #[repr(u8)] diff --git a/kernel/src/main.rs b/kernel/src/main.rs index 7f17cbc18..21fb03518 100644 --- a/kernel/src/main.rs +++ b/kernel/src/main.rs @@ -84,7 +84,7 @@ fn main(kernel_info: KernelInfo) { // awkernel_async_lib::task::perf::print_node_table(); // awkernel_async_lib::task::perf::print_pubsub_table(); } - + last_print = awkernel_lib::time::Time::now(); } // handle IRQs From 3ff0804a0dba7a82500a2ce587aca697ff479b31 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 17 Apr 2026 19:39:56 +0900 Subject: [PATCH 34/60] fix: delete NodeRecord Signed-off-by: nokosaaan --- awkernel_async_lib/src/task.rs | 146 +-------------------------------- kernel/src/main.rs | 3 +- 2 files changed, 5 insertions(+), 144 deletions(-) diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index faadc2640..a05632324 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -487,11 +487,6 @@ pub mod perf { } } } - #[derive(Debug, Clone)] - pub struct NodeRecord { - pub period_count: u32, - pub dag_info: task::DagInfo, - } static mut PERF_STATES: [u8; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; @@ -528,20 +523,14 @@ pub mod perf { static RECV_OUTER_TIMESTAMP: Mutex> = Mutex::new(None); static ABSOLUTE_DEADLINE: Mutex> = Mutex::new(None); static RELATIVE_DEADLINE: Mutex> = Mutex::new(None); - static DAG_PREEMPT_COUNT: Mutex> = Mutex::new(None); //DAG+1 const MAX_DAGS: usize = 4; pub static PERIOD_COUNT: [AtomicU32; MAX_DAGS] = array![_ => AtomicU32::new(0); MAX_DAGS]; - const MAX_NODES: usize = 20; - static NODE_START: Mutex> = Mutex::new(None); - static NODE_FINISH: Mutex> = Mutex::new(None); - static NODE_PREEMPT_COUNT: Mutex> = Mutex::new(None); - static NODE_CORE: Mutex> = Mutex::new(None); - //pubsub const MAX_PUBSUB: usize = 3; + const MAX_NODES: usize = 20; static PUBLISH: Mutex> = Mutex::new(None); static SUBSCRIBE: Mutex> = Mutex::new(None); @@ -607,66 +596,6 @@ pub mod perf { } } - pub fn node_start(node: NodeRecord, start: u64) { - assert!( - (node.dag_info.node_id as usize) < MAX_NODES, - "Node ID out of bounds" - ); - - let mut mcs_node = MCSNode::new(); - let mut recorder_opt = NODE_START.lock(&mut mcs_node); - - let recorder = recorder_opt.get_or_insert_with(|| [[0; MAX_NODES]; MAX_LOGS]); - - if recorder[node.period_count as usize][node.dag_info.node_id as usize] == 0 { - recorder[node.period_count as usize][node.dag_info.node_id as usize] = start; - } - } - - pub fn node_finish(node: NodeRecord, finish: u64) { - assert!( - (node.dag_info.node_id as usize) < MAX_NODES, - "Node ID out of bounds" - ); - - let mut mcs_node = MCSNode::new(); - let mut recorder_opt = NODE_FINISH.lock(&mut mcs_node); - - let recorder = recorder_opt.get_or_insert_with(|| [[0; MAX_NODES]; MAX_LOGS]); - - if recorder[node.period_count as usize][node.dag_info.node_id as usize] == 0 { - recorder[node.period_count as usize][node.dag_info.node_id as usize] = finish; - } - } - - pub fn node_preempt(node: NodeRecord) { - assert!( - (node.dag_info.node_id as usize) < MAX_NODES, - "Node ID out of bounds" - ); - - let mut mcs_node = MCSNode::new(); - let mut recorder_opt = NODE_PREEMPT_COUNT.lock(&mut mcs_node); - - let recorder = recorder_opt.get_or_insert_with(|| [[0; MAX_NODES]; MAX_LOGS]); - - recorder[node.period_count as usize][node.dag_info.node_id as usize] += 1; - } - - pub fn dag_preempt(node: NodeRecord) { - assert!( - (node.dag_info.dag_id as usize) < MAX_DAGS, - "DAG ID out of bounds" - ); - - let mut mcs_node = MCSNode::new(); - let mut recorder_opt = DAG_PREEMPT_COUNT.lock(&mut mcs_node); - - let recorder = recorder_opt.get_or_insert_with(|| [[0; MAX_DAGS]; MAX_LOGS]); - - recorder[node.period_count as usize][node.dag_info.dag_id as usize] += 1; - } - pub fn publish_timestamp_at(index: usize, new_timestamp: u64, pub_id: u32, node_id: u32) { assert!(index < MAX_LOGS, "Timestamp index out of bounds"); assert!((pub_id as usize) < MAX_PUBSUB, "Publish ID out of bounds"); @@ -701,25 +630,22 @@ pub mod perf { let mut node2 = MCSNode::new(); let mut node3 = MCSNode::new(); let mut node4 = MCSNode::new(); - let mut node5 = MCSNode::new(); let send_outer_opt = SEND_OUTER_TIMESTAMP.lock(&mut node1); let recv_outer_opt = RECV_OUTER_TIMESTAMP.lock(&mut node2); let absolute_deadline_opt = ABSOLUTE_DEADLINE.lock(&mut node3); let relative_deadline_opt = RELATIVE_DEADLINE.lock(&mut node4); - let dag_preempt_opt = DAG_PREEMPT_COUNT.lock(&mut node5); log::info!("--- Timestamp Summary (in nanoseconds) ---"); log::info!( - "{: ^5} | {: ^5} | {: ^14} | {: ^14} | {: ^14} | {: ^14} | {: ^14} | {: ^14}", + "{: ^5} | {: ^5} | {: ^14} | {: ^14} | {: ^14} | {: ^14} | {: ^14}", "Index", "DAG-ID", "Send-Outer", "Recv-Outer", "Latency", "Absolute Deadline", - "Relative Deadline", - "DAG Preemptions" + "Relative Deadline" ); log::info!("-----|--------|----------------|----------------|----------------|--------------------|--------------------|--------------------|--------------------"); @@ -730,13 +656,11 @@ pub mod perf { let fin_recv_outer = recv_outer_opt.as_ref().map_or(0, |arr| arr[i][j]); let absolute_deadline = absolute_deadline_opt.as_ref().map_or(0, |arr| arr[i][j]); let relative_deadline = relative_deadline_opt.as_ref().map_or(0, |arr| arr[i][j]); - let dag_preempt = dag_preempt_opt.as_ref().map_or(0, |arr| arr[i][j]); if pre_send_outer != 0 || fin_recv_outer != 0 || absolute_deadline != 0 || relative_deadline != 0 - || dag_preempt != 0 { let format_ts = |ts: u64| -> String { if ts == 0 { @@ -753,7 +677,7 @@ pub mod perf { }; log::info!( - "{: >5} | {: >5} | {: >14} | {: >14} | {: >14} | {: >20} | {: >20} | {: >20}", + "{: >5} | {: >5} | {: >14} | {: >14} | {: >14} | {: >20} | {: >20}", i, format_ts(j as u64), format_ts(pre_send_outer), @@ -761,7 +685,6 @@ pub mod perf { latency_str, format_ts(absolute_deadline), format_ts(relative_deadline), - format_ts(dag_preempt as u64), ); } } @@ -769,67 +692,6 @@ pub mod perf { log::info!("----------------------------------------------------------"); } - /// Print per-node timing table. - /// Columns: DAG ID | node id | period | start(ns) | end(ns) | duration(ns) | preemptions | core - /// not used now - pub fn print_node_table() { - let mut node1 = MCSNode::new(); - let mut node2 = MCSNode::new(); - let mut node3 = MCSNode::new(); - let mut node4 = MCSNode::new(); - - let node_start_opt = NODE_START.lock(&mut node1); - let node_finish_opt = NODE_FINISH.lock(&mut node2); - let node_preempt_opt = NODE_PREEMPT_COUNT.lock(&mut node3); - let node_core_opt = NODE_CORE.lock(&mut node4); - - log::info!("--- Per-node Timing Summary (in nanoseconds) ---"); - log::info!( - "{:<5} | {:<6} | {:<7} | {:<20} | {:<20} | {:<20} | {:<12} | {:<4}", - "Index", - "DAG-ID", - "NODE-ID", - "start(ns)", - "end(ns)", - "duration(ns)", - "preemptions", - "core" - ); - log::info!("------|--------|---------|----------------------|----------------------|----------------------|-----"); - - for i in 0..MAX_LOGS { - for j in 0..MAX_NODES { - let start = node_start_opt.as_ref().map_or(0, |arr| arr[i][j]); - let finish = node_finish_opt.as_ref().map_or(0, |arr| arr[i][j]); - let preempt_count = node_preempt_opt.as_ref().map_or(0, |arr| arr[i][j]); - let core_id = node_core_opt.as_ref().map_or(0, |arr| arr[i][j]); - - if start != 0 || finish != 0 || preempt_count != 0 { - let format_ts = |ts: u64| -> String { ts.to_string() }; - - let duration = if start != 0 && finish != 0 { - finish.saturating_sub(start).to_string() - } else { - "-".to_string() - }; - - log::info!( - "{:<5} | {:<6} | {:<7} | {:<20} | {:<20} | {:<20} | {:<12} | {:<4}", - i, - 1, // DAG ID (assumed 1 for simplicity) - format_ts(j as u64), - format_ts(start), - format_ts(finish), - duration, - format_ts(preempt_count as u64), - format_ts(core_id as u64), - ); - } - } - } - log::info!("--------------------------------------------------------------"); - } - // For pubsub communication latency pub fn print_pubsub_table() { let mut node1 = MCSNode::new(); diff --git a/kernel/src/main.rs b/kernel/src/main.rs index 21fb03518..c9ddb1e4c 100644 --- a/kernel/src/main.rs +++ b/kernel/src/main.rs @@ -77,11 +77,10 @@ fn main(kernel_info: KernelInfo) { let mut last_print = awkernel_lib::time::Time::now(); loop { - if last_print.elapsed().as_secs() >= 40 { + if last_print.elapsed().as_secs() >= 30 { #[cfg(feature = "perf")] { awkernel_async_lib::task::perf::print_timestamp_table(); - // awkernel_async_lib::task::perf::print_node_table(); // awkernel_async_lib::task::perf::print_pubsub_table(); } From d8e28cd5fc2a6fa3b6a094a1f5f0b622964c202e Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 17 Apr 2026 19:48:15 +0900 Subject: [PATCH 35/60] fix: unify start publish_timestamp_at to pubsub.rs Signed-off-by: nokosaaan --- awkernel_async_lib/src/dag.rs | 6 ------ awkernel_async_lib/src/pubsub.rs | 1 + 2 files changed, 1 insertion(+), 6 deletions(-) diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index 1f6cab477..937914d4d 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -976,9 +976,6 @@ where subscribe_timestamp_at(count_st as usize, end, 1, dag_info.node_id.clone()); let results = f(args); - // [start] pubsub communication latency - let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - publish_timestamp_at(count_st as usize, end, 1, dag_info.node_id.clone()); publishers .send_all_with_meta(results, 1, count_st as usize, dag_info.node_id) .await; @@ -1041,9 +1038,6 @@ where ); } let results = f(); - // [start] pubsub communication latency - let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - publish_timestamp_at(index, end, 0, dag_info.node_id); publishers .send_all_with_meta(results, 0, index, dag_info.node_id) .await; diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index 2ea5b6907..bd788f22b 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -387,6 +387,7 @@ where pub async fn send_with_meta(&self, data: T, _pub_id: u32, _index: usize, _node_id: u32) { #[cfg(feature = "need-get-period")] { + // [start] pubsub communication latency let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; publish_timestamp_at(_index, start, _pub_id, _node_id); } From 2de13a9c4966ac89603a3fc6cbc4cfe0da49ca45 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 17 Apr 2026 19:50:19 +0900 Subject: [PATCH 36/60] fix: delete unused imports Signed-off-by: nokosaaan --- awkernel_async_lib/src/dag.rs | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index 937914d4d..284e53e7e 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -70,7 +70,7 @@ use crate::{ #[cfg(feature = "need-get-period")] use crate::task::perf::{ - get_period_count, increment_period_count, publish_timestamp_at, subscribe_timestamp_at, + get_period_count, increment_period_count, subscribe_timestamp_at, update_fin_recv_outer_timestamp_at, update_pre_send_outer_timestamp_at, }; From 9a9d2dae3730248e1c36384f5848df7055b6fba9 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 17 Apr 2026 19:55:54 +0900 Subject: [PATCH 37/60] fix: add dependics in kernel/Cargo.toml for print_timestamp_table Signed-off-by: nokosaaan --- kernel/Cargo.toml | 1 + kernel/src/main.rs | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/kernel/Cargo.toml b/kernel/Cargo.toml index 942920387..9d0b86276 100644 --- a/kernel/Cargo.toml +++ b/kernel/Cargo.toml @@ -78,6 +78,7 @@ optional = true [features] default = ["x86"] perf = ["awkernel_async_lib/perf", "userland/perf"] +need-get-period = ["awkernel_async_lib/need-get-period"] no_std_unwinding = ["dep:unwinding"] debug = ["dep:gimli", "dep:addr2line"] x86 = [ diff --git a/kernel/src/main.rs b/kernel/src/main.rs index c9ddb1e4c..15daa23d4 100644 --- a/kernel/src/main.rs +++ b/kernel/src/main.rs @@ -78,7 +78,7 @@ fn main(kernel_info: KernelInfo) { loop { if last_print.elapsed().as_secs() >= 30 { - #[cfg(feature = "perf")] + #[cfg(feature = "need-get-period")] { awkernel_async_lib::task::perf::print_timestamp_table(); // awkernel_async_lib::task::perf::print_pubsub_table(); From 14f92ca3f89aac42078d0d2bf4f2df0beee1621d Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Fri, 17 Apr 2026 21:31:21 +0900 Subject: [PATCH 38/60] fix: clarify the responsibility between send_all and send_all_with_meta with features Signed-off-by: nokosaaan --- awkernel_async_lib/src/dag.rs | 11 ++++++----- awkernel_async_lib/src/pubsub.rs | 6 ++++++ 2 files changed, 12 insertions(+), 5 deletions(-) diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index 284e53e7e..8018356ea 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -133,17 +133,18 @@ impl_tuple_traits!(0 => T1); impl_tuple_traits!(1 => T1, T2); impl_tuple_traits!(2 => T1, T2, T3); +#[cfg(not(feature = "need-get-period"))] +pub trait DagSubscriberItem: TupleSize + Send {} + +#[cfg(not(feature = "need-get-period"))] +impl DagSubscriberItem for T where T: TupleSize + Send {} + #[cfg(feature = "need-get-period")] pub trait DagSubscriberItem: TupleSize + GetPeriod + Send {} #[cfg(feature = "need-get-period")] impl DagSubscriberItem for T where T: TupleSize + GetPeriod + Send {} -#[cfg(not(feature = "need-get-period"))] -pub trait DagSubscriberItem: TupleSize + Send {} - -#[cfg(not(feature = "need-get-period"))] -impl DagSubscriberItem for T where T: TupleSize + Send {} #[cfg(feature = "need-get-period")] pub fn get_period(args: &T) -> u32 { args.get_period() diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index bd788f22b..4077212ff 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -777,8 +777,10 @@ pub trait MultipleReceiver { pub trait MultipleSender { type Item; + #[cfg(not(feature = "need-get-period"))] fn send_all(&self, item: Self::Item) -> Pin + Send + '_>>; + #[cfg(feature = "need-get-period")] fn send_all_with_meta( &self, item: Self::Item, @@ -863,9 +865,11 @@ macro_rules! impl_async_receiver_for_tuple { impl MultipleSender for () { type Item = (); + #[cfg(not(feature = "need-get-period"))] fn send_all(&self, _item: Self::Item) -> Pin + Send + '_>> { Box::pin(async move{}) } + #[cfg(feature = "need-get-period")] fn send_all_with_meta(&self, _item: Self::Item, _pub_id: u32, _index: usize, _node_id: u32) -> Pin + Send + '_>> { Box::pin(async move{}) } @@ -886,6 +890,7 @@ macro_rules! impl_async_receiver_for_tuple { impl<$($T: Clone + Sync + Send + 'static),+> MultipleSender for ($(Publisher<$T>,)+) { type Item = ($($T,)+); + #[cfg(not(feature = "need-get-period"))] fn send_all(&self, item: Self::Item) -> Pin + Send + '_>> { let ($($idx,)+) = self; let ($($idx2,)+) = item; @@ -896,6 +901,7 @@ macro_rules! impl_async_receiver_for_tuple { }) } + #[cfg(feature = "need-get-period")] fn send_all_with_meta(&self, item: Self::Item, pub_id: u32, index: usize, node_id: u32) -> Pin + Send + '_>> { let ($($idx,)+) = self; let ($($idx2,)+) = item; From 968c05859f12f0ac9e0334b2facc0a6f038320df Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Sat, 18 Apr 2026 01:17:05 +0900 Subject: [PATCH 39/60] fix: delete get_period and the logic for passing periodic information has been internalized and solve bootloader error changing const numbers by using Box Signed-off-by: nokosaaan --- awkernel_async_lib/src/dag.rs | 94 ++++++------- awkernel_async_lib/src/pubsub.rs | 78 +++++++++-- awkernel_async_lib/src/task.rs | 178 ++++++++++++++++++------ awkernel_async_lib/src/time_interval.rs | 1 + 4 files changed, 240 insertions(+), 111 deletions(-) diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index 8018356ea..396fa656b 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -103,52 +103,21 @@ pub trait TupleSize { const SIZE: usize; } -pub trait GetPeriod { - fn get_period(&self) -> u32; -} - -macro_rules! impl_tuple_traits { - () => { - impl TupleSize for () { - const SIZE: usize = 0; - } - }; +macro_rules! impl_tuple_size { + (@count) => { 0 }; + (@count $_head:ident $($tail:ident)*) => { 1 + impl_tuple_size!(@count $($tail)*) }; - ($last_idx:tt => $($T:ident),+) => { - impl<$($T),+> TupleSize for ($($T,)+) { - const SIZE: usize = $last_idx + 1; - } - - #[cfg(feature = "need-get-period")] - impl<$($T),+> GetPeriod for ($(($T, u32),)+) { - fn get_period(&self) -> u32 { - self.$last_idx .1 - } + ($($T:ident),*) => { + impl<$($T),*> TupleSize for ($($T,)*) { + const SIZE: usize = impl_tuple_size!(@count $($T)*); } }; } -impl_tuple_traits!(); -impl_tuple_traits!(0 => T1); -impl_tuple_traits!(1 => T1, T2); -impl_tuple_traits!(2 => T1, T2, T3); - -#[cfg(not(feature = "need-get-period"))] -pub trait DagSubscriberItem: TupleSize + Send {} - -#[cfg(not(feature = "need-get-period"))] -impl DagSubscriberItem for T where T: TupleSize + Send {} - -#[cfg(feature = "need-get-period")] -pub trait DagSubscriberItem: TupleSize + GetPeriod + Send {} - -#[cfg(feature = "need-get-period")] -impl DagSubscriberItem for T where T: TupleSize + GetPeriod + Send {} - -#[cfg(feature = "need-get-period")] -pub fn get_period(args: &T) -> u32 { - args.get_period() -} +impl_tuple_size!(); +impl_tuple_size!(T1); +impl_tuple_size!(T1, T2); +impl_tuple_size!(T1, T2, T3); #[derive(Clone)] pub enum DagError { @@ -336,8 +305,8 @@ impl Dag { Ret: VectorToPublishers, Ret::Publishers: Send, Args::Subscribers: Send, - ::Item: DagSubscriberItem, - ::Item: TupleSize + Send, + ::Item: TupleSize, + ::Item: TupleSize, { let node_idx = self.add_node_with_topic_edges(&subscribe_topic_names, &publish_topic_names); self.check_subscribe_mismatch::(&subscribe_topic_names, node_idx); @@ -430,7 +399,7 @@ impl Dag { F: Fn(::Item) + Send + 'static, Args: VectorToSubscribers, Args::Subscribers: Send, - ::Item: DagSubscriberItem, + ::Item: TupleSize, { let node_idx = self.add_node_with_topic_edges(&subscribe_topic_names, &Vec::new()); self.set_relative_deadline(node_idx, relative_deadline); @@ -953,8 +922,8 @@ where Ret: VectorToPublishers, Ret::Publishers: Send, Args::Subscribers: Send, - ::Item: DagSubscriberItem, - ::Item: TupleSize + Send, + ::Item: TupleSize, + ::Item: TupleSize, { let future = async move { let publishers = ::create_publishers( @@ -966,14 +935,15 @@ where Args::create_subscribers(subscribe_topic_names, Attribute::default()); loop { - let args: <::Subscribers as MultipleReceiver>::Item = - subscribers.recv_all().await; - #[cfg(feature = "need-get-period")] { + let (args, count_st): ( + <::Subscribers as MultipleReceiver>::Item, + u32, + ) = subscribers.recv_all_with_period().await; + // [end] pubsub communication latency let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - let count_st = get_period(&args); subscribe_timestamp_at(count_st as usize, end, 1, dag_info.node_id.clone()); let results = f(args); @@ -981,8 +951,12 @@ where .send_all_with_meta(results, 1, count_st as usize, dag_info.node_id) .await; } + #[cfg(not(feature = "need-get-period"))] { + let args: <::Subscribers as MultipleReceiver>::Item = + subscribers.recv_all().await; + let results = f(args); publishers.send_all(results).await; } @@ -1031,6 +1005,7 @@ where { let index = get_period_count(dag_info.dag_id.clone() as usize) as usize; if index != 0 { + // [start] cycle deviation index >= 1 let release_time = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; update_pre_send_outer_timestamp_at( index, @@ -1077,29 +1052,38 @@ where F: Fn(::Item) + Send + 'static, Args: VectorToSubscribers, Args::Subscribers: Send, - ::Item: DagSubscriberItem, + ::Item: TupleSize, { let future = async move { let subscribers: ::Subscribers = Args::create_subscribers(subscribe_topic_names, Attribute::default()); loop { - let args: ::Item = subscribers.recv_all().await; - #[cfg(feature = "need-get-period")] { + let (args, count_st): ( + ::Item, + u32, + ) = subscribers.recv_all_with_period().await; + // [end] pubsub communication latency let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - let count_st = get_period(&args); subscribe_timestamp_at(count_st as usize, end, 2, dag_info.node_id.clone()); let timenow = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; if count_st != 0 { update_fin_recv_outer_timestamp_at(count_st as usize, timenow, dag_info.dag_id); } + + f(args); } - f(args); + #[cfg(not(feature = "need-get-period"))] + { + let args: ::Item = + subscribers.recv_all().await; + f(args); + } } }; diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index 4077212ff..57fbd2946 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -60,6 +60,8 @@ use crate::task::perf::publish_timestamp_at; pub struct Data { pub timestamp: awkernel_lib::time::Time, pub data: T, + #[cfg(feature = "need-get-period")] + pub index: u32, } /// Publisher. @@ -263,6 +265,8 @@ struct Sender<'a, T: 'static + Send> { subscribers: VecDeque>, state: SenderState, timestamp: awkernel_lib::time::Time, + #[cfg(feature = "need-get-period")] + index: u32, } enum SenderState { @@ -279,8 +283,16 @@ impl<'a, T: Send> Sender<'a, T> { subscribers: Default::default(), state: SenderState::Start, timestamp: awkernel_lib::time::Time::now(), + #[cfg(feature = "need-get-period")] + index: 0, } } + + #[cfg(feature = "need-get-period")] + pub(super) fn with_period(mut self, index: u32) -> Self { + self.index = index; + self + } } impl Future for Sender<'_, T> @@ -312,6 +324,8 @@ where if let Err(data) = guard.push(Data { timestamp: awkernel_lib::time::Time::now(), data: data.clone(), + #[cfg(feature = "need-get-period")] + index: *this.index, }) { // If the send buffer is full, then remove the oldest one and store again. guard.pop(); @@ -345,6 +359,8 @@ where match inner.queue.push(Data { timestamp: *this.timestamp, data: data.clone(), + #[cfg(feature = "need-get-period")] + index: *this.index, }) { Ok(_) => { // Wake the subscriber up. @@ -384,21 +400,18 @@ impl Publisher where T: Clone + Sync + Send, { - pub async fn send_with_meta(&self, data: T, _pub_id: u32, _index: usize, _node_id: u32) { - #[cfg(feature = "need-get-period")] - { - // [start] pubsub communication latency - let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - publish_timestamp_at(_index, start, _pub_id, _node_id); - } - + pub async fn send(&self, data: T) { let sender = Sender::new(self, data); sender.await; r#yield().await; } - pub async fn send(&self, data: T) { - let sender = Sender::new(self, data); + #[cfg(feature = "need-get-period")] + pub async fn send_with_meta(&self, data: T, pub_id: u32, index: usize, node_id: u32) { + // [start] pubsub communication latency + let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; + publish_timestamp_at(index, start, pub_id, node_id); + let sender = Sender::new(self, data).with_period(index as u32); sender.await; r#yield().await; } @@ -772,6 +785,11 @@ pub trait MultipleReceiver { type Item; fn recv_all(&self) -> Pin + Send + '_>>; + + #[cfg(feature = "need-get-period")] + fn recv_all_with_period( + &self, + ) -> Pin + Send + '_>>; } pub trait MultipleSender { @@ -860,6 +878,13 @@ macro_rules! impl_async_receiver_for_tuple { fn recv_all(&self) -> Pin + Send + '_>> { Box::pin(async move{}) } + + #[cfg(feature = "need-get-period")] + fn recv_all_with_period( + &self, + ) -> Pin + Send + '_>> { + Box::pin(async move { ((), 0) }) + } } impl MultipleSender for () { @@ -869,8 +894,15 @@ macro_rules! impl_async_receiver_for_tuple { fn send_all(&self, _item: Self::Item) -> Pin + Send + '_>> { Box::pin(async move{}) } + #[cfg(feature = "need-get-period")] - fn send_all_with_meta(&self, _item: Self::Item, _pub_id: u32, _index: usize, _node_id: u32) -> Pin + Send + '_>> { + fn send_all_with_meta( + &self, + _item: Self::Item, + _pub_id: u32, + _index: usize, + _node_id: u32, + ) -> Pin + Send + '_>> { Box::pin(async move{}) } } @@ -885,6 +917,22 @@ macro_rules! impl_async_receiver_for_tuple { ($($idx.recv().await.data,)+) }) } + + #[cfg(feature = "need-get-period")] + fn recv_all_with_period( + &self, + ) -> Pin + Send + '_>> { + let ($($idx,)+) = self; + Box::pin(async move { + let mut _period: u32 = 0; + $( + let item = $idx.recv().await; + _period = item.index; + let $idx2 = item.data; + )+ + (($($idx2,)+), _period) + }) + } } impl<$($T: Clone + Sync + Send + 'static),+> MultipleSender for ($(Publisher<$T>,)+) { @@ -902,7 +950,13 @@ macro_rules! impl_async_receiver_for_tuple { } #[cfg(feature = "need-get-period")] - fn send_all_with_meta(&self, item: Self::Item, pub_id: u32, index: usize, node_id: u32) -> Pin + Send + '_>> { + fn send_all_with_meta( + &self, + item: Self::Item, + pub_id: u32, + index: usize, + node_id: u32, + ) -> Pin + Send + '_>> { let ($($idx,)+) = self; let ($($idx2,)+) = item; Box::pin(async move { diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index a05632324..363202a70 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -455,6 +455,7 @@ fn get_next_task(execution_ensured: bool) -> Option> { #[cfg(feature = "perf")] pub mod perf { use crate::task::{self}; + use alloc::boxed::Box; use alloc::string::{String, ToString}; use array_macro::array; use awkernel_lib::cpu::NUM_MAX_CPU; @@ -517,12 +518,17 @@ pub mod perf { static mut PERF_COUNT: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; use awkernel_lib::sync::{mcs::MCSNode, mutex::Mutex}; + use alloc::vec::Vec; const MAX_LOGS: usize = 8192; - static SEND_OUTER_TIMESTAMP: Mutex> = Mutex::new(None); - static RECV_OUTER_TIMESTAMP: Mutex> = Mutex::new(None); - static ABSOLUTE_DEADLINE: Mutex> = Mutex::new(None); - static RELATIVE_DEADLINE: Mutex> = Mutex::new(None); + static SEND_OUTER_TIMESTAMP: Mutex>> = + Mutex::new(None); + static RECV_OUTER_TIMESTAMP: Mutex>> = + Mutex::new(None); + static ABSOLUTE_DEADLINE: Mutex>> = + Mutex::new(None); + static RELATIVE_DEADLINE: Mutex>> = + Mutex::new(None); //DAG+1 const MAX_DAGS: usize = 4; @@ -531,8 +537,46 @@ pub mod perf { //pubsub const MAX_PUBSUB: usize = 3; const MAX_NODES: usize = 20; - static PUBLISH: Mutex> = Mutex::new(None); - static SUBSCRIBE: Mutex> = Mutex::new(None); + #[derive(Clone)] + struct PubSubTable { + timestamps: [[[u64; MAX_NODES]; MAX_PUBSUB]; MAX_LOGS], + used_indices: Vec, + } + + impl Default for PubSubTable { + fn default() -> Self { + Self { + timestamps: [[[0; MAX_NODES]; MAX_PUBSUB]; MAX_LOGS], + used_indices: Vec::new(), + } + } + } + + impl PubSubTable { + #[inline(always)] + fn flat_index(index: usize, pub_id: usize, node_id: usize) -> usize { + (index * MAX_PUBSUB * MAX_NODES) + (pub_id * MAX_NODES) + node_id + } + + #[inline(always)] + fn decode_flat_index(flat_index: usize) -> (usize, usize, usize) { + let per_log = MAX_PUBSUB * MAX_NODES; + let index = flat_index / per_log; + let rem = flat_index % per_log; + let pub_id = rem / MAX_NODES; + let node_id = rem % MAX_NODES; + (index, pub_id, node_id) + } + + #[inline(always)] + fn mark_used(&mut self, index: usize, pub_id: usize, node_id: usize) { + self.used_indices + .push(Self::flat_index(index, pub_id, node_id)); + } + } + + static PUBLISH: Mutex>> = Mutex::new(None); + static SUBSCRIBE: Mutex>> = Mutex::new(None); pub fn increment_period_count(dag_id: usize) { assert!(dag_id < MAX_DAGS, "DAG ID out of bounds"); @@ -550,7 +594,7 @@ pub mod perf { let mut node = MCSNode::new(); let mut recorder_opt = SEND_OUTER_TIMESTAMP.lock(&mut node); - let recorder = recorder_opt.get_or_insert_with(|| [[0; MAX_DAGS]; MAX_LOGS]); + let recorder = recorder_opt.get_or_insert_with(|| Box::new([[0; MAX_DAGS]; MAX_LOGS])); if recorder[index][dag_id as usize] == 0 { recorder[index][dag_id as usize] = new_timestamp; @@ -563,7 +607,7 @@ pub mod perf { let mut node = MCSNode::new(); let mut recorder_opt = RECV_OUTER_TIMESTAMP.lock(&mut node); - let recorder = recorder_opt.get_or_insert_with(|| [[0; MAX_DAGS]; MAX_LOGS]); + let recorder = recorder_opt.get_or_insert_with(|| Box::new([[0; MAX_DAGS]; MAX_LOGS])); if (dag_id as usize) < recorder[0].len() { recorder[index][dag_id as usize] = new_timestamp; @@ -576,7 +620,7 @@ pub mod perf { let mut node = MCSNode::new(); let mut recorder_opt = ABSOLUTE_DEADLINE.lock(&mut node); - let recorder = recorder_opt.get_or_insert_with(|| [[0; MAX_DAGS]; MAX_LOGS]); + let recorder = recorder_opt.get_or_insert_with(|| Box::new([[0; MAX_DAGS]; MAX_LOGS])); if recorder[index][dag_id as usize] == 0 { recorder[index][dag_id as usize] = deadline; @@ -589,7 +633,7 @@ pub mod perf { let mut node = MCSNode::new(); let mut recorder_opt = RELATIVE_DEADLINE.lock(&mut node); - let recorder = recorder_opt.get_or_insert_with(|| [[0; MAX_DAGS]; MAX_LOGS]); + let recorder = recorder_opt.get_or_insert_with(|| Box::new([[0; MAX_DAGS]; MAX_LOGS])); if recorder[index][dag_id as usize] == 0 { recorder[index][dag_id as usize] = deadline; @@ -600,13 +644,21 @@ pub mod perf { assert!(index < MAX_LOGS, "Timestamp index out of bounds"); assert!((pub_id as usize) < MAX_PUBSUB, "Publish ID out of bounds"); + let node_id_usize = node_id as usize; + if node_id_usize >= MAX_NODES { + log::warn!("Publish node ID out of bounds: {} (max {})", node_id_usize, MAX_NODES); + return; + } + let mut node = MCSNode::new(); let mut recorder_opt = PUBLISH.lock(&mut node); - let recorder = recorder_opt.get_or_insert_with(|| [[[0; MAX_NODES]; MAX_PUBSUB]; MAX_LOGS]); + let recorder = recorder_opt.get_or_insert_with(|| Box::new(PubSubTable::default())); + let pub_id = pub_id as usize; - if recorder[index][pub_id as usize][node_id as usize] == 0 { - recorder[index][pub_id as usize][node_id as usize] = new_timestamp; + if recorder.timestamps[index][pub_id][node_id_usize] == 0 { + recorder.timestamps[index][pub_id][node_id_usize] = new_timestamp; + recorder.mark_used(index, pub_id, node_id_usize); } } @@ -614,13 +666,21 @@ pub mod perf { assert!(index < MAX_LOGS, "Timestamp index out of bounds"); assert!((sub_id as usize) < MAX_PUBSUB, "Subscribe ID out of bounds"); + let node_id_usize = node_id as usize; + if node_id_usize >= MAX_NODES { + log::warn!("Subscribe node ID out of bounds: {} (max {})", node_id_usize, MAX_NODES); + return; + } + let mut node = MCSNode::new(); let mut recorder_opt = SUBSCRIBE.lock(&mut node); - let recorder = recorder_opt.get_or_insert_with(|| [[[0; MAX_NODES]; MAX_PUBSUB]; MAX_LOGS]); + let recorder = recorder_opt.get_or_insert_with(|| Box::new(PubSubTable::default())); + let sub_id = sub_id as usize; - if recorder[index][sub_id as usize][node_id as usize] == 0 { - recorder[index][sub_id as usize][node_id as usize] = new_timestamp; + if recorder.timestamps[index][sub_id][node_id_usize] == 0 { + recorder.timestamps[index][sub_id][node_id_usize] = new_timestamp; + recorder.mark_used(index, sub_id, node_id_usize); } } @@ -652,10 +712,22 @@ pub mod perf { for i in 0..MAX_LOGS { for j in 1..MAX_DAGS { - let pre_send_outer = send_outer_opt.as_ref().map_or(0, |arr| arr[i][j]); - let fin_recv_outer = recv_outer_opt.as_ref().map_or(0, |arr| arr[i][j]); - let absolute_deadline = absolute_deadline_opt.as_ref().map_or(0, |arr| arr[i][j]); - let relative_deadline = relative_deadline_opt.as_ref().map_or(0, |arr| arr[i][j]); + let pre_send_outer = match &*send_outer_opt { + Some(arr) => arr[i][j], + None => 0, + }; + let fin_recv_outer = match &*recv_outer_opt { + Some(arr) => arr[i][j], + None => 0, + }; + let absolute_deadline = match &*absolute_deadline_opt { + Some(arr) => arr[i][j], + None => 0, + }; + let relative_deadline = match &*relative_deadline_opt { + Some(arr) => arr[i][j], + None => 0, + }; if pre_send_outer != 0 || fin_recv_outer != 0 @@ -700,6 +772,16 @@ pub mod perf { let publish_opt = PUBLISH.lock(&mut node1); let subscribe_opt = SUBSCRIBE.lock(&mut node2); + let mut indices = Vec::new(); + if let Some(publish) = publish_opt.as_ref() { + indices.extend_from_slice(&publish.used_indices); + } + if let Some(subscribe) = subscribe_opt.as_ref() { + indices.extend_from_slice(&subscribe.used_indices); + } + indices.sort_unstable(); + indices.dedup(); + log::info!("--- Pub/Sub Timestamp Summary (in nanoseconds) ---"); log::info!( "{: ^5} | {: ^10} | {: ^7} | {: ^14} | {: ^14}", @@ -710,31 +792,39 @@ pub mod perf { "Subscribe Time" ); log::info!("-----|------------|---------|----------------|----------------"); - for i in 0..MAX_LOGS { - for j in 0..MAX_PUBSUB { - for k in 0..MAX_NODES { - let publish_time = publish_opt.as_ref().map_or(0, |arr| arr[i][j][k]); - let subscribe_time = subscribe_opt.as_ref().map_or(0, |arr| arr[i][j][k]); - - if publish_time != 0 || subscribe_time != 0 { - let format_ts = |ts: u64| -> String { - if ts == 0 { - "-".to_string() - } else { - ts.to_string() - } - }; - - log::info!( - "{: >5} | {: >10} | {: >7} | {: >14} | {: >14}", - i, - j, - k, - format_ts(publish_time), - format_ts(subscribe_time), - ); + for flat_index in indices { + let (i, j, k) = PubSubTable::decode_flat_index(flat_index); + // Skip if decoded indices are out of bounds + if i >= MAX_LOGS || j >= MAX_PUBSUB || k >= MAX_NODES { + log::warn!("Decoded index out of bounds: ({}, {}, {})", i, j, k); + continue; + } + let publish_time = match &*publish_opt { + Some(table) => table.timestamps[i][j][k], + None => 0, + }; + let subscribe_time = match &*subscribe_opt { + Some(table) => table.timestamps[i][j][k], + None => 0, + }; + + if publish_time != 0 || subscribe_time != 0 { + let format_ts = |ts: u64| -> String { + if ts == 0 { + "-".to_string() + } else { + ts.to_string() } - } + }; + + log::info!( + "{: >5} | {: >10} | {: >7} | {: >14} | {: >14}", + i, + j, + k, + format_ts(publish_time), + format_ts(subscribe_time), + ); } } log::info!("--------------------------------------------------------------"); diff --git a/awkernel_async_lib/src/time_interval.rs b/awkernel_async_lib/src/time_interval.rs index b583cf516..bb947b048 100644 --- a/awkernel_async_lib/src/time_interval.rs +++ b/awkernel_async_lib/src/time_interval.rs @@ -107,6 +107,7 @@ pub fn interval_at(start: Time, period: Duration, _dag_id: u32) -> Interval { #[cfg(feature = "need-get-period")] { let index = get_period_count(_dag_id.clone() as usize) as usize; + // [start] cycle deviation index == 0 (basis of cycle deviation) update_pre_send_outer_timestamp_at( index, start.uptime().as_nanos() as u64, From efc54b69ea1ead58e78a9a37cf00ba03429e6486 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Sat, 18 Apr 2026 01:17:46 +0900 Subject: [PATCH 40/60] fix: apply cargo fmt 5 Signed-off-by: nokosaaan --- awkernel_async_lib/src/dag.rs | 6 ++---- awkernel_async_lib/src/pubsub.rs | 4 +--- awkernel_async_lib/src/task.rs | 26 +++++++++++++++----------- 3 files changed, 18 insertions(+), 18 deletions(-) diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index 396fa656b..6066392d7 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -1061,10 +1061,8 @@ where loop { #[cfg(feature = "need-get-period")] { - let (args, count_st): ( - ::Item, - u32, - ) = subscribers.recv_all_with_period().await; + let (args, count_st): (::Item, u32) = + subscribers.recv_all_with_period().await; // [end] pubsub communication latency let end = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index 57fbd2946..dee13893c 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -787,9 +787,7 @@ pub trait MultipleReceiver { fn recv_all(&self) -> Pin + Send + '_>>; #[cfg(feature = "need-get-period")] - fn recv_all_with_period( - &self, - ) -> Pin + Send + '_>>; + fn recv_all_with_period(&self) -> Pin + Send + '_>>; } pub trait MultipleSender { diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index 363202a70..5fb9e72bb 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -517,18 +517,14 @@ pub mod perf { static mut IDLE_COUNT: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; static mut PERF_COUNT: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; - use awkernel_lib::sync::{mcs::MCSNode, mutex::Mutex}; use alloc::vec::Vec; + use awkernel_lib::sync::{mcs::MCSNode, mutex::Mutex}; const MAX_LOGS: usize = 8192; - static SEND_OUTER_TIMESTAMP: Mutex>> = - Mutex::new(None); - static RECV_OUTER_TIMESTAMP: Mutex>> = - Mutex::new(None); - static ABSOLUTE_DEADLINE: Mutex>> = - Mutex::new(None); - static RELATIVE_DEADLINE: Mutex>> = - Mutex::new(None); + static SEND_OUTER_TIMESTAMP: Mutex>> = Mutex::new(None); + static RECV_OUTER_TIMESTAMP: Mutex>> = Mutex::new(None); + static ABSOLUTE_DEADLINE: Mutex>> = Mutex::new(None); + static RELATIVE_DEADLINE: Mutex>> = Mutex::new(None); //DAG+1 const MAX_DAGS: usize = 4; @@ -646,7 +642,11 @@ pub mod perf { let node_id_usize = node_id as usize; if node_id_usize >= MAX_NODES { - log::warn!("Publish node ID out of bounds: {} (max {})", node_id_usize, MAX_NODES); + log::warn!( + "Publish node ID out of bounds: {} (max {})", + node_id_usize, + MAX_NODES + ); return; } @@ -668,7 +668,11 @@ pub mod perf { let node_id_usize = node_id as usize; if node_id_usize >= MAX_NODES { - log::warn!("Subscribe node ID out of bounds: {} (max {})", node_id_usize, MAX_NODES); + log::warn!( + "Subscribe node ID out of bounds: {} (max {})", + node_id_usize, + MAX_NODES + ); return; } From 64e87b63c00d5f3bb791c1f834c8f088f7906103 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Sat, 18 Apr 2026 01:20:26 +0900 Subject: [PATCH 41/60] fix: apply copilot suggestion in kernel/main.rs Signed-off-by: nokosaaan --- kernel/src/main.rs | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/kernel/src/main.rs b/kernel/src/main.rs index 15daa23d4..ee7dc19dc 100644 --- a/kernel/src/main.rs +++ b/kernel/src/main.rs @@ -74,15 +74,14 @@ fn main(kernel_info: KernelInfo) { // Enable awkernel_lib::cpu::sleep_cpu() and awkernel_lib::cpu::wakeup_cpu(). unsafe { awkernel_lib::cpu::init_sleep() }; + #[cfg(feature = "need-get-period")] let mut last_print = awkernel_lib::time::Time::now(); loop { + #[cfg(feature = "need-get-period")] if last_print.elapsed().as_secs() >= 30 { - #[cfg(feature = "need-get-period")] - { - awkernel_async_lib::task::perf::print_timestamp_table(); - // awkernel_async_lib::task::perf::print_pubsub_table(); - } + awkernel_async_lib::task::perf::print_timestamp_table(); + // awkernel_async_lib::task::perf::print_pubsub_table(); last_print = awkernel_lib::time::Time::now(); } From 12fb54a4a87dc904b8f9de7ae7a6d94db72d5a54 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Sat, 18 Apr 2026 01:39:41 +0900 Subject: [PATCH 42/60] fix: delete unnecessary declare and add dependics to need Signed-off-by: nokosaaan --- awkernel_async_lib/Cargo.toml | 2 +- awkernel_async_lib/src/dag.rs | 3 --- kernel/Cargo.toml | 2 +- 3 files changed, 2 insertions(+), 5 deletions(-) diff --git a/awkernel_async_lib/Cargo.toml b/awkernel_async_lib/Cargo.toml index 961ed2ad7..ac3688d55 100644 --- a/awkernel_async_lib/Cargo.toml +++ b/awkernel_async_lib/Cargo.toml @@ -45,4 +45,4 @@ no_preempt = [] spinlock = ["awkernel_lib/spinlock"] clippy = [] perf = [] -need-get-period = [] +need-get-period = ["perf"] diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index 6066392d7..642d581ee 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -922,8 +922,6 @@ where Ret: VectorToPublishers, Ret::Publishers: Send, Args::Subscribers: Send, - ::Item: TupleSize, - ::Item: TupleSize, { let future = async move { let publishers = ::create_publishers( @@ -1052,7 +1050,6 @@ where F: Fn(::Item) + Send + 'static, Args: VectorToSubscribers, Args::Subscribers: Send, - ::Item: TupleSize, { let future = async move { let subscribers: ::Subscribers = diff --git a/kernel/Cargo.toml b/kernel/Cargo.toml index 9d0b86276..efcf539e0 100644 --- a/kernel/Cargo.toml +++ b/kernel/Cargo.toml @@ -78,7 +78,7 @@ optional = true [features] default = ["x86"] perf = ["awkernel_async_lib/perf", "userland/perf"] -need-get-period = ["awkernel_async_lib/need-get-period"] +need-get-period = ["perf", "awkernel_async_lib/need-get-period"] no_std_unwinding = ["dep:unwinding"] debug = ["dep:gimli", "dep:addr2line"] x86 = [ From 0e3156a906d0b8ecd6e78e5f6ce4806645772210 Mon Sep 17 00:00:00 2001 From: "copilot-swe-agent[bot]" <198982749+Copilot@users.noreply.github.com> Date: Fri, 17 Apr 2026 17:00:55 +0000 Subject: [PATCH 43/60] fix(perf): make period-based recording resilient to dag/index overflow Agent-Logs-Url: https://github.com/tier4/awkernel/sessions/27c4a5cf-6c1d-4fd2-a11a-0c3b66b8f566 Co-authored-by: nokosaaan <106376734+nokosaaan@users.noreply.github.com> --- awkernel_async_lib/src/pubsub.rs | 3 +- awkernel_async_lib/src/task.rs | 71 +++++++++++++++++++++++--------- 2 files changed, 54 insertions(+), 20 deletions(-) diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index dee13893c..9698ee14d 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -411,7 +411,8 @@ where // [start] pubsub communication latency let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; publish_timestamp_at(index, start, pub_id, node_id); - let sender = Sender::new(self, data).with_period(index as u32); + let period = u32::try_from(index).unwrap_or(u32::MAX); + let sender = Sender::new(self, data).with_period(period); sender.await; r#yield().await; } diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index 5fb9e72bb..8502a4ea4 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -574,70 +574,103 @@ pub mod perf { static PUBLISH: Mutex>> = Mutex::new(None); static SUBSCRIBE: Mutex>> = Mutex::new(None); + #[inline(always)] + fn normalize_log_index(index: usize) -> usize { + index % MAX_LOGS + } + + #[inline(always)] + fn dag_index(dag_id: u32) -> Option { + let dag_idx = dag_id as usize; + if dag_idx < MAX_DAGS { + Some(dag_idx) + } else { + log::warn!("DAG ID out of bounds: {} (max {})", dag_idx, MAX_DAGS - 1); + None + } + } + pub fn increment_period_count(dag_id: usize) { - assert!(dag_id < MAX_DAGS, "DAG ID out of bounds"); - PERIOD_COUNT[dag_id].fetch_add(1, Ordering::Relaxed); + if dag_id < MAX_DAGS { + PERIOD_COUNT[dag_id].fetch_add(1, Ordering::Relaxed); + } else { + log::warn!("DAG ID out of bounds: {} (max {})", dag_id, MAX_DAGS - 1); + } } pub fn get_period_count(dag_id: usize) -> u32 { - assert!(dag_id < MAX_DAGS, "DAG ID out of bounds"); - PERIOD_COUNT[dag_id].load(Ordering::Relaxed) + if dag_id < MAX_DAGS { + PERIOD_COUNT[dag_id].load(Ordering::Relaxed) + } else { + log::warn!("DAG ID out of bounds: {} (max {})", dag_id, MAX_DAGS - 1); + 0 + } } pub fn update_pre_send_outer_timestamp_at(index: usize, new_timestamp: u64, dag_id: u32) { - assert!(index < MAX_LOGS, "Timestamp index out of bounds"); + let Some(dag_idx) = dag_index(dag_id) else { + return; + }; + let index = normalize_log_index(index); let mut node = MCSNode::new(); let mut recorder_opt = SEND_OUTER_TIMESTAMP.lock(&mut node); let recorder = recorder_opt.get_or_insert_with(|| Box::new([[0; MAX_DAGS]; MAX_LOGS])); - if recorder[index][dag_id as usize] == 0 { - recorder[index][dag_id as usize] = new_timestamp; + if recorder[index][dag_idx] == 0 { + recorder[index][dag_idx] = new_timestamp; } } pub fn update_fin_recv_outer_timestamp_at(index: usize, new_timestamp: u64, dag_id: u32) { - assert!(index < MAX_LOGS, "Timestamp index out of bounds"); + let Some(dag_idx) = dag_index(dag_id) else { + return; + }; + let index = normalize_log_index(index); let mut node = MCSNode::new(); let mut recorder_opt = RECV_OUTER_TIMESTAMP.lock(&mut node); let recorder = recorder_opt.get_or_insert_with(|| Box::new([[0; MAX_DAGS]; MAX_LOGS])); - if (dag_id as usize) < recorder[0].len() { - recorder[index][dag_id as usize] = new_timestamp; - } + recorder[index][dag_idx] = new_timestamp; } pub fn update_absolute_deadline_timestamp_at(index: usize, deadline: u64, dag_id: u32) { - assert!(index < MAX_LOGS, "Timestamp index out of bounds"); + let Some(dag_idx) = dag_index(dag_id) else { + return; + }; + let index = normalize_log_index(index); let mut node = MCSNode::new(); let mut recorder_opt = ABSOLUTE_DEADLINE.lock(&mut node); let recorder = recorder_opt.get_or_insert_with(|| Box::new([[0; MAX_DAGS]; MAX_LOGS])); - if recorder[index][dag_id as usize] == 0 { - recorder[index][dag_id as usize] = deadline; + if recorder[index][dag_idx] == 0 { + recorder[index][dag_idx] = deadline; } } pub fn update_relative_deadline_timestamp_at(index: usize, deadline: u64, dag_id: u32) { - assert!(index < MAX_LOGS, "Timestamp index out of bounds"); + let Some(dag_idx) = dag_index(dag_id) else { + return; + }; + let index = normalize_log_index(index); let mut node = MCSNode::new(); let mut recorder_opt = RELATIVE_DEADLINE.lock(&mut node); let recorder = recorder_opt.get_or_insert_with(|| Box::new([[0; MAX_DAGS]; MAX_LOGS])); - if recorder[index][dag_id as usize] == 0 { - recorder[index][dag_id as usize] = deadline; + if recorder[index][dag_idx] == 0 { + recorder[index][dag_idx] = deadline; } } pub fn publish_timestamp_at(index: usize, new_timestamp: u64, pub_id: u32, node_id: u32) { - assert!(index < MAX_LOGS, "Timestamp index out of bounds"); + let index = normalize_log_index(index); assert!((pub_id as usize) < MAX_PUBSUB, "Publish ID out of bounds"); let node_id_usize = node_id as usize; @@ -663,7 +696,7 @@ pub mod perf { } pub fn subscribe_timestamp_at(index: usize, new_timestamp: u64, sub_id: u32, node_id: u32) { - assert!(index < MAX_LOGS, "Timestamp index out of bounds"); + let index = normalize_log_index(index); assert!((sub_id as usize) < MAX_PUBSUB, "Subscribe ID out of bounds"); let node_id_usize = node_id as usize; From bf7ba7b19d83ea543a8d3971838be53efab5e5e3 Mon Sep 17 00:00:00 2001 From: "copilot-swe-agent[bot]" <198982749+Copilot@users.noreply.github.com> Date: Fri, 17 Apr 2026 17:04:28 +0000 Subject: [PATCH 44/60] fix(perf): warn when period metadata saturates Agent-Logs-Url: https://github.com/tier4/awkernel/sessions/27c4a5cf-6c1d-4fd2-a11a-0c3b66b8f566 Co-authored-by: nokosaaan <106376734+nokosaaan@users.noreply.github.com> --- awkernel_async_lib/src/pubsub.rs | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index 9698ee14d..790657700 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -411,7 +411,16 @@ where // [start] pubsub communication latency let start = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; publish_timestamp_at(index, start, pub_id, node_id); - let period = u32::try_from(index).unwrap_or(u32::MAX); + let period = match u32::try_from(index) { + Ok(period) => period, + Err(_) => { + log::warn!( + "Period index {} exceeds u32::MAX; saturating period metadata", + index + ); + u32::MAX + } + }; let sender = Sender::new(self, data).with_period(period); sender.await; r#yield().await; From 5ff88eb082ced889855f08ec5fbd30b2fc135c49 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Sat, 18 Apr 2026 06:02:40 +0900 Subject: [PATCH 45/60] fix: apply copilot suggestion 1 Signed-off-by: nokosaaan --- awkernel_async_lib/src/task.rs | 3 +++ 1 file changed, 3 insertions(+) diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index 8502a4ea4..bea7693b9 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -1065,6 +1065,9 @@ pub mod perf { // Normal task-specific handling update_time_and_state(PerfState::Interrupt); } + } else { + // Default handling if the current task cannot be resolved + update_time_and_state(PerfState::Interrupt); } } else { // Default handling if no task is running From 465f75e1e8dfffaf0938de368160155b1ad5a7e4 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Sat, 18 Apr 2026 06:04:03 +0900 Subject: [PATCH 46/60] fix: apply copilot suggestion 2 Signed-off-by: nokosaaan --- awkernel_async_lib/src/pubsub.rs | 3 --- 1 file changed, 3 deletions(-) diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index 790657700..492ebc447 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -803,7 +803,6 @@ pub trait MultipleReceiver { pub trait MultipleSender { type Item; - #[cfg(not(feature = "need-get-period"))] fn send_all(&self, item: Self::Item) -> Pin + Send + '_>>; #[cfg(feature = "need-get-period")] @@ -898,7 +897,6 @@ macro_rules! impl_async_receiver_for_tuple { impl MultipleSender for () { type Item = (); - #[cfg(not(feature = "need-get-period"))] fn send_all(&self, _item: Self::Item) -> Pin + Send + '_>> { Box::pin(async move{}) } @@ -946,7 +944,6 @@ macro_rules! impl_async_receiver_for_tuple { impl<$($T: Clone + Sync + Send + 'static),+> MultipleSender for ($(Publisher<$T>,)+) { type Item = ($($T,)+); - #[cfg(not(feature = "need-get-period"))] fn send_all(&self, item: Self::Item) -> Pin + Send + '_>> { let ($($idx,)+) = self; let ($($idx2,)+) = item; From 74b6d2770e0a99d8e0014ba342d2f66d78cb3075 Mon Sep 17 00:00:00 2001 From: nokosaaan <106376734+nokosaaan@users.noreply.github.com> Date: Sat, 18 Apr 2026 08:20:33 +0900 Subject: [PATCH 47/60] Update awkernel_async_lib/src/pubsub.rs Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> --- awkernel_async_lib/src/pubsub.rs | 67 ++++++++++++++++++++++++++++++++ 1 file changed, 67 insertions(+) diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index 492ebc447..406567f35 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -427,6 +427,73 @@ where } } +#[cfg(all(test, feature = "need-get-period"))] +mod need_get_period_tests { + use super::*; + use core::{ + future::Future, + pin::Pin, + task::{Context, Poll, RawWaker, RawWakerVTable, Waker}, + }; + + fn block_on(future: F) -> F::Output { + fn raw_waker() -> RawWaker { + fn clone(_: *const ()) -> RawWaker { + raw_waker() + } + fn wake(_: *const ()) {} + fn wake_by_ref(_: *const ()) {} + fn drop(_: *const ()) {} + + RawWaker::new( + core::ptr::null(), + &RawWakerVTable::new(clone, wake, wake_by_ref, drop), + ) + } + + let waker = unsafe { Waker::from_raw(raw_waker()) }; + let mut future = Box::pin(future); + + loop { + let mut context = Context::from_waker(&waker); + match Pin::as_mut(&mut future).poll(&mut context) { + Poll::Ready(output) => return output, + Poll::Pending => {} + } + } + } + + #[test] + fn send_with_meta_propagates_period_to_receiver() { + block_on(async { + let (publisher, subscriber) = create_pubsub::(Attribute::default()); + publisher.send_with_meta(42, 1, 7, 99).await; + + let (value, period) = subscriber.recv_with_period().await; + assert_eq!(value, 42); + assert_eq!(period, 7); + }); + } + + #[test] + fn tuple_recv_all_with_period_preserves_each_period() { + block_on(async { + let (publisher1, subscriber1) = create_pubsub::(Attribute::default()); + let (publisher2, subscriber2) = create_pubsub::(Attribute::default()); + + publisher1.send_with_meta(10, 11, 3, 21).await; + publisher2.send_with_meta(20, 12, 5, 22).await; + + let ((value1, period1), (value2, period2)) = + (subscriber1, subscriber2).recv_all_with_period().await; + + assert_eq!(value1, 10); + assert_eq!(period1, 3); + assert_eq!(value2, 20); + assert_eq!(period2, 5); + }); + } +} /// Create an anonymous publisher and an anonymous subscriber. /// This channel works as a channel of multiple producers and multiple consumers. /// From f8589f536cf8938135dc1886cd191a00c704ca2c Mon Sep 17 00:00:00 2001 From: nokosaaan <106376734+nokosaaan@users.noreply.github.com> Date: Sat, 18 Apr 2026 08:20:52 +0900 Subject: [PATCH 48/60] Update awkernel_async_lib/src/pubsub.rs Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> --- awkernel_async_lib/src/pubsub.rs | 18 +++++++++++++++--- 1 file changed, 15 insertions(+), 3 deletions(-) diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index 406567f35..aa18fafdd 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -997,13 +997,25 @@ macro_rules! impl_async_receiver_for_tuple { ) -> Pin + Send + '_>> { let ($($idx,)+) = self; Box::pin(async move { - let mut _period: u32 = 0; + let mut period: Option = None; $( let item = $idx.recv().await; - _period = item.index; + match period { + Some(expected) => { + assert!( + expected == item.index, + "recv_all_with_period received mismatched periods: expected {}, got {}", + expected, + item.index + ); + } + None => { + period = Some(item.index); + } + } let $idx2 = item.data; )+ - (($($idx2,)+), _period) + (($($idx2,)+), period.expect("recv_all_with_period requires at least one subscriber")) }) } } From 160c9eb95b6150943e87408a705af61d226b3e1f Mon Sep 17 00:00:00 2001 From: "copilot-swe-agent[bot]" <198982749+Copilot@users.noreply.github.com> Date: Fri, 17 Apr 2026 23:22:48 +0000 Subject: [PATCH 49/60] fix(perf): snapshot and cap timestamp summary output Agent-Logs-Url: https://github.com/tier4/awkernel/sessions/b953688d-3187-46b4-8726-abddc38082fc Co-authored-by: nokosaaan <106376734+nokosaaan@users.noreply.github.com> --- awkernel_async_lib/src/task.rs | 104 +++++++++++++++++++++------------ 1 file changed, 66 insertions(+), 38 deletions(-) diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index bea7693b9..0c2b85abd 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -727,27 +727,16 @@ pub mod perf { let mut node2 = MCSNode::new(); let mut node3 = MCSNode::new(); let mut node4 = MCSNode::new(); + const MAX_ROWS_TO_PRINT: usize = 256; let send_outer_opt = SEND_OUTER_TIMESTAMP.lock(&mut node1); let recv_outer_opt = RECV_OUTER_TIMESTAMP.lock(&mut node2); let absolute_deadline_opt = ABSOLUTE_DEADLINE.lock(&mut node3); let relative_deadline_opt = RELATIVE_DEADLINE.lock(&mut node4); - log::info!("--- Timestamp Summary (in nanoseconds) ---"); - log::info!( - "{: ^5} | {: ^5} | {: ^14} | {: ^14} | {: ^14} | {: ^14} | {: ^14}", - "Index", - "DAG-ID", - "Send-Outer", - "Recv-Outer", - "Latency", - "Absolute Deadline", - "Relative Deadline" - ); - - log::info!("-----|--------|----------------|----------------|----------------|--------------------|--------------------|--------------------|--------------------"); - - for i in 0..MAX_LOGS { + let mut rows = Vec::new(); + let mut truncated = false; + 'collect_rows: for i in 0..MAX_LOGS { for j in 1..MAX_DAGS { let pre_send_outer = match &*send_outer_opt { Some(arr) => arr[i][j], @@ -771,33 +760,72 @@ pub mod perf { || absolute_deadline != 0 || relative_deadline != 0 { - let format_ts = |ts: u64| -> String { - if ts == 0 { - "-".to_string() - } else { - ts.to_string() - } - }; - - let latency_str = if pre_send_outer != 0 && fin_recv_outer != 0 { - fin_recv_outer.saturating_sub(pre_send_outer).to_string() - } else { - "-".to_string() - }; - - log::info!( - "{: >5} | {: >5} | {: >14} | {: >14} | {: >14} | {: >20} | {: >20}", + if rows.len() >= MAX_ROWS_TO_PRINT { + truncated = true; + break 'collect_rows; + } + rows.push(( i, - format_ts(j as u64), - format_ts(pre_send_outer), - format_ts(fin_recv_outer), - latency_str, - format_ts(absolute_deadline), - format_ts(relative_deadline), - ); + j, + pre_send_outer, + fin_recv_outer, + absolute_deadline, + relative_deadline, + )); } } } + drop(relative_deadline_opt); + drop(absolute_deadline_opt); + drop(recv_outer_opt); + drop(send_outer_opt); + + log::info!("--- Timestamp Summary (in nanoseconds) ---"); + log::info!( + "{: ^5} | {: ^5} | {: ^14} | {: ^14} | {: ^14} | {: ^14} | {: ^14}", + "Index", + "DAG-ID", + "Send-Outer", + "Recv-Outer", + "Latency", + "Absolute Deadline", + "Relative Deadline" + ); + + log::info!("-----|--------|----------------|----------------|----------------|--------------------|--------------------|--------------------|--------------------"); + + for (i, j, pre_send_outer, fin_recv_outer, absolute_deadline, relative_deadline) in rows { + let format_ts = |ts: u64| -> String { + if ts == 0 { + "-".to_string() + } else { + ts.to_string() + } + }; + + let latency_str = if pre_send_outer != 0 && fin_recv_outer != 0 { + fin_recv_outer.saturating_sub(pre_send_outer).to_string() + } else { + "-".to_string() + }; + + log::info!( + "{: >5} | {: >5} | {: >14} | {: >14} | {: >14} | {: >20} | {: >20}", + i, + format_ts(j as u64), + format_ts(pre_send_outer), + format_ts(fin_recv_outer), + latency_str, + format_ts(absolute_deadline), + format_ts(relative_deadline), + ); + } + if truncated { + log::warn!( + "Timestamp Summary truncated to {} rows; call print_timestamp_table() again to continue inspection", + MAX_ROWS_TO_PRINT + ); + } log::info!("----------------------------------------------------------"); } From 2c08c1c2b43479a5d75996d5dc9af9eb27bfae53 Mon Sep 17 00:00:00 2001 From: nokosaaan <106376734+nokosaaan@users.noreply.github.com> Date: Sat, 18 Apr 2026 08:28:18 +0900 Subject: [PATCH 50/60] Update awkernel_async_lib/src/task.rs Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> --- awkernel_async_lib/src/task.rs | 34 ++++++++++++++++++++++++++-------- 1 file changed, 26 insertions(+), 8 deletions(-) diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index 0c2b85abd..daf37d904 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -517,19 +517,37 @@ pub mod perf { static mut IDLE_COUNT: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; static mut PERF_COUNT: [u64; NUM_MAX_CPU] = [0; NUM_MAX_CPU]; - use alloc::vec::Vec; + use alloc::{collections::BTreeMap, vec::Vec}; use awkernel_lib::sync::{mcs::MCSNode, mutex::Mutex}; const MAX_LOGS: usize = 8192; - static SEND_OUTER_TIMESTAMP: Mutex>> = Mutex::new(None); - static RECV_OUTER_TIMESTAMP: Mutex>> = Mutex::new(None); - static ABSOLUTE_DEADLINE: Mutex>> = Mutex::new(None); - static RELATIVE_DEADLINE: Mutex>> = Mutex::new(None); + type DagTimestampMap = BTreeMap; + type DagTimestampTable = [DagTimestampMap; MAX_LOGS]; - //DAG+1 - const MAX_DAGS: usize = 4; - pub static PERIOD_COUNT: [AtomicU32; MAX_DAGS] = array![_ => AtomicU32::new(0); MAX_DAGS]; + static SEND_OUTER_TIMESTAMP: Mutex>> = Mutex::new(None); + static RECV_OUTER_TIMESTAMP: Mutex>> = Mutex::new(None); + static ABSOLUTE_DEADLINE: Mutex>> = Mutex::new(None); + static RELATIVE_DEADLINE: Mutex>> = Mutex::new(None); + pub static PERIOD_COUNT: Mutex> = Mutex::new(BTreeMap::new()); + + pub fn get_period_count(dag_id: u32) -> u32 { + let mut node = MCSNode::new(); + let period_count = PERIOD_COUNT.lock(&mut node); + period_count + .get(&dag_id) + .map(|count| count.load(core::sync::atomic::Ordering::Relaxed)) + .unwrap_or(0) + } + + pub fn increment_period_count(dag_id: u32) -> u32 { + let mut node = MCSNode::new(); + let mut period_count = PERIOD_COUNT.lock(&mut node); + let count = period_count + .entry(dag_id) + .or_insert_with(|| AtomicU32::new(0)); + count.fetch_add(1, core::sync::atomic::Ordering::Relaxed) + 1 + } //pubsub const MAX_PUBSUB: usize = 3; const MAX_NODES: usize = 20; From 696a2729c4bd3e2d409f00f126725a425ab60e91 Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Mon, 20 Apr 2026 02:04:12 +0900 Subject: [PATCH 51/60] fix: apply cargo fmt 6 Signed-off-by: nokosaaan --- awkernel_async_lib/src/task.rs | 104 ++++++++++++++------------------- 1 file changed, 43 insertions(+), 61 deletions(-) diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index daf37d904..d5495f851 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -457,10 +457,9 @@ pub mod perf { use crate::task::{self}; use alloc::boxed::Box; use alloc::string::{String, ToString}; - use array_macro::array; use awkernel_lib::cpu::NUM_MAX_CPU; use core::ptr::{read_volatile, write_volatile}; - use core::sync::atomic::{AtomicU32, Ordering}; + use core::sync::atomic::AtomicU32; #[derive(Debug, Clone, PartialEq, Eq)] #[repr(u8)] @@ -597,93 +596,57 @@ pub mod perf { index % MAX_LOGS } - #[inline(always)] - fn dag_index(dag_id: u32) -> Option { - let dag_idx = dag_id as usize; - if dag_idx < MAX_DAGS { - Some(dag_idx) - } else { - log::warn!("DAG ID out of bounds: {} (max {})", dag_idx, MAX_DAGS - 1); - None - } - } - - pub fn increment_period_count(dag_id: usize) { - if dag_id < MAX_DAGS { - PERIOD_COUNT[dag_id].fetch_add(1, Ordering::Relaxed); - } else { - log::warn!("DAG ID out of bounds: {} (max {})", dag_id, MAX_DAGS - 1); - } - } - - pub fn get_period_count(dag_id: usize) -> u32 { - if dag_id < MAX_DAGS { - PERIOD_COUNT[dag_id].load(Ordering::Relaxed) - } else { - log::warn!("DAG ID out of bounds: {} (max {})", dag_id, MAX_DAGS - 1); - 0 - } - } - pub fn update_pre_send_outer_timestamp_at(index: usize, new_timestamp: u64, dag_id: u32) { - let Some(dag_idx) = dag_index(dag_id) else { - return; - }; let index = normalize_log_index(index); let mut node = MCSNode::new(); let mut recorder_opt = SEND_OUTER_TIMESTAMP.lock(&mut node); - let recorder = recorder_opt.get_or_insert_with(|| Box::new([[0; MAX_DAGS]; MAX_LOGS])); + let recorder = + recorder_opt.get_or_insert_with(|| Box::new(core::array::from_fn(|_| BTreeMap::new()))); - if recorder[index][dag_idx] == 0 { - recorder[index][dag_idx] = new_timestamp; + if recorder[index].get(&dag_id).copied().unwrap_or(0) == 0 { + recorder[index].insert(dag_id, new_timestamp); } } pub fn update_fin_recv_outer_timestamp_at(index: usize, new_timestamp: u64, dag_id: u32) { - let Some(dag_idx) = dag_index(dag_id) else { - return; - }; let index = normalize_log_index(index); let mut node = MCSNode::new(); let mut recorder_opt = RECV_OUTER_TIMESTAMP.lock(&mut node); - let recorder = recorder_opt.get_or_insert_with(|| Box::new([[0; MAX_DAGS]; MAX_LOGS])); + let recorder = + recorder_opt.get_or_insert_with(|| Box::new(core::array::from_fn(|_| BTreeMap::new()))); - recorder[index][dag_idx] = new_timestamp; + recorder[index].insert(dag_id, new_timestamp); } pub fn update_absolute_deadline_timestamp_at(index: usize, deadline: u64, dag_id: u32) { - let Some(dag_idx) = dag_index(dag_id) else { - return; - }; let index = normalize_log_index(index); let mut node = MCSNode::new(); let mut recorder_opt = ABSOLUTE_DEADLINE.lock(&mut node); - let recorder = recorder_opt.get_or_insert_with(|| Box::new([[0; MAX_DAGS]; MAX_LOGS])); + let recorder = + recorder_opt.get_or_insert_with(|| Box::new(core::array::from_fn(|_| BTreeMap::new()))); - if recorder[index][dag_idx] == 0 { - recorder[index][dag_idx] = deadline; + if recorder[index].get(&dag_id).copied().unwrap_or(0) == 0 { + recorder[index].insert(dag_id, deadline); } } pub fn update_relative_deadline_timestamp_at(index: usize, deadline: u64, dag_id: u32) { - let Some(dag_idx) = dag_index(dag_id) else { - return; - }; let index = normalize_log_index(index); let mut node = MCSNode::new(); let mut recorder_opt = RELATIVE_DEADLINE.lock(&mut node); - let recorder = recorder_opt.get_or_insert_with(|| Box::new([[0; MAX_DAGS]; MAX_LOGS])); + let recorder = + recorder_opt.get_or_insert_with(|| Box::new(core::array::from_fn(|_| BTreeMap::new()))); - if recorder[index][dag_idx] == 0 { - recorder[index][dag_idx] = deadline; + if recorder[index].get(&dag_id).copied().unwrap_or(0) == 0 { + recorder[index].insert(dag_id, deadline); } } @@ -755,21 +718,38 @@ pub mod perf { let mut rows = Vec::new(); let mut truncated = false; 'collect_rows: for i in 0..MAX_LOGS { - for j in 1..MAX_DAGS { + let mut dag_ids = Vec::new(); + if let Some(arr) = &*send_outer_opt { + dag_ids.extend(arr[i].keys().copied()); + } + if let Some(arr) = &*recv_outer_opt { + dag_ids.extend(arr[i].keys().copied()); + } + if let Some(arr) = &*absolute_deadline_opt { + dag_ids.extend(arr[i].keys().copied()); + } + if let Some(arr) = &*relative_deadline_opt { + dag_ids.extend(arr[i].keys().copied()); + } + + dag_ids.sort_unstable(); + dag_ids.dedup(); + + for dag_id in dag_ids { let pre_send_outer = match &*send_outer_opt { - Some(arr) => arr[i][j], + Some(arr) => arr[i].get(&dag_id).copied().unwrap_or(0), None => 0, }; let fin_recv_outer = match &*recv_outer_opt { - Some(arr) => arr[i][j], + Some(arr) => arr[i].get(&dag_id).copied().unwrap_or(0), None => 0, }; let absolute_deadline = match &*absolute_deadline_opt { - Some(arr) => arr[i][j], + Some(arr) => arr[i].get(&dag_id).copied().unwrap_or(0), None => 0, }; let relative_deadline = match &*relative_deadline_opt { - Some(arr) => arr[i][j], + Some(arr) => arr[i].get(&dag_id).copied().unwrap_or(0), None => 0, }; @@ -784,7 +764,7 @@ pub mod perf { } rows.push(( i, - j, + dag_id, pre_send_outer, fin_recv_outer, absolute_deadline, @@ -812,7 +792,9 @@ pub mod perf { log::info!("-----|--------|----------------|----------------|----------------|--------------------|--------------------|--------------------|--------------------"); - for (i, j, pre_send_outer, fin_recv_outer, absolute_deadline, relative_deadline) in rows { + for (i, dag_id, pre_send_outer, fin_recv_outer, absolute_deadline, relative_deadline) in + rows + { let format_ts = |ts: u64| -> String { if ts == 0 { "-".to_string() @@ -830,7 +812,7 @@ pub mod perf { log::info!( "{: >5} | {: >5} | {: >14} | {: >14} | {: >14} | {: >20} | {: >20}", i, - format_ts(j as u64), + format_ts(dag_id as u64), format_ts(pre_send_outer), format_ts(fin_recv_outer), latency_str, From 6545debfd93adb8bf8f7cae92304824e12b9b628 Mon Sep 17 00:00:00 2001 From: "copilot-swe-agent[bot]" <198982749+Copilot@users.noreply.github.com> Date: Sun, 19 Apr 2026 17:22:07 +0000 Subject: [PATCH 52/60] fix(time_interval): pass dag_id as u32 to perf period API Agent-Logs-Url: https://github.com/tier4/awkernel/sessions/5c1de7d3-233c-477e-b87f-e0362c9c9090 Co-authored-by: nokosaaan <106376734+nokosaaan@users.noreply.github.com> --- awkernel_async_lib/src/time_interval.rs | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/awkernel_async_lib/src/time_interval.rs b/awkernel_async_lib/src/time_interval.rs index bb947b048..48bce689d 100644 --- a/awkernel_async_lib/src/time_interval.rs +++ b/awkernel_async_lib/src/time_interval.rs @@ -106,13 +106,9 @@ pub fn interval_at(start: Time, period: Duration, _dag_id: u32) -> Interval { assert!(!period.is_zero(), "`period` must be non-zero."); #[cfg(feature = "need-get-period")] { - let index = get_period_count(_dag_id.clone() as usize) as usize; + let index = get_period_count(_dag_id) as usize; // [start] cycle deviation index == 0 (basis of cycle deviation) - update_pre_send_outer_timestamp_at( - index, - start.uptime().as_nanos() as u64, - _dag_id.clone(), - ); + update_pre_send_outer_timestamp_at(index, start.uptime().as_nanos() as u64, _dag_id); } Interval { delay: None, From 1e8551907e2be3ac30e96b56bce4e8670ae3ac55 Mon Sep 17 00:00:00 2001 From: nokosaaan <106376734+nokosaaan@users.noreply.github.com> Date: Mon, 20 Apr 2026 12:25:23 +0900 Subject: [PATCH 53/60] Update awkernel_async_lib/src/pubsub.rs Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> --- awkernel_async_lib/src/pubsub.rs | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index aa18fafdd..d14b6b627 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -481,8 +481,8 @@ mod need_get_period_tests { let (publisher1, subscriber1) = create_pubsub::(Attribute::default()); let (publisher2, subscriber2) = create_pubsub::(Attribute::default()); - publisher1.send_with_meta(10, 11, 3, 21).await; - publisher2.send_with_meta(20, 12, 5, 22).await; + publisher1.send_with_meta(10, 1, 3, 21).await; + publisher2.send_with_meta(20, 2, 5, 22).await; let ((value1, period1), (value2, period2)) = (subscriber1, subscriber2).recv_all_with_period().await; From ef6f24eebccc8ce38907b5783732f6e4b3176a61 Mon Sep 17 00:00:00 2001 From: "copilot-swe-agent[bot]" <198982749+Copilot@users.noreply.github.com> Date: Mon, 20 Apr 2026 03:34:01 +0000 Subject: [PATCH 54/60] docs(time_interval): update interval example with dag_id argument Agent-Logs-Url: https://github.com/tier4/awkernel/sessions/0f0de978-4786-4b46-83e0-f647f3f1aa35 Co-authored-by: nokosaaan <106376734+nokosaaan@users.noreply.github.com> --- awkernel_async_lib/src/time_interval.rs | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/awkernel_async_lib/src/time_interval.rs b/awkernel_async_lib/src/time_interval.rs index 48bce689d..d3eb054af 100644 --- a/awkernel_async_lib/src/time_interval.rs +++ b/awkernel_async_lib/src/time_interval.rs @@ -88,7 +88,7 @@ pub enum MissedTickBehavior { /// use crate::time_interval::interval; /// use core::time::Duration; /// -/// let mut interval = interval(Duration::from_secs(1)); +/// let mut interval = interval(Duration::from_secs(1), 0); /// let mut ticks = 0; /// while ticks < 5 { /// let tick_time = interval.tick().await; From dd39f3e250f5eaf0632149c2223ad44ee445446e Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Mon, 20 Apr 2026 12:38:15 +0900 Subject: [PATCH 55/60] fix: change pubsub test case Signed-off-by: nokosaaan --- awkernel_async_lib/src/pubsub.rs | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index d14b6b627..d15ea5862 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -469,9 +469,9 @@ mod need_get_period_tests { let (publisher, subscriber) = create_pubsub::(Attribute::default()); publisher.send_with_meta(42, 1, 7, 99).await; - let (value, period) = subscriber.recv_with_period().await; - assert_eq!(value, 42); - assert_eq!(period, 7); + let received = subscriber.recv().await; + assert_eq!(received.data, 42); + assert_eq!(received.index, 7); }); } From 9b76322b70ebaafd836690aa11256667e454c95b Mon Sep 17 00:00:00 2001 From: nokosaaan <106376734+nokosaaan@users.noreply.github.com> Date: Mon, 20 Apr 2026 12:40:24 +0900 Subject: [PATCH 56/60] Update awkernel_async_lib/src/task.rs Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> --- awkernel_async_lib/src/task.rs | 3 +++ 1 file changed, 3 insertions(+) diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index d5495f851..7c56fe0d8 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -1155,6 +1155,9 @@ pub mod perf { // Normal task-specific handling update_time_and_state(PerfState::ContextSwitchMain); } + } else { + // Fallback handling if the current task ID cannot be resolved + update_time_and_state(PerfState::ContextSwitchMain); } } else { // Default handling if no task is running From 786398adbedfb3169323854d1ae5c5e3ed080547 Mon Sep 17 00:00:00 2001 From: nokosaaan <106376734+nokosaaan@users.noreply.github.com> Date: Mon, 20 Apr 2026 12:41:18 +0900 Subject: [PATCH 57/60] Update awkernel_async_lib/src/pubsub.rs Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> --- awkernel_async_lib/src/pubsub.rs | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/awkernel_async_lib/src/pubsub.rs b/awkernel_async_lib/src/pubsub.rs index d15ea5862..618015650 100644 --- a/awkernel_async_lib/src/pubsub.rs +++ b/awkernel_async_lib/src/pubsub.rs @@ -476,21 +476,20 @@ mod need_get_period_tests { } #[test] - fn tuple_recv_all_with_period_preserves_each_period() { + fn tuple_recv_all_with_period_returns_shared_period() { block_on(async { let (publisher1, subscriber1) = create_pubsub::(Attribute::default()); let (publisher2, subscriber2) = create_pubsub::(Attribute::default()); - publisher1.send_with_meta(10, 1, 3, 21).await; - publisher2.send_with_meta(20, 2, 5, 22).await; + publisher1.send_with_meta(10, 11, 3, 21).await; + publisher2.send_with_meta(20, 12, 3, 22).await; - let ((value1, period1), (value2, period2)) = + let ((value1, value2), period) = (subscriber1, subscriber2).recv_all_with_period().await; assert_eq!(value1, 10); - assert_eq!(period1, 3); assert_eq!(value2, 20); - assert_eq!(period2, 5); + assert_eq!(period, 3); }); } } From 50794a2e93fade809710bbd2bedd956162742aeb Mon Sep 17 00:00:00 2001 From: nokosaaan <106376734+nokosaaan@users.noreply.github.com> Date: Mon, 20 Apr 2026 12:57:59 +0900 Subject: [PATCH 58/60] Update awkernel_async_lib/src/dag.rs Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> --- awkernel_async_lib/src/dag.rs | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index 642d581ee..c248226dc 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -1001,21 +1001,21 @@ where loop { #[cfg(feature = "need-get-period")] { - let index = get_period_count(dag_info.dag_id.clone() as usize) as usize; + let index = get_period_count(dag_info.dag_id) as usize; if index != 0 { // [start] cycle deviation index >= 1 let release_time = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; update_pre_send_outer_timestamp_at( index, release_time, - dag_info.dag_id.clone(), + dag_info.dag_id, ); } let results = f(); publishers .send_all_with_meta(results, 0, index, dag_info.node_id) .await; - increment_period_count(dag_info.dag_id.clone() as usize); + increment_period_count(dag_info.dag_id); } #[cfg(not(feature = "need-get-period"))] From 95c8fef2757de4e347850930f4db0da869e4071f Mon Sep 17 00:00:00 2001 From: nokosaaan <106376734+nokosaaan@users.noreply.github.com> Date: Mon, 20 Apr 2026 12:58:23 +0900 Subject: [PATCH 59/60] Update awkernel_async_lib/src/task.rs Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> --- awkernel_async_lib/src/task.rs | 3 +++ 1 file changed, 3 insertions(+) diff --git a/awkernel_async_lib/src/task.rs b/awkernel_async_lib/src/task.rs index 7c56fe0d8..0cbbfcd0b 100644 --- a/awkernel_async_lib/src/task.rs +++ b/awkernel_async_lib/src/task.rs @@ -1134,6 +1134,9 @@ pub mod perf { // Normal task-specific handling update_time_and_state(PerfState::ContextSwitch); } + } else { + // Default handling if the current task cannot be resolved + update_time_and_state(PerfState::ContextSwitch); } } else { // Default handling if no task is running From c5ed577357719016fb7ca4283109e24eb024283a Mon Sep 17 00:00:00 2001 From: nokosaaan Date: Mon, 20 Apr 2026 14:08:34 +0900 Subject: [PATCH 60/60] fix: apply cargo fmt 7 Signed-off-by: nokosaaan --- awkernel_async_lib/src/dag.rs | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/awkernel_async_lib/src/dag.rs b/awkernel_async_lib/src/dag.rs index c248226dc..956933651 100644 --- a/awkernel_async_lib/src/dag.rs +++ b/awkernel_async_lib/src/dag.rs @@ -1005,11 +1005,7 @@ where if index != 0 { // [start] cycle deviation index >= 1 let release_time = awkernel_lib::time::Time::now().uptime().as_nanos() as u64; - update_pre_send_outer_timestamp_at( - index, - release_time, - dag_info.dag_id, - ); + update_pre_send_outer_timestamp_at(index, release_time, dag_info.dag_id); } let results = f(); publishers